1#include "state_representation_bindings.hpp" 
    3#include <state_representation/State.hpp> 
    4#include <state_representation/geometry/Shape.hpp> 
    5#include <state_representation/geometry/Ellipsoid.hpp> 
    8void shape(py::module_& m) {
 
    9  py::class_<Shape, std::shared_ptr<Shape>, 
State> c(m, 
"Shape");
 
   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"));
 
   27  c.def(
"__copy__", [](
const Shape &shape) {
 
   30  c.def(
"__deepcopy__", [](
const Shape &shape, py::dict) {
 
   33  c.def(
"__repr__", [](
const Shape& shape) {
 
   34    std::stringstream buffer;
 
   40void ellipsoid(py::module_& m) {
 
   41  py::class_<Ellipsoid, std::shared_ptr<Ellipsoid>, 
Shape> c(m, 
"Ellipsoid");
 
   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"));
 
   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);
 
   58  c.def(
"fit", &
Ellipsoid::fit, 
"Fit an ellipsoid on a set of points.");
 
   60  c.def(
"to_std_vector", &
Ellipsoid::to_std_vector, 
"Convert the ellipse to an std vector representation of its parameter.");
 
   62  c.def(
"__copy__", [](
const Shape &shape) {
 
   65  c.def(
"__deepcopy__", [](
const Shape &shape, py::dict) {
 
   68  c.def(
"__repr__", [](
const Shape& shape) {
 
   69    std::stringstream buffer;
 
   75void bind_geometry(py::module_& m) {
 
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.
 
void set_rotation_angle(double rotation_angle)
Setter of the rotation angle.
 
double get_axis_length(unsigned int index) const
Getter of the axis length in one direction.
 
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.
 
void set_axis_lengths(const std::vector< double > &axis_lengths)
Setter of the axis lengths.
 
double get_rotation_angle() const
Getter of the rotation angle.
 
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.
 
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,...
 
void set_center_orientation(const Eigen::Quaterniond &orientation)
Setter of the pose.
 
void set_center_state(const CartesianState &state)
Setter of the state.
 
static Shape Unit(const std::string &name, const std::string &reference_frame="world")
Constructor for a Shape with identity state.
 
const Eigen::Vector3d get_center_position() const
Getter of the position from the state.
 
const CartesianState & get_center_state() const
Getter of the state.
 
const CartesianPose & get_center_pose() const
Getter of the pose from the state.
 
const Eigen::Quaterniond get_center_orientation() const
Getter of the orientation from the state.
 
void set_center_pose(const CartesianPose &pose)
Setter of the pose.
 
void set_center_position(const Eigen::Vector3d &position)
Setter of the position.
 
const CartesianTwist & get_center_twist() const
Getter of the twist from the state.
 
Abstract class to represent a state.