Control Libraries 6.3.4
Loading...
Searching...
No Matches
bind_cartesian_space.cpp
1#include "state_representation_bindings.h"
2
3#include <state_representation/State.hpp>
4#include <state_representation/space/SpatialState.hpp>
5#include <state_representation/space/cartesian/CartesianState.hpp>
6#include <state_representation/space/cartesian/CartesianPose.hpp>
7#include <state_representation/space/cartesian/CartesianTwist.hpp>
8#include <state_representation/space/cartesian/CartesianAcceleration.hpp>
9#include <state_representation/space/cartesian/CartesianWrench.hpp>
10
11
12void spatial_state(py::module_& m) {
13 py::class_<SpatialState, std::shared_ptr<SpatialState>, State> c(m, "SpatialState");
14
15 c.def(py::init(), "Empty constructor.");
16 c.def(py::init<const StateType&>(), "Constructor only specifying the type.", "type"_a);
17 c.def(py::init<const StateType&, const std::string&, const std::string&, const bool&>(), "Constructor with name and reference frame specification.", "type"_a, "name"_a, "reference_frame"_a=std::string("world"), "empty"_a=true);
18 c.def(py::init<const SpatialState&>(), "Copy constructor from another SpatialState.", "state"_a);
19
20 c.def("get_reference_frame", &SpatialState::get_reference_frame, "Getter of the reference frame.");
21 c.def("set_reference_frame", &SpatialState::set_reference_frame, "Setter of the reference frame.", "reference_frame"_a);
22 c.def("is_compatible", &SpatialState::is_compatible, "Check if the state is compatible for operations with the state given as argument.", "state"_a);
23
24 c.def("__copy__", [](const SpatialState &state) {
25 return SpatialState(state);
26 });
27 c.def("__deepcopy__", [](const SpatialState &state, py::dict) {
28 return SpatialState(state);
29 }, "memo"_a);
30 c.def("__repr__", [](const SpatialState& state) {
31 std::stringstream buffer;
32 buffer << state;
33 return buffer.str();
34 });
35}
36
37void cartesian_state_variable(py::module_& m) {
38 py::enum_<CartesianStateVariable>(m, "CartesianStateVariable")
39 .value("POSITION", CartesianStateVariable::POSITION)
40 .value("ORIENTATION", CartesianStateVariable::ORIENTATION)
41 .value("POSE", CartesianStateVariable::POSE)
42 .value("LINEAR_VELOCITY", CartesianStateVariable::LINEAR_VELOCITY)
43 .value("ANGULAR_VELOCITY", CartesianStateVariable::ANGULAR_VELOCITY)
44 .value("TWIST", CartesianStateVariable::TWIST)
45 .value("LINEAR_ACCELERATION", CartesianStateVariable::LINEAR_ACCELERATION)
46 .value("ANGULAR_ACCELERATION", CartesianStateVariable::ANGULAR_ACCELERATION)
47 .value("ACCELERATION", CartesianStateVariable::ACCELERATION)
48 .value("FORCE", CartesianStateVariable::FORCE)
49 .value("TORQUE", CartesianStateVariable::TORQUE)
50 .value("WRENCH", CartesianStateVariable::WRENCH)
51 .value("ALL", CartesianStateVariable::ALL)
52 .export_values();
53}
54
55void cartesian_state(py::module_& m) {
56 m.def("dist", py::overload_cast<const CartesianState&, const CartesianState&, const CartesianStateVariable&>(&state_representation::dist), "Compute the distance between two CartesianStates", "s1"_a, "s2"_a, "state_variable_type"_a=CartesianStateVariable::ALL);
57
58 py::class_<CartesianState, std::shared_ptr<CartesianState>, SpatialState> c(m, "CartesianState");
59 c.def(py::init(), "Empty constructor");
60 c.def(py::init<const std::string&, const std::string&>(), "Constructor with name and reference frame provided", "name"_a, "reference_frame"_a=std::string("world"));
61 c.def(py::init<const CartesianState&>(), "Copy constructor of a CartesianState", "state"_a);
62
63 c.def_static("Identity", &CartesianState::Identity, "Constructor for the identity CartesianState (identity pose and 0 for the rest)", "name"_a, "reference_frame"_a=std::string("world"));
64 c.def_static("Random", &CartesianState::Random, "Constructor for a random state", "name"_a, "reference_frame"_a=std::string("world"));
65
66 c.def("get_position", &CartesianState::get_position, "Getter of the position attribute");
67 c.def("get_orientation", [](const CartesianState &state) -> py::object {
68 py::object PyQuaternion = py::module_::import("pyquaternion").attr("Quaternion");
69 return PyQuaternion(state.get_orientation_coefficients());;
70 }, "Getter of the orientation attribute as pyquaternion object");
71 c.def("get_orientation_coefficients", &CartesianState::get_orientation_coefficients, "Getter of the orientation attribute as quaternion coefficients (w, x, y, z)");
72 c.def("get_pose", &CartesianState::get_pose, "Getter of a 7d pose vector from position and orientation coefficients");
73 c.def("get_transformation_matrix", &CartesianState::get_transformation_matrix, "Getter of a 4x4 transformation matrix of the pose");
74
75 c.def("get_linear_velocity", &CartesianState::get_linear_velocity, "Getter of the linear velocity attribute");
76 c.def("get_angular_velocity", &CartesianState::get_angular_velocity, "Getter of the angular velocity attribute");
77 c.def("get_twist", &CartesianState::get_twist, "Getter of the 6d twist from linear and angular velocity attributes");
78
79 c.def("get_linear_acceleration", &CartesianState::get_linear_acceleration, "Getter of the linear acceleration attribute");
80 c.def("get_angular_acceleration", &CartesianState::get_angular_acceleration, "Getter of the angular acceleration attribute");
81 c.def("get_acceleration", &CartesianState::get_acceleration, "Getter of the 6d acceleration from linear and angular acceleration attributes");
82
83 c.def("get_force", &CartesianState::get_force, "Getter of the force attribute");
84 c.def("get_torque", &CartesianState::get_torque, "Getter of the torque attribute");
85 c.def("get_wrench", &CartesianState::get_wrench, "Getter of the 6d wrench from force and torque attributes");
86
87 c.def("set_position", py::overload_cast<const Eigen::Vector3d&>(&CartesianState::set_position), "Setter of the position");
88 c.def("set_position", py::overload_cast<const std::vector<double>&>(&CartesianState::set_position), "Setter of the position from a list");
89 c.def("set_position", py::overload_cast<const double&, const double&, const double&>(&CartesianState::set_position), "Setter of the position from three scalar coordinates", "x"_a, "y"_a, "z"_a);
90 c.def("set_orientation", [](CartesianState &state, const py::object& quaternion) {
91 py::object PyQuaternion = py::module_::import("pyquaternion").attr("Quaternion");
92 if (py::isinstance<py::list>(quaternion)) {
93 state.set_orientation(py::cast<std::vector<double>>(quaternion));
94 } else if (py::isinstance<py::array>(quaternion)) {
95 state.set_orientation(py::cast<Eigen::Vector4d>(quaternion));
96 } else if (py::isinstance(quaternion, PyQuaternion)) {
97 state.set_orientation(py::cast<Eigen::Vector4d>(quaternion.attr("elements")));
98 } else {
99 throw std::invalid_argument("Type of input argument quaternion is not supported. "
100 "Supported types are: pyquaternion.Quaternion, numpy.array, list");
101 }
102 }, "Setter of the orientation attribute from a pyquaternion.Quaternion, numpy.array(w, x, y, z), or list(w, x, y, z)");
103 c.def("set_pose", py::overload_cast<const Eigen::Matrix<double, 7, 1>&>(&CartesianState::set_pose), "Setter of the pose from a 7d vector of position and orientation coefficients (x, y, z, qw, qx, qy, qz)");
104 c.def("set_pose", py::overload_cast<const std::vector<double>&>(&CartesianState::set_pose), "Setter of the pose from a 7d list of position and orientation coefficients (x, y, z, qw, qx, qy, qz)");
105
106 c.def("set_linear_velocity", py::overload_cast<const Eigen::Vector3d&>(&CartesianState::set_linear_velocity), "Setter of the linear velocity attribute");
107 c.def("set_linear_velocity", py::overload_cast<const std::vector<double>&>(&CartesianState::set_linear_velocity), "Setter of the linear velocity from a list");
108 c.def("set_linear_velocity", py::overload_cast<const double&, const double&, const double&>(&CartesianState::set_linear_velocity), "Setter of the linear velocity from three scalar coordinates", "x"_a, "y"_a, "z"_a);
109 c.def("set_angular_velocity", py::overload_cast<const Eigen::Vector3d&>(&CartesianState::set_angular_velocity), "Setter of the angular velocity attribute");
110 c.def("set_angular_velocity", py::overload_cast<const std::vector<double>&>(&CartesianState::set_angular_velocity), "Setter of the angular velocity from a list");
111 c.def("set_angular_velocity", py::overload_cast<const double&, const double&, const double&>(&CartesianState::set_angular_velocity), "Setter of the angular velocity from three scalar coordinates", "x"_a, "y"_a, "z"_a);
112 c.def("set_twist", py::overload_cast<const Eigen::Matrix<double, 6, 1>&>(&CartesianState::set_twist), "Setter of the linear and angular velocities from a 6d twist vector");
113 c.def("set_twist", py::overload_cast<const std::vector<double>&>(&CartesianState::set_twist), "Setter of the linear and angular velocities from a list");
114
115 c.def("set_linear_acceleration", py::overload_cast<const Eigen::Vector3d&>(&CartesianState::set_linear_acceleration), "Setter of the linear acceleration attribute");
116 c.def("set_linear_acceleration", py::overload_cast<const std::vector<double>&>(&CartesianState::set_linear_acceleration), "Setter of the linear acceleration from a list");
117 c.def("set_linear_acceleration", py::overload_cast<const double&, const double&, const double&>(&CartesianState::set_linear_acceleration), "Setter of the linear acceleration from three scalar coordinates", "x"_a, "y"_a, "z"_a);
118 c.def("set_angular_acceleration", py::overload_cast<const Eigen::Vector3d&>(&CartesianState::set_angular_acceleration), "Setter of the angular acceleration attribute");
119 c.def("set_angular_acceleration", py::overload_cast<const std::vector<double>&>(&CartesianState::set_angular_acceleration), "Setter of the angular acceleration from a list");
120 c.def("set_angular_acceleration", py::overload_cast<const double&, const double&, const double&>(&CartesianState::set_angular_acceleration), "Setter of the angular acceleration from three scalar coordinates", "x"_a, "y"_a, "z"_a);
121 c.def("set_acceleration", py::overload_cast<const Eigen::Matrix<double, 6, 1>&>(&CartesianState::set_acceleration), "Setter of the linear and angular accelerations from a 6d acceleration vector");
122 c.def("set_acceleration", py::overload_cast<const std::vector<double>&>(&CartesianState::set_acceleration), "Setter of the linear and angular accelerations from a list");
123
124 c.def("set_force", py::overload_cast<const Eigen::Vector3d&>(&CartesianState::set_force), "Setter of the force attribute");
125 c.def("set_force", py::overload_cast<const std::vector<double>&>(&CartesianState::set_force), "Setter of the force from a list");
126 c.def("set_force", py::overload_cast<const double&, const double&, const double&>(&CartesianState::set_force), "Setter of the force from three scalar coordinates", "x"_a, "y"_a, "z"_a);
127 c.def("set_torque", py::overload_cast<const Eigen::Vector3d&>(&CartesianState::set_torque), "Setter of the torque attribute");
128 c.def("set_torque", py::overload_cast<const std::vector<double>&>(&CartesianState::set_torque), "Setter of the torque from a list");
129 c.def("set_torque", py::overload_cast<const double&, const double&, const double&>(&CartesianState::set_torque), "Setter of the torque from three scalar coordinates", "x"_a, "y"_a, "z"_a);
130 c.def("set_wrench", py::overload_cast<const Eigen::Matrix<double, 6, 1>&>(&CartesianState::set_wrench), "Setter of the force and torque from a 6d wrench vector");
131 c.def("set_wrench", py::overload_cast<const std::vector<double>&>(&CartesianState::set_wrench), "Setter of the force and torque velocities from a list");
132
133 c.def("set_zero", &CartesianState::set_zero, "Set the CartesianState to a zero value");
134 c.def("clamp_state_variable", &CartesianState::clamp_state_variable, "Clamp inplace the magnitude of the a specific state variable (velocity, acceleration or force)", "max_value"_a, "state_variable_type"_a, "noise_ratio"_a=double(0));
135 c.def("copy", &CartesianState::copy, "Return a copy of the CartesianState");
136 c.def("data", &CartesianState::data, "Returns the data as the concatenation of all the state variables in a single vector");
137 c.def("array", &CartesianState::array, "Returns the data vector as an array");
138 c.def("set_data", py::overload_cast<const Eigen::VectorXd&>(&CartesianState::set_data), "Set the data of the state from all the state variables in a single vector", "data"_a);
139 c.def("set_data", py::overload_cast<const std::vector<double>&>(&CartesianState::set_data), "Set the data of the state from all the state variables in a single list", "data"_a);
140
141 c.def(py::self *= py::self);
142 c.def(py::self * py::self);
143 c.def(py::self *= double());
144 c.def(py::self * double());
145 c.def(double() * py::self);
146 c.def(py::self /= double());
147 c.def(py::self / double());
148 c.def(py::self += py::self);
149 c.def(py::self + py::self);
150 c.def(py::self -= py::self);
151 c.def(py::self - py::self);
152
153 c.def("inverse", &CartesianState::inverse, "Compute the inverse of the current CartesianState");
154 c.def("dist", &CartesianState::dist, "Compute the distance to another state as the sum of distances between each features", "state"_a, "state_variable_type"_a=CartesianStateVariable::ALL);
155 c.def("norms", &CartesianState::norms, "Compute the norms of the state variable specified by the input type (default is full state)", "state_variable_type"_a=CartesianStateVariable::ALL);
156 c.def("normalize", &CartesianState::normalize, "Normalize inplace the state at the state variable given in argument (default is full state)", "state_variable_type"_a=CartesianStateVariable::ALL);
157 c.def("normalized", &CartesianState::normalized, "Compute the normalized state at the state variable given in argument (default is full state)", "state_variable_type"_a=CartesianStateVariable::ALL);
158
159 c.def("to_list", &CartesianState::to_std_vector, "Return the state as a list");
160
161 c.def("__copy__", [](const CartesianState &state) {
162 return CartesianState(state);
163 });
164 c.def("__deepcopy__", [](const CartesianState &state, py::dict) {
165 return CartesianState(state);
166 }, "memo"_a);
167 c.def("__repr__", [](const CartesianState& state) {
168 std::stringstream buffer;
169 buffer << state;
170 return buffer.str();
171 });
172}
173
174void cartesian_pose(py::module_& m) {
175 py::class_<CartesianPose, std::shared_ptr<CartesianPose>, CartesianState> c(m, "CartesianPose");
176
177 c.def(py::init(), "Empty constructor");
178 c.def(py::init<const std::string&, const std::string&>(), "Constructor with name and reference frame provided", "name"_a, "reference_frame"_a=std::string("world"));
179 c.def(py::init<const CartesianPose&>(), "Copy constructor of a CartesianPose", "pose"_a);
180 c.def(py::init<const CartesianState&>(), "Copy constructor from a CartesianState", "state"_a);
181 c.def(py::init<const CartesianTwist&>(), "Copy constructor from a CartesianTwist by considering that it is a displacement over 1 second", "twist"_a);
182
183 c.def(py::init<const std::string&, const Eigen::Vector3d&, const std::string&>(), "Constructor of a CartesianPose from a position given as a vector of coordinates", "name"_a, "position"_a, "reference_frame"_a=std::string("world"));
184 c.def(py::init<const std::string&, double, double, double, const std::string&>(), "Constructor of a CartesianPose from a position given as three scalar coordinates", "name"_a, "x"_a, "y"_a, "z"_a, "reference_frame"_a=std::string("world"));
185 c.def(py::init([](const std::string& name, const Eigen::Vector4d& orientation, const std::string& reference) {
186 Eigen::Quaterniond q(orientation(0), orientation(1), orientation(2), orientation(3));
187 return new CartesianPose(name, q, reference);
188 }), "Constructor of a CartesianPose from a quaternion", "name"_a, "orientation"_a, "reference_frame"_a=std::string("world"));
189 c.def(py::init([](const std::string& name, const Eigen::Vector3d& position, const Eigen::Vector4d& orientation, const std::string& reference) {
190 Eigen::Quaterniond q(orientation(0), orientation(1), orientation(2), orientation(3));
191 return new CartesianPose(name, position, q, reference);
192 }), "Constructor of a CartesianPose from a position given as a vector of coordinates and a quaternion", "name"_a, "position"_a, "orientation"_a, "reference_frame"_a=std::string("world"));
193
194 c.def_static("Identity", &CartesianPose::Identity, "Constructor for the identity pose", "name"_a, "reference_frame"_a=std::string("world"));
195 c.def_static("Random", &CartesianPose::Random, "Constructor for a random pose", "name"_a, "reference_frame"_a=std::string("world"));
196
197 std::vector<std::string> deleted_attributes = {
198 "linear_velocity",
199 "angular_velocity",
200 "twist",
201 "linear_acceleration",
202 "angular_acceleration",
203 "acceleration",
204 "force",
205 "torque",
206 "wrench"
207 };
208
209 for (const std::string& attr : deleted_attributes) {
210 c.def(std::string("get_" + attr).c_str(), [](const CartesianPose&) -> void {}, "Deleted method from parent class.");
211 c.def(std::string("set_" + attr).c_str(), [](const CartesianPose& pose) -> CartesianPose { return pose; }, "Deleted method from parent class.");
212 }
213
214 c.def(py::self *= py::self);
215 c.def(py::self * py::self);
216 c.def(py::self * CartesianState());
217 c.def(py::self * CartesianTwist());
218 c.def(py::self * CartesianWrench());
219 c.def(py::self * Eigen::Vector3d());
220 c.def(py::self *= double());
221 c.def(py::self * double());
222 c.def(double() * py::self);
223 c.def(py::self /= double());
224 c.def(py::self / double());
225
226 c.def(py::self += py::self);
227 c.def(py::self + py::self);
228 c.def(py::self -= py::self);
229 c.def(py::self - py::self);
230
231 c.def(py::self / std::chrono::nanoseconds());
232
233 c.def("copy", &CartesianPose::copy, "Return a copy of the CartesianPose");
234 c.def("data", &CartesianPose::data, "Returns the pose data as a vector");
235 c.def("set_data", py::overload_cast<const Eigen::VectorXd&>(&CartesianPose::set_data), "Set the pose data from a vector", "data"_a);
236 c.def("set_data", py::overload_cast<const std::vector<double>&>(&CartesianPose::set_data), "Set the pose data from a list", "data"_a);
237 c.def("norms", &CartesianPose::norms, "Compute the norms of the state variable specified by the input type (default is full pose)", "state_variable_type"_a=CartesianStateVariable::POSE);
238 c.def("normalized", &CartesianPose::normalized, "Compute the normalized pose at the state variable given in argument (default is full pose)", "state_variable_type"_a=CartesianStateVariable::POSE);
239
240 c.def("__copy__", [](const CartesianPose &pose) {
241 return CartesianPose(pose);
242 });
243 c.def("__deepcopy__", [](const CartesianPose &pose, py::dict) {
244 return CartesianPose(pose);
245 }, "memo"_a);
246 c.def("__repr__", [](const CartesianPose& pose) {
247 std::stringstream buffer;
248 buffer << pose;
249 return buffer.str();
250 });
251}
252
253void cartesian_twist(py::module_& m) {
254 py::class_<CartesianTwist, std::shared_ptr<CartesianTwist>, CartesianState> c(m, "CartesianTwist");
255
256 c.def(py::init(), "Empty constructor");
257 c.def(py::init<const std::string&, const std::string&>(), "Constructor with name and reference frame provided", "name"_a, "reference_frame"_a=std::string("world"));
258 c.def(py::init<const CartesianTwist&>(), "Copy constructor", "twist"_a);
259 c.def(py::init<const CartesianState&>(), "Copy constructor from a CartesianState", "state"_a);
260 c.def(py::init<const CartesianPose&>(), "Copy constructor from a CartesianPose by considering that it is equivalent to dividing the pose by 1 second", "pose"_a);
261
262 c.def(py::init<const std::string&, const Eigen::Vector3d&, const std::string&>(), "Construct a CartesianTwist from a linear velocity given as a vector.", "name"_a, "linear_velocity"_a, "reference_frame"_a=std::string("world"));
263 c.def(py::init<const std::string&, const Eigen::Vector3d&, const Eigen::Vector3d&, const std::string&>(), "Construct a CartesianTwist from a linear velocity and angular velocity given as vectors.", "name"_a, "linear_velocity"_a, "angular_velocity"_a, "reference_frame"_a=std::string("world"));
264 c.def(py::init<const std::string&, const Eigen::Matrix<double, 6, 1>&, const std::string&>(), "Construct a CartesianTwist from a single 6d twist vector", "name"_a, "twist"_a, "reference_frame"_a=std::string("world"));
265
266 c.def_static("Zero", &CartesianTwist::Zero, "Constructor for the zero twist", "name"_a, "reference_frame"_a=std::string("world"));
267 c.def_static("Random", &CartesianTwist::Random, "Constructor for a random twist", "name"_a, "reference_frame"_a=std::string("world"));
268
269 std::vector<std::string> deleted_attributes = {
270 "position",
271 "orientation",
272 "pose",
273 "linear_acceleration",
274 "angular_acceleration",
275 "acceleration",
276 "force",
277 "torque",
278 "wrench"
279 };
280
281 for (const std::string& attr : deleted_attributes) {
282 c.def(std::string("get_" + attr).c_str(), [](const CartesianTwist&) -> void {}, "Deleted method from parent class.");
283 c.def(std::string("set_" + attr).c_str(), [](const CartesianTwist& twist) -> CartesianTwist { return twist; }, "Deleted method from parent class.");
284 }
285 c.def(std::string("get_orientation_coefficients").c_str(), [](const CartesianTwist&) -> void {}, "Deleted method from parent class.");
286
287 c.def(py::self += py::self);
288 c.def(py::self + py::self);
289 c.def(py::self -= py::self);
290 c.def(py::self - py::self);
291
292 c.def(py::self *= double());
293 c.def(py::self * double());
294 c.def(py::self /= double());
295 c.def(py::self / double());
296 c.def(py::self *= Eigen::Matrix<double, 6, 6>());
297 c.def(py::self * std::chrono::nanoseconds());
298 c.def(py::self / std::chrono::nanoseconds());
299
300 c.def(double() * py::self);
301 c.def(std::chrono::nanoseconds() * py::self);
302 c.def(Eigen::Matrix<double, 6, 6>() * py::self);
303
304 c.def("clamp", &CartesianTwist::clamp, "Clamp inplace the magnitude of the twist to the values in argument", "max_linear"_a, "max_angular"_a, "linear_noise_ratio"_a=0, "angular_noise_ratio"_a=0);
305 c.def("clamped", &CartesianTwist::clamped, "Return the clamped twist", "max_linear"_a, "max_angular"_a, "linear_noise_ratio"_a=0, "angular_noise_ratio"_a=0);
306
307 c.def("copy", &CartesianTwist::copy, "Return a copy of the CartesianTwist");
308 c.def("data", &CartesianTwist::data, "Returns the twist data as a vector");
309 c.def("set_data", py::overload_cast<const Eigen::VectorXd&>(&CartesianTwist::set_data), "Set the twist data from a vector", "data"_a);
310 c.def("set_data", py::overload_cast<const std::vector<double>&>(&CartesianTwist::set_data), "Set the twist data from a list", "data"_a);
311 c.def("norms", &CartesianTwist::norms, "Compute the norms of the state variable specified by the input type (default is full twist)", "state_variable_type"_a=CartesianStateVariable::TWIST);
312 c.def("normalized", &CartesianTwist::normalized, "Compute the normalized twist at the state variable given in argument (default is full twist)", "state_variable_type"_a=CartesianStateVariable::TWIST);
313
314 c.def("__copy__", [](const CartesianTwist &twist) {
315 return CartesianTwist(twist);
316 });
317 c.def("__deepcopy__", [](const CartesianTwist &twist, py::dict) {
318 return CartesianTwist(twist);
319 }, "memo"_a);
320 c.def("__repr__", [](const CartesianTwist& twist) {
321 std::stringstream buffer;
322 buffer << twist;
323 return buffer.str();
324 });
325}
326
327void cartesian_acceleration(py::module_& m) {
328 py::class_<CartesianAcceleration, std::shared_ptr<CartesianAcceleration>, CartesianState> c(m, "CartesianAcceleration");
329
330 c.def(py::init(), "Empty constructor");
331 c.def(py::init<const std::string&, const std::string&>(), "Constructor with name and reference frame provided", "name"_a, "reference_frame"_a=std::string("world"));
332 c.def(py::init<const CartesianAcceleration&>(), "Copy constructor", "acceleration"_a);
333 c.def(py::init<const CartesianState&>(), "Copy constructor from a CartesianState", "state"_a);
334 c.def(py::init<const CartesianTwist&>(), "Copy constructor from a CartesianTwist by considering that it is equivalent to dividing the twist by 1 second", "twist"_a);
335
336 c.def(py::init<const std::string&, const Eigen::Vector3d&, const std::string&>(), "Construct a CartesianAcceleration from a linear acceleration given as a vector.", "name"_a, "linear_acceleration"_a, "reference_frame"_a=std::string("world"));
337 c.def(py::init<const std::string&, const Eigen::Vector3d&, const Eigen::Vector3d&, const std::string&>(), "Construct a CartesianAcceleration from a linear acceleration and angular acceleration given as vectors.", "name"_a, "linear_acceleration"_a, "angular_acceleration"_a, "reference_frame"_a=std::string("world"));
338 c.def(py::init<const std::string&, const Eigen::Matrix<double, 6, 1>&, const std::string&>(), "Construct a CartesianAcceleration from a single 6d acceleration vector", "name"_a, "acceleration"_a, "reference_frame"_a=std::string("world"));
339
340 c.def_static("Zero", &CartesianAcceleration::Zero, "Constructor for the zero acceleration", "name"_a, "reference_frame"_a=std::string("world"));
341 c.def_static("Random", &CartesianAcceleration::Random, "Constructor for a random acceleration", "name"_a, "reference_frame"_a=std::string("world"));
342
343 std::vector<std::string> deleted_attributes = {
344 "position",
345 "orientation",
346 "pose",
347 "linear_velocity",
348 "angular_velocity",
349 "twist",
350 "force",
351 "torque",
352 "wrench"
353 };
354
355 for (const std::string& attr : deleted_attributes) {
356 c.def(std::string("get_" + attr).c_str(), [](const CartesianAcceleration&) -> void {}, "Deleted method from parent class.");
357 c.def(std::string("set_" + attr).c_str(), [](const CartesianAcceleration& acceleration) -> CartesianAcceleration { return acceleration; }, "Deleted method from parent class.");
358 }
359 c.def(std::string("get_orientation_coefficients").c_str(), [](const CartesianAcceleration&) -> void {}, "Deleted method from parent class.");
360
361 c.def(py::self += py::self);
362 c.def(py::self + py::self);
363 c.def(py::self -= py::self);
364 c.def(py::self - py::self);
365
366 c.def(py::self *= double());
367 c.def(py::self * double());
368 c.def(py::self /= double());
369 c.def(py::self / double());
370 c.def(py::self *= Eigen::Matrix<double, 6, 6>());
371 c.def(py::self * std::chrono::nanoseconds());
372
373 c.def(double() * py::self);
374 c.def(std::chrono::nanoseconds() * py::self);
375 c.def(Eigen::Matrix<double, 6, 6>() * py::self);
376
377 c.def("clamp", &CartesianAcceleration::clamp, "Clamp inplace the magnitude of the acceleration to the values in argument", "max_linear"_a, "max_angular"_a, "linear_noise_ratio"_a=0, "angular_noise_ratio"_a=0);
378 c.def("clamped", &CartesianAcceleration::clamped, "Return the clamped acceleration", "max_linear"_a, "max_angular"_a, "linear_noise_ratio"_a=0, "angular_noise_ratio"_a=0);
379
380 c.def("copy", &CartesianAcceleration::copy, "Return a copy of the CartesianAcceleration");
381 c.def("data", &CartesianAcceleration::data, "Returns the acceleration data as a vector");
382 c.def("set_data", py::overload_cast<const Eigen::VectorXd&>(&CartesianAcceleration::set_data), "Set the acceleration data from a vector", "data"_a);
383 c.def("set_data", py::overload_cast<const std::vector<double>&>(&CartesianAcceleration::set_data), "Set the acceleration data from a list", "data"_a);
384 c.def("norms", &CartesianAcceleration::norms, "Compute the norms of the state variable specified by the input type (default is full acceleration)", "state_variable_type"_a=CartesianStateVariable::ACCELERATION);
385 c.def("normalized", &CartesianAcceleration::normalized, "Compute the normalized acceleration at the state variable given in argument (default is full acceleration)", "state_variable_type"_a=CartesianStateVariable::ACCELERATION);
386
387 c.def("__copy__", [](const CartesianAcceleration &acceleration) {
388 return CartesianAcceleration(acceleration);
389 });
390 c.def("__deepcopy__", [](const CartesianAcceleration &acceleration, py::dict) {
391 return CartesianAcceleration(acceleration);
392 }, "memo"_a);
393 c.def("__repr__", [](const CartesianAcceleration& acceleration) {
394 std::stringstream buffer;
395 buffer << acceleration;
396 return buffer.str();
397 });
398}
399
400void cartesian_wrench(py::module_& m) {
401 py::class_<CartesianWrench, std::shared_ptr<CartesianWrench>, CartesianState> c(m, "CartesianWrench");
402
403 c.def(py::init(), "Empty constructor");
404 c.def(py::init<const std::string&, const std::string&>(), "Constructor with name and reference frame provided", "name"_a, "reference_frame"_a=std::string("world"));
405 c.def(py::init<const CartesianWrench&>(), "Copy constructor", "twist"_a);
406 c.def(py::init<const CartesianState&>(), "Copy constructor from a CartesianState", "state"_a);
407
408 c.def(py::init<const std::string&, const Eigen::Vector3d&, const std::string&>(), "Construct a CartesianWrench from a force given as a vector.", "name"_a, "force"_a, "reference_frame"_a=std::string("world"));
409 c.def(py::init<const std::string&, const Eigen::Vector3d&, const Eigen::Vector3d&, const std::string&>(), "Construct a CartesianWrench from a force and torque given as vectors.", "name"_a, "force"_a, "torque"_a, "reference_frame"_a=std::string("world"));
410 c.def(py::init<const std::string&, const Eigen::Matrix<double, 6, 1>&, const std::string&>(), "Construct a CartesianTwist from a single 6d wrench vector", "name"_a, "wrench"_a, "reference_frame"_a=std::string("world"));
411
412 c.def_static("Zero", &CartesianWrench::Zero, "Constructor for the zero wrench", "name"_a, "reference_frame"_a=std::string("world"));
413 c.def_static("Random", &CartesianWrench::Random, "Constructor for a random wrench", "name"_a, "reference_frame"_a=std::string("world"));
414
415 std::vector<std::string> deleted_attributes = {
416 "position",
417 "orientation",
418 "pose",
419 "linear_velocity",
420 "angular_velocity",
421 "twist",
422 "linear_acceleration",
423 "angular_acceleration",
424 "acceleration",
425 };
426
427 for (const std::string& attr : deleted_attributes) {
428 c.def(std::string("get_" + attr).c_str(), [](const CartesianWrench&) -> void {}, "Deleted method from parent class.");
429 c.def(std::string("set_" + attr).c_str(), [](const CartesianWrench& wrench) -> CartesianWrench { return wrench; }, "Deleted method from parent class.");
430 }
431 c.def(std::string("get_orientation_coefficients").c_str(), [](const CartesianWrench&) -> void {}, "Deleted method from parent class.");
432
433 c.def(py::self += py::self);
434 c.def(py::self + py::self);
435 c.def(py::self -= py::self);
436 c.def(py::self - py::self);
437
438 c.def(py::self *= double());
439 c.def(py::self * double());
440 c.def(double() * py::self);
441 c.def(py::self /= double());
442 c.def(py::self / double());
443
444 c.def("clamp", &CartesianWrench::clamp, "Clamp inplace the magnitude of the wrench to the values in argument", "max_force"_a, "max_torque"_a, "force_noise_ratio"_a=0, "torque_noise_ratio"_a=0);
445 c.def("clamped", &CartesianWrench::clamped, "Return the clamped wrench", "max_force"_a, "max_torque"_a, "force_noise_ratio"_a=0, "torque_noise_ratio"_a=0);
446
447 c.def("copy", &CartesianWrench::copy, "Return a copy of the CartesianWrench");
448 c.def("data", &CartesianWrench::data, "Returns the wrench data as a vector");
449 c.def("set_data", py::overload_cast<const Eigen::VectorXd&>(&CartesianWrench::set_data), "Set the wrench data from a vector", "data"_a);
450 c.def("set_data", py::overload_cast<const std::vector<double>&>(&CartesianWrench::set_data), "Set the wrench data from a list", "data"_a);
451 c.def("norms", &CartesianWrench::norms, "Compute the norms of the state variable specified by the input type (default is full wrench)", "state_variable_type"_a=CartesianStateVariable::WRENCH);
452 c.def("normalized", &CartesianWrench::normalized, "Compute the normalized twist at the state variable given in argument (default is full wrench)", "state_variable_type"_a=CartesianStateVariable::WRENCH);
453
454 c.def("__copy__", [](const CartesianWrench &wrench) {
455 return CartesianWrench(wrench);
456 });
457 c.def("__deepcopy__", [](const CartesianWrench &wrench, py::dict) {
458 return CartesianWrench(wrench);
459 }, "memo"_a);
460 c.def("__repr__", [](const CartesianWrench& wrench) {
461 std::stringstream buffer;
462 buffer << wrench;
463 return buffer.str();
464 });
465}
466
467void bind_cartesian_space(py::module_& m) {
468 spatial_state(m);
469 cartesian_state_variable(m);
470 cartesian_state(m);
471 cartesian_pose(m);
472 cartesian_twist(m);
473 cartesian_acceleration(m);
474 cartesian_wrench(m);
475}
Class to define acceleration in cartesian space as 3D linear and angular acceleration vectors.
void clamp(double max_linear, double max_angular, double linear_noise_ratio=0, double angular_noise_ratio=0)
Clamp inplace the magnitude of the acceleration to the values in argument.
CartesianAcceleration copy() const
Return a copy of the CartesianAcceleration.
CartesianAcceleration clamped(double max_linear, double max_angular, double noise_ratio=0, double angular_noise_ratio=0) const
Return the clamped twist.
Eigen::VectorXd data() const override
Returns the acceleration data as an Eigen vector.
static CartesianAcceleration Zero(const std::string &name, const std::string &reference="world")
Constructor for the zero acceleration.
static CartesianAcceleration Random(const std::string &name, const std::string &reference="world")
Constructor for a random acceleration.
std::vector< double > norms(const CartesianStateVariable &state_variable_type=CartesianStateVariable::ACCELERATION) const override
Compute the norms of the state variable specified by the input type (default is full twist)
void set_data(const Eigen::VectorXd &data) override
Set the acceleration data from an Eigen vector.
CartesianAcceleration normalized(const CartesianStateVariable &state_variable_type=CartesianStateVariable::ACCELERATION) const
Compute the normalized acceleration at the state variable given in argument (default is full accelera...
Class to define CartesianPose in cartesian space as 3D position and quaternion based orientation.
void set_data(const Eigen::VectorXd &data) override
Set the pose data from an Eigen vector.
std::vector< double > norms(const CartesianStateVariable &state_variable_type=CartesianStateVariable::POSE) const override
Compute the norms of the state variable specified by the input type (default is full pose)
static CartesianPose Identity(const std::string &name, const std::string &reference="world")
Constructor for the identity pose.
Eigen::VectorXd data() const override
Returns the pose data as an Eigen vector.
CartesianPose normalized(const CartesianStateVariable &state_variable_type=CartesianStateVariable::POSE) const
Compute the normalized pose at the state variable given in argument (default is full pose)
CartesianPose copy() const
Return a copy of the CartesianPose.
static CartesianPose Random(const std::string &name, const std::string &reference="world")
Constructor for a random pose.
Class to represent a state in Cartesian space.
void set_zero()
Set the State to a zero value.
const Eigen::Vector3d & get_force() const
Getter of the force attribute.
void set_acceleration(const Eigen::Matrix< double, 6, 1 > &acceleration)
Setter of the linear and angular acceleration from a 6d acceleration vector.
CartesianState inverse() const
Compute the inverse of the current CartesianState.
Eigen::ArrayXd array() const
Return the data vector as an Eigen Array.
const Eigen::Vector3d & get_torque() const
Getter of the torque attribute.
static CartesianState Random(const std::string &name, const std::string &reference="world")
Constructor for a random state.
const Eigen::Vector3d & get_linear_velocity() const
Getter of the linear velocity attribute.
void set_angular_acceleration(const Eigen::Vector3d &angular_acceleration)
Setter of the angular velocity attribute.
const Eigen::Vector3d & get_position() const
Getter of the position attribute.
void normalize(const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL)
Normalize inplace the state at the state variable given in argument (default is full state)
virtual std::vector< double > norms(const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL) const
Compute the norms of the state variable specified by the input type (default is full state)
void set_force(const Eigen::Vector3d &force)
Setter of the force attribute.
Eigen::Matrix< double, 6, 1 > get_twist() const
Getter of the 6d twist from linear and angular velocity attributes.
CartesianState normalized(const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL) const
Compute the normalized state at the state variable given in argument (default is full state)
friend double dist(const CartesianState &s1, const CartesianState &s2, const CartesianStateVariable &state_variable_type)
compute the distance between two CartesianStates
static CartesianState Identity(const std::string &name, const std::string &reference="world")
Constructor for the identity CartesianState (identity pose and 0 for the rest)
const Eigen::Vector3d & get_linear_acceleration() const
Getter of the linear acceleration attribute.
Eigen::Matrix4d get_transformation_matrix() const
Getter of a pose from position and orientation attributes.
void set_linear_acceleration(const Eigen::Vector3d &linear_acceleration)
Setter of the linear acceleration attribute.
void clamp_state_variable(double max_norm, const CartesianStateVariable &state_variable_type, double noise_ratio=0)
Clamp inplace the norm of the a specific state variable.
Eigen::Matrix< double, 7, 1 > get_pose() const
Getter of a pose from position and orientation attributes.
void set_position(const Eigen::Vector3d &position)
Setter of the position.
void set_wrench(const Eigen::Matrix< double, 6, 1 > &wrench)
Setter of the force and torque from a 6d wrench vector.
Eigen::Matrix< double, 6, 1 > get_wrench() const
Getter of the 6d wrench from force and torque attributes.
void set_twist(const Eigen::Matrix< double, 6, 1 > &twist)
Setter of the linear and angular velocities from a 6d twist vector.
virtual Eigen::VectorXd data() const
Return the data as the concatenation of all the state variables in a single vector.
const Eigen::Vector3d & get_angular_velocity() const
Getter of the angular velocity attribute.
void set_pose(const Eigen::Vector3d &position, const Eigen::Quaterniond &orientation)
Setter of the pose from both position and orientation.
CartesianState copy() const
Return a copy of the CartesianState.
void set_torque(const Eigen::Vector3d &torque)
Setter of the torque attribute.
virtual void set_data(const Eigen::VectorXd &data) override
Set the data of the state from all the state variables in a single Eigen vector.
Eigen::Vector4d get_orientation_coefficients() const
Getter of the orientation attribute as Vector4d of coefficients Beware, quaternion coefficients are r...
const Eigen::Vector3d & get_angular_acceleration() const
Getter of the angular acceleration attribute.
std::vector< double > to_std_vector() const
Return the state as a std vector.
void set_linear_velocity(const Eigen::Vector3d &linear_velocity)
Setter of the linear velocity attribute.
void set_angular_velocity(const Eigen::Vector3d &angular_velocity)
Setter of the angular velocity attribute.
Eigen::Matrix< double, 6, 1 > get_acceleration() const
Getter of the 6d acceleration from linear and angular acceleration attributes.
Class to define twist in cartesian space as 3D linear and angular velocity vectors.
std::vector< double > norms(const CartesianStateVariable &state_variable_type=CartesianStateVariable::TWIST) const override
Compute the norms of the state variable specified by the input type (default is full twist)
Eigen::VectorXd data() const override
Returns the twist data as an Eigen vector.
CartesianTwist clamped(double max_linear, double max_angular, double noise_ratio=0, double angular_noise_ratio=0) const
Return the clamped twist.
static CartesianTwist Random(const std::string &name, const std::string &reference="world")
Constructor for a random twist.
static CartesianTwist Zero(const std::string &name, const std::string &reference="world")
Constructor for the zero twist.
void set_data(const Eigen::VectorXd &data) override
Set the twist data from an Eigen vector.
void clamp(double max_linear, double max_angular, double linear_noise_ratio=0, double angular_noise_ratio=0)
Clamp inplace the magnitude of the twist to the values in argument.
CartesianTwist copy() const
Return a copy of the CartesianTwist.
CartesianTwist normalized(const CartesianStateVariable &state_variable_type=CartesianStateVariable::TWIST) const
Compute the normalized twist at the state variable given in argument (default is full twist)
Class to define wrench in cartesian space as 3D force and torque vectors.
Eigen::VectorXd data() const override
Returns the wrench data as an Eigen vector.
CartesianWrench normalized(const CartesianStateVariable &state_variable_type=CartesianStateVariable::WRENCH) const
Compute the normalized wrench at the state variable given in argument (default is full wrench)
static CartesianWrench Zero(const std::string &name, const std::string &reference="world")
Constructor for the zero wrench.
void set_data(const Eigen::VectorXd &data) override
Set the wrench data from an Eigen vector.
CartesianWrench clamped(double max_force, double max_torque, double force_noise_ratio=0, double torque_noise_ratio=0) const
Return the clamped wrench.
std::vector< double > norms(const CartesianStateVariable &state_variable_type=CartesianStateVariable::WRENCH) const override
Compute the norms of the state variable specified by the input type (default is full wrench)
CartesianWrench copy() const
Return a copy of the CartesianWrench.
void clamp(double max_force, double max_torque, double force_noise_ratio=0, double torque_noise_ratio=0)
Clamp inplace the magnitude of the wrench to the values in argument.
static CartesianWrench Random(const std::string &name, const std::string &reference="world")
Constructor for a random wrench.
virtual void set_reference_frame(const std::string &reference_frame)
Setter of the reference frame.
virtual bool is_compatible(const State &state) const override
Check if the state is compatible for operations with the state given as argument.
const std::string & get_reference_frame() const
Getter of the reference frame as const reference.
Abstract class to represent a state.
Definition: State.hpp:25
double dist(const CartesianState &s1, const CartesianState &s2, const CartesianStateVariable &state_variable_type=CartesianStateVariable::ALL)
compute the distance between two CartesianStates