Control Libraries 6.3.4
All Classes Namespaces Functions Variables Typedefs Enumerations Friends Pages
bind_geometry.cpp
1#include "state_representation_bindings.h"
2
3#include <state_representation/State.hpp>
4#include <state_representation/geometry/Shape.hpp>
5#include <state_representation/geometry/Ellipsoid.hpp>
6
7
8void shape(py::module_& m) {
9 py::class_<Shape, std::shared_ptr<Shape>, State> c(m, "Shape");
10
11 c.def(py::init<const StateType&>(), "Constructor with a type", "type"_a);
12 c.def(py::init<const StateType&, const std::string&, const std::string&>(), "Constructor with name but empty state.", "type"_a, "name"_a, "reference_frame"_a=std::string("world"));
13 c.def(py::init<const Shape&>(), "Copy constructor from another Shape.", "shape"_a);
14
15 c.def("get_center_state", &Shape::get_center_state, "Getter of the state.");
16 c.def("get_center_pose", &Shape::get_center_pose, "Getter of the pose from the state.");
17 c.def("get_center_position", &Shape::get_center_position, "Getter of the position from the state.");
18 c.def("get_center_orientation", &Shape::get_center_orientation, "Getter of the orientation from the state.");
19 c.def("get_center_twist", &Shape::get_center_twist, "Getter of the twist from the state.");
20
21 c.def("set_center_state", &Shape::set_center_state, "Setter of the state.");
22 c.def("set_center_pose", &Shape::set_center_pose, "Setter of the pose from the state.");
23 c.def("set_center_position", &Shape::set_center_position, "Setter of the position from the state.");
24 c.def("set_center_orientation", &Shape::set_center_orientation, "Setter of the orientation from the state.");
25
26 c.def("__copy__", [](const Shape &shape) {
27 return Shape(shape);
28 });
29 c.def("__deepcopy__", [](const Shape &shape, py::dict) {
30 return Shape(shape);
31 }, "memo"_a);
32 c.def("__repr__", [](const Shape& shape) {
33 std::stringstream buffer;
34 buffer << shape;
35 return buffer.str();
36 });
37}
38
39void ellipsoid(py::module_& m) {
40 py::class_<Ellipsoid, std::shared_ptr<Ellipsoid>, Shape> c(m, "Ellipsoid");
41
42 c.def(py::init(), "Empty constructor.");
43 c.def(py::init<const std::string&, const std::string&>(), "Constructor with name but empty state.", "name"_a, "reference_frame"_a=std::string("world"));
44 c.def(py::init<const Ellipsoid&>(), "Copy constructor from another Ellipsoid.", "ellipsoid"_a);
45
46 c.def("get_axis_lengths", &Ellipsoid::get_axis_lengths, "Getter of the axis lengths.");
47 c.def("get_axis_length", &Ellipsoid::get_axis_length, "Getter of the axis length in one direction.", "index"_a);
48 c.def("set_axis_lengths", py::overload_cast<const std::vector<double>&>(&Ellipsoid::set_axis_lengths), "Setter of the axis lengths.", "axis_lengths"_a);
49 c.def("set_axis_lengths", py::overload_cast<unsigned int, double>(&Ellipsoid::set_axis_lengths), "Setter of the axis length at given index.", "index"_a, "axis_length"_a);
50 c.def("get_rotation_angle", &Ellipsoid::get_rotation_angle, "Getter of the rotation angle.");
51 c.def("set_rotation_angle", &Ellipsoid::set_rotation_angle, "Setter of the rotation angle.", "rotation_angle"_a);
52
53 c.def("get_rotation", &Ellipsoid::get_rotation, "Getter of the rotation.");
54 c.def("sample_from_parameterization", &Ellipsoid::sample_from_parameterization, "Function to sample an obstacle from its parameterization.", "nb_samples"_a);
55 c.def("from_algebraic_equation", &Ellipsoid::from_algebraic_equation, "Compute an ellipsoid from its algebraic equation ax2 + bxy + cy2 + cx + ey + f.");
56 c.def("fit", &Ellipsoid::fit, "Fit an ellipsoid on a set of points.");
57
58 c.def("to_std_vector", &Ellipsoid::to_std_vector, "Convert the ellipse to an std vector representation of its parameter.");
59
60 c.def("__copy__", [](const Shape &shape) {
61 return Shape(shape);
62 });
63 c.def("__deepcopy__", [](const Shape &shape, py::dict) {
64 return Shape(shape);
65 }, "memo"_a);
66 c.def("__repr__", [](const Shape& shape) {
67 std::stringstream buffer;
68 buffer << shape;
69 return buffer.str();
70 });
71}
72
73void bind_geometry(py::module_& m) {
74 shape(m);
75 ellipsoid(m);
76}
void set_rotation_angle(double rotation_angle)
Setter of the rotation angle.
Definition: Ellipsoid.hpp:167
double get_axis_length(unsigned int index) const
Getter of the axis length in one direction.
Definition: Ellipsoid.hpp:149
static const Ellipsoid from_algebraic_equation(const std::string &name, const std::vector< double > &coefficients, const std::string &reference_frame="world")
Compute an ellipsoid from its algebraic equation ax2 + bxy + cy2 + cx + ey + f.
Definition: Ellipsoid.cpp:39
const std::list< CartesianPose > sample_from_parameterization(unsigned int nb_samples) const
Function to sample an obstacle from its parameterization.
Definition: Ellipsoid.cpp:18
void set_axis_lengths(const std::vector< double > &axis_lengths)
Setter of the axis lengths.
Definition: Ellipsoid.hpp:153
double get_rotation_angle() const
Getter of the rotation angle.
Definition: Ellipsoid.hpp:163
const std::vector< double > to_std_vector() const
Convert the ellipse to an std vector representation of its parameter.
Definition: Ellipsoid.hpp:172
const std::vector< double > & get_axis_lengths() const
Getter of the axis lengths.
Definition: Ellipsoid.hpp:145
static const Ellipsoid fit(const std::string &name, const std::list< CartesianPose > &points, const std::string &reference_frame="world", double noise_level=0.01)
Fit an ellipsoid on a set of points This method uses direct least square fitting from Fitzgibbon,...
Definition: Ellipsoid.cpp:85
void set_center_orientation(const Eigen::Quaterniond &orientation)
Setter of the pose.
Definition: Shape.hpp:157
void set_center_state(const CartesianState &state)
Setter of the state.
Definition: Shape.hpp:137
const Eigen::Vector3d get_center_position() const
Getter of the position from the state.
Definition: Shape.hpp:125
const CartesianState & get_center_state() const
Getter of the state.
Definition: Shape.hpp:117
const CartesianPose & get_center_pose() const
Getter of the pose from the state.
Definition: Shape.hpp:121
const Eigen::Quaterniond get_center_orientation() const
Getter of the orientation from the state.
Definition: Shape.hpp:129
void set_center_pose(const CartesianPose &pose)
Setter of the pose.
Definition: Shape.hpp:142
void set_center_position(const Eigen::Vector3d &position)
Setter of the position.
Definition: Shape.hpp:150
const CartesianTwist & get_center_twist() const
Getter of the twist from the state.
Definition: Shape.hpp:133
Abstract class to represent a state.
Definition: State.hpp:25