Control Libraries 6.3.4
Loading...
Searching...
No Matches
bind_model.cpp
1#include "robot_model_bindings.h"
2
3#include <robot_model/Model.hpp>
4
5using namespace state_representation;
6
7void inverse_kinematics_parameters(py::module_& m) {
8 py::class_<InverseKinematicsParameters> c(m, "InverseKinematicsParameters");
9 c.def(py::init());
10 c.def_readwrite("damp", &InverseKinematicsParameters::damp);
11 c.def_readwrite("alpha", &InverseKinematicsParameters::alpha);
12 c.def_readwrite("gamma", &InverseKinematicsParameters::gamma);
13 c.def_readwrite("margin", &InverseKinematicsParameters::margin);
14 c.def_readwrite("tolerance", &InverseKinematicsParameters::tolerance);
15 c.def_readwrite("max_number_of_iterations", &InverseKinematicsParameters::max_number_of_iterations);
16}
17
18void qp_inverse_velocity_parameters(py::module_& m) {
19 py::class_<QPInverseVelocityParameters> c(m, "QPInverseVelocityParameters");
20 c.def(py::init());
21 c.def_readwrite("alpha", &QPInverseVelocityParameters::alpha);
22 c.def_readwrite("proportional_gain", &QPInverseVelocityParameters::proportional_gain);
23 c.def_readwrite("linear_velocity_limit", &QPInverseVelocityParameters::linear_velocity_limit);
24 c.def_readwrite("angular_velocity_limit", &QPInverseVelocityParameters::angular_velocity_limit);
25 c.def_readwrite("dt", &QPInverseVelocityParameters::dt);
26}
27
28void model(py::module_& m) {
29 m.def("create_urdf_from_string", &Model::create_urdf_from_string, "Creates a URDF file with desired path and name from a string (possibly the robot description string from the ROS parameter server).", "urdf_string"_a, "desired_path"_a);
30
31 py::class_<Model> c(m, "Model");
32
33 c.def(py::init<const std::string&, const std::string&>(), "Constructor with robot name and path to URDF file.", "robot_name"_a, "urdf_path"_a);
34 c.def(py::init<const Model&>(), "Copy constructor from another Model", "model"_a);
35
36 c.def("get_robot_name", &Model::get_robot_name, "Getter of the robot name.");
37 c.def("set_robot_name", &Model::set_robot_name, "Setter of the robot name.", "robot_name"_a);
38 c.def("get_urdf_path", &Model::get_urdf_path, "Getter of the URDF path.");
39 c.def("get_number_of_joints", &Model::get_number_of_joints, "Getter of the number of joints.");
40 c.def("get_joint_frames", &Model::get_joint_frames, "Getter of the joint frames of the model.");
41 c.def("get_frames", &Model::get_frames, "Getter of the frames of the model.");
42 c.def("get_base_frame", &Model::get_base_frame, "Getter of the base frame of the model.");
43 c.def("get_gravity_vector", &Model::get_gravity_vector, "Getter of the gravity vector.");
44 c.def("set_gravity_vector", &Model::set_gravity_vector, "Setter of the gravity vector.", "gravity"_a);
45// c.def("get_pinocchio_model", &Model::get_pinocchio_model, "Getter of the pinocchio model.");
46
47 c.def(
48 "compute_jacobian", py::overload_cast<const JointPositions&, const std::string&>(&Model::compute_jacobian),
49 "Compute the Jacobian from a given joint state at the frame given in parameter.", "joint_positions"_a, "frame"_a = std::string(""));
50 c.def(
51 "compute_jacobian_time_derivative", py::overload_cast<const JointPositions&, const JointVelocities&, const std::string&>(&Model::compute_jacobian_time_derivative),
52 "Compute the time derivative of the Jacobian from given joint positions and velocities at the frame in parameter.", "joint_positions"_a, "joint_velocities"_a, "frame"_a = std::string(""));
53 c.def("compute_inertia_matrix", py::overload_cast<const JointPositions&>(&Model::compute_inertia_matrix), "Compute the Inertia matrix from given joint positions.", "joint_positions"_a);
54 c.def(
55 "compute_inertia_torques", py::overload_cast<const JointState&>(&Model::compute_inertia_torques),
56 "Compute the Inertia torques, i.e the inertia matrix multiplied by the joint accelerations. Joint positions are needed as well for computations of the inertia matrix.", "joint_state"_a);
57 c.def("compute_coriolis_matrix", py::overload_cast<const JointState&>(&Model::compute_coriolis_matrix), "Compute the Coriolis matrix from a given joint state.", "joint_state"_a);
58 c.def(
59 "compute_coriolis_torques", py::overload_cast<const JointState&>(&Model::compute_coriolis_torques),
60 "Compute the Coriolis torques, i.e. the Coriolis matrix multiplied by the joint velocities and express the result as a JointTorques.", "joint_state"_a);
61 c.def("compute_gravity_torques", py::overload_cast<const JointPositions&>(&Model::compute_gravity_torques), "Compute the gravity torques.", "joint_positions"_a);
62
63 c.def("forward_kinematics", py::overload_cast<const JointPositions&, const std::vector<std::string>&>(&Model::forward_kinematics),
64 "Compute the forward kinematics, i.e. the pose of certain frames from the joint positions", "joint_positions"_a, "frames"_a);
65 c.def("forward_kinematics", py::overload_cast<const JointPositions&, const std::string&>(&Model::forward_kinematics),
66 "Compute the forward kinematics, i.e. the pose of the frame from the joint positions", "joint_positions"_a, "frame"_a = std::string(""));
67
68 c.def("inverse_kinematics", py::overload_cast<const CartesianPose&, const InverseKinematicsParameters&, const std::string&>(&Model::inverse_kinematics),
69 "Compute the inverse kinematics, i.e. joint positions from the pose of the end-effector in an iterative manner", "cartesian_pose"_a, "parameters"_a = InverseKinematicsParameters(), "frame"_a = std::string(""));
70 c.def("inverse_kinematics", py::overload_cast<const CartesianPose&, const JointPositions&, const InverseKinematicsParameters&, const std::string&>(&Model::inverse_kinematics),
71 " Compute the inverse kinematics, i.e. joint positions from the pose of the end-effector", "cartesian_pose"_a, "joint_positions"_a, "parameters"_a = InverseKinematicsParameters(), "frame"_a = std::string(""));
72
73 c.def("forward_velocity", py::overload_cast<const JointState&, const std::vector<std::string>&>(&Model::forward_velocity),
74 "Compute the forward velocity kinematics, i.e. the twist of certain frames from the joint states", "joint_state"_a, "frames"_a);
75 c.def("forward_velocity", py::overload_cast<const JointState&, const std::string&>(&Model::forward_velocity),
76 "Compute the forward velocity kinematics, i.e. the twist of the end-effector from the joint velocities", "joint_state"_a, "frame"_a = std::string(""));
77
78 c.def("inverse_velocity", py::overload_cast<const std::vector<CartesianTwist>&, const JointPositions&, const std::vector<std::string>&>(&Model::inverse_velocity),
79 "Compute the inverse velocity kinematics, i.e. joint velocities from the velocities of the frames in parameter the Jacobian", "cartesian_twists"_a, "joint_positions"_a, "frames"_a);
80 c.def("inverse_velocity", py::overload_cast<const CartesianTwist&, const JointPositions&, const std::string&>(&Model::inverse_velocity),
81 "Compute the inverse velocity kinematics, i.e. joint velocities from the twist of the end-effector using the Jacobian", "cartesian_twist"_a, "joint_positions"_a, "frame"_a = std::string(""));
82 c.def("inverse_velocity", py::overload_cast<const std::vector<CartesianTwist>&, const JointPositions&, const QPInverseVelocityParameters&, const std::vector<std::string>&>(&Model::inverse_velocity),
83 "Compute the inverse velocity kinematics, i.e. joint velocities from the velocities of the frames in parameter using the QP optimization method", "cartesian_twists"_a, "joint_positions"_a, "parameters"_a, "frames"_a);
84 c.def("inverse_velocity", py::overload_cast<const CartesianTwist&, const JointPositions&, const QPInverseVelocityParameters&, const std::string&>(&Model::inverse_velocity),
85 "Compute the inverse velocity kinematics, i.e. joint velocities from the twist of the end-effector using the QP optimization method", "cartesian_twist"_a, "joint_positions"_a, "parameters"_a, "frame"_a = std::string(""));
86
87 c.def("print_qp_problem", &Model::print_qp_problem, "Helper function to print the qp problem (for debugging).");
88 c.def("in_range", [](Model& self, const JointPositions& joint_positions) -> bool { return self.in_range(joint_positions); },
89 "Check if the joint positions are inside the limits provided by the model", "joint_positions"_a);
90 c.def("in_range", [](Model& self, const JointVelocities& joint_velocities) -> bool { return self.in_range(joint_velocities); },
91 "Check if the joint velocities are inside the limits provided by the model", "joint_velocities"_a);
92 c.def("in_range", [](Model& self, const JointTorques& joint_torques) -> bool { return self.in_range(joint_torques); },
93 "Check if the joint torques are inside the limits provided by the model", "joint_torques"_a);
94 c.def("in_range", [](Model& self, const JointState& joint_state) -> bool { return self.in_range(joint_state); },
95 "Check if the joint state variables (positions, velocities & torques) are inside the limits provided by the model", "joint_state"_a);
96
97 c.def("clamp_in_range", [](Model& self, const JointState& joint_state) -> JointState { return self.clamp_in_range(joint_state); },
98 "Clamp the joint state variables (positions, velocities & torques) according to the limits provided by the model", "joint_state"_a);
99}
100
101void bind_model(py::module_& m) {
102 inverse_kinematics_parameters(m);
103 qp_inverse_velocity_parameters(m);
104 model(m);
105}
The Model class is a wrapper around pinocchio dynamic computation library with state_representation e...
Definition: Model.hpp:62
unsigned int get_number_of_joints() const
Getter of the number of joints.
Definition: Model.hpp:529
std::vector< state_representation::CartesianTwist > forward_velocity(const state_representation::JointState &joint_state, const std::vector< std::string > &frames)
Compute the forward velocity kinematics, i.e. the twist of certain frames from the joint states.
Definition: Model.cpp:362
Eigen::Vector3d get_gravity_vector() const
Getter of the gravity vector.
Definition: Model.hpp:547
Eigen::MatrixXd compute_coriolis_matrix(const state_representation::JointState &joint_state)
Compute the Coriolis matrix from a given joint state.
Definition: Model.cpp:201
state_representation::JointTorques compute_inertia_torques(const state_representation::JointState &joint_state)
Compute the Inertia torques, i.e the inertia matrix multiplied by the joint accelerations....
Definition: Model.cpp:194
state_representation::JointVelocities inverse_velocity(const std::vector< state_representation::CartesianTwist > &cartesian_twists, const state_representation::JointPositions &joint_positions, const std::vector< std::string > &frames)
Compute the inverse velocity kinematics, i.e. joint velocities from the velocities of the frames in p...
Definition: Model.cpp:394
const std::string & get_base_frame() const
Getter of the base frame of the robot.
Definition: Model.hpp:539
state_representation::JointTorques compute_gravity_torques(const state_representation::JointPositions &joint_positions)
Compute the gravity torques.
Definition: Model.cpp:217
void set_gravity_vector(const Eigen::Vector3d &gravity)
Setter of the gravity vector.
Definition: Model.hpp:551
Eigen::MatrixXd compute_inertia_matrix(const state_representation::JointPositions &joint_positions)
Compute the Inertia matrix from a given joint positions.
Definition: Model.cpp:185
const std::string & get_urdf_path() const
Getter of the URDF path.
Definition: Model.hpp:525
state_representation::JointPositions inverse_kinematics(const state_representation::CartesianPose &cartesian_pose, const InverseKinematicsParameters &parameters=InverseKinematicsParameters(), const std::string &frame="")
Compute the inverse kinematics, i.e. joint positions from the pose of the end-effector in an iterativ...
Definition: Model.cpp:353
std::vector< std::string > get_frames() const
Getter of the frames from the model.
Definition: Model.hpp:543
void set_robot_name(const std::string &robot_name)
Setter of the robot name.
Definition: Model.hpp:521
state_representation::JointTorques compute_coriolis_torques(const state_representation::JointState &joint_state)
Compute the Coriolis torques, i.e. the Coriolis matrix multiplied by the joint velocities and express...
Definition: Model.cpp:209
void print_qp_problem()
Helper function to print the qp_problem (for debugging)
Definition: Model.cpp:510
const std::string & get_robot_name() const
Getter of the robot name.
Definition: Model.hpp:517
std::vector< std::string > get_joint_frames() const
Getter of the joint frames from the model.
Definition: Model.hpp:533
static bool create_urdf_from_string(const std::string &urdf_string, const std::string &desired_path)
Creates a URDF file with desired path and name from a string (possibly the robot description string f...
Definition: Model.cpp:22
Class to define a positions of the joints.
Class to define a state in joint space.
Definition: JointState.hpp:36
Class to define torques of the joints.
Class to define velocities of the joints.
Core state variables and objects.
parameters for the inverse kinematics function
Definition: Model.hpp:32
parameters for the inverse velocity kinematics function
Definition: Model.hpp:49