Control Libraries 7.4.0
Loading...
Searching...
No Matches
bind_geometry.cpp
1#include "state_representation_bindings.hpp"
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<>(), "Empty constructor");
12 c.def(py::init<const std::string&, const std::string&>(), "Constructor with name but empty state.", "name"_a, "reference_frame"_a=std::string("world"));
13 c.def(py::init<const Shape&>(), "Copy constructor from another Shape.", "shape"_a);
14 c.def_static("Unit", py::overload_cast<const std::string&, const std::string&>(&Shape::Unit), "Constructor for a Shape with identity state", "name"_a, "reference_frame"_a=std::string("world"));
15
16 c.def("get_center_state", &Shape::get_center_state, "Getter of the state.");
17 c.def("get_center_pose", &Shape::get_center_pose, "Getter of the pose from the state.");
18 c.def("get_center_position", &Shape::get_center_position, "Getter of the position from the state.");
19 c.def("get_center_orientation", &Shape::get_center_orientation, "Getter of the orientation from the state.");
20 c.def("get_center_twist", &Shape::get_center_twist, "Getter of the twist from the state.");
21
22 c.def("set_center_state", &Shape::set_center_state, "Setter of the state.");
23 c.def("set_center_pose", &Shape::set_center_pose, "Setter of the pose from the state.");
24 c.def("set_center_position", &Shape::set_center_position, "Setter of the position from the state.");
25 c.def("set_center_orientation", &Shape::set_center_orientation, "Setter of the orientation from the state.");
26
27 c.def("__copy__", [](const Shape &shape) {
28 return Shape(shape);
29 });
30 c.def("__deepcopy__", [](const Shape &shape, py::dict) {
31 return Shape(shape);
32 }, "memo"_a);
33 c.def("__repr__", [](const Shape& shape) {
34 std::stringstream buffer;
35 buffer << shape;
36 return buffer.str();
37 });
38}
39
40void ellipsoid(py::module_& m) {
41 py::class_<Ellipsoid, std::shared_ptr<Ellipsoid>, Shape> c(m, "Ellipsoid");
42
43 c.def(py::init(), "Empty constructor.");
44 c.def(py::init<const std::string&, const std::string&>(), "Constructor with name but empty state.", "name"_a, "reference_frame"_a=std::string("world"));
45 c.def(py::init<const Ellipsoid&>(), "Copy constructor from another Ellipsoid.", "ellipsoid"_a);
46 c.def_static("Unit", py::overload_cast<const std::string&, const std::string&>(&Ellipsoid::Unit), "Constructor for a Ellipsoid with identity state", "name"_a, "reference_frame"_a=std::string("world"));
47
48 c.def("get_axis_lengths", &Ellipsoid::get_axis_lengths, "Getter of the axis lengths.");
49 c.def("get_axis_length", &Ellipsoid::get_axis_length, "Getter of the axis length in one direction.", "index"_a);
50 c.def("set_axis_lengths", py::overload_cast<const std::vector<double>&>(&Ellipsoid::set_axis_lengths), "Setter of the axis lengths.", "axis_lengths"_a);
51 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);
52 c.def("get_rotation_angle", &Ellipsoid::get_rotation_angle, "Getter of the rotation angle.");
53 c.def("set_rotation_angle", &Ellipsoid::set_rotation_angle, "Setter of the rotation angle.", "rotation_angle"_a);
54
55 c.def("get_rotation", &Ellipsoid::get_rotation, "Getter of the rotation.");
56 c.def("sample_from_parameterization", &Ellipsoid::sample_from_parameterization, "Function to sample an obstacle from its parameterization.", "nb_samples"_a);
57 c.def("from_algebraic_equation", &Ellipsoid::from_algebraic_equation, "Compute an ellipsoid from its algebraic equation ax2 + bxy + cy2 + cx + ey + f.");
58 c.def("fit", &Ellipsoid::fit, "Fit an ellipsoid on a set of points.");
59
60 c.def("to_std_vector", &Ellipsoid::to_std_vector, "Convert the ellipse to an std vector representation of its parameter.");
61
62 c.def("__copy__", [](const Shape &shape) {
63 return Shape(shape);
64 });
65 c.def("__deepcopy__", [](const Shape &shape, py::dict) {
66 return Shape(shape);
67 }, "memo"_a);
68 c.def("__repr__", [](const Shape& shape) {
69 std::stringstream buffer;
70 buffer << shape;
71 return buffer.str();
72 });
73}
74
75void bind_geometry(py::module_& m) {
76 shape(m);
77 ellipsoid(m);
78}
static Ellipsoid Unit(const std::string &name, const std::string &reference_frame="world")
Constructor for a Ellipsoid with identity state, unit axis lengths and zero rotation angle.
Definition Ellipsoid.cpp:29
void set_rotation_angle(double rotation_angle)
Setter of the rotation angle.
Definition Ellipsoid.cpp:74
double get_axis_length(unsigned int index) const
Getter of the axis length in one direction.
Definition Ellipsoid.cpp:46
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.
const std::list< CartesianPose > sample_from_parameterization(unsigned int nb_samples) const
Function to sample an obstacle from its parameterization.
const CartesianPose get_rotation() const
Getter of the rotation as a pose.
Definition Ellipsoid.cpp:56
void set_axis_lengths(const std::vector< double > &axis_lengths)
Setter of the axis lengths.
Definition Ellipsoid.cpp:64
double get_rotation_angle() const
Getter of the rotation angle.
Definition Ellipsoid.cpp:51
const std::vector< double > to_std_vector() const
Convert the Ellipsoid to an std vector representation of its parameter.
const std::vector< double > & get_axis_lengths() const
Getter of the axis lengths.
Definition Ellipsoid.cpp:41
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:93
void set_center_orientation(const Eigen::Quaterniond &orientation)
Setter of the pose.
Definition Shape.cpp:82
void set_center_state(const CartesianState &state)
Setter of the state.
Definition Shape.cpp:60
static Shape Unit(const std::string &name, const std::string &reference_frame="world")
Constructor for a Shape with identity state.
Definition Shape.cpp:23
const Eigen::Vector3d get_center_position() const
Getter of the position from the state.
Definition Shape.cpp:45
const CartesianState & get_center_state() const
Getter of the state.
Definition Shape.cpp:35
const CartesianPose & get_center_pose() const
Getter of the pose from the state.
Definition Shape.cpp:40
const Eigen::Quaterniond get_center_orientation() const
Getter of the orientation from the state.
Definition Shape.cpp:50
void set_center_pose(const CartesianPose &pose)
Setter of the pose.
Definition Shape.cpp:68
void set_center_position(const Eigen::Vector3d &position)
Setter of the position.
Definition Shape.cpp:77
const CartesianTwist & get_center_twist() const
Getter of the twist from the state.
Definition Shape.cpp:55
Abstract class to represent a state.
Definition State.hpp:25