Control Libraries 7.4.0
Loading...
Searching...
No Matches
Model.hpp
1#pragma once
2
3#include <string>
4#include <vector>
5#include <OsqpEigen/OsqpEigen.h>
6#include <pinocchio/algorithm/crba.hpp>
7#include <pinocchio/algorithm/rnea.hpp>
8#include <pinocchio/multibody/data.hpp>
9#include <pinocchio/parsers/urdf.hpp>
10#include <state_representation/parameters/Parameter.hpp>
11#include <state_representation/parameters/ParameterInterface.hpp>
12#include <state_representation/space/Jacobian.hpp>
13#include <state_representation/space/joint/JointState.hpp>
14#include <state_representation/space/cartesian/CartesianState.hpp>
15
16using namespace std::chrono_literals;
17
22namespace robot_model {
33 double damp = 1e-6;
34 double alpha = 0.5;
35 double gamma = 0.8;
36 double margin = 0.07;
37 double tolerance = 1e-3;
38 unsigned int max_number_of_iterations = 1000;
39};
40
50 double alpha = 0.1;
51 double proportional_gain = 1.0;
52 double linear_velocity_limit = 2.0;
53 double angular_velocity_limit = 2.0;
54 std::chrono::nanoseconds dt = 1000ns;
55};
56
62class Model {
63private:
64 // @format:off
65 std::shared_ptr<state_representation::Parameter<std::string>> robot_name_;
66 std::shared_ptr<state_representation::Parameter<std::string>> urdf_path_;
67 std::vector<std::string> frames_;
68 pinocchio::Model robot_model_;
69 pinocchio::Data robot_data_;
70 OsqpEigen::Solver solver_;
71 Eigen::SparseMatrix<double> hessian_;
72 Eigen::VectorXd gradient_;
73 Eigen::SparseMatrix<double> constraint_matrix_;
74 Eigen::VectorXd lower_bound_constraints_;
75 Eigen::VectorXd upper_bound_constraints_;
76 // @format:on
80 void init_model();
81
85 bool init_qp_solver();
86
92 std::vector<unsigned int> get_frame_ids(const std::vector<std::string>& frames);
93
99 unsigned int get_frame_id(const std::string& frame);
100
107 state_representation::Jacobian compute_jacobian(const state_representation::JointPositions& joint_positions,
108 unsigned int frame_id);
109
117 Eigen::MatrixXd compute_jacobian_time_derivative(const state_representation::JointPositions& joint_positions,
118 const state_representation::JointVelocities& joint_velocities,
119 unsigned int frame_id);
120
127 std::vector<state_representation::CartesianPose> forward_kinematics(const state_representation::JointPositions& joint_positions,
128 const std::vector<unsigned int>& frame_ids);
129
136 state_representation::CartesianPose forward_kinematics(const state_representation::JointPositions& joint_positions,
137 unsigned int frame_id);
138
146 static bool in_range(const Eigen::VectorXd& vector,
147 const Eigen::VectorXd& lower_limits,
148 const Eigen::VectorXd& upper_limits);
149
157 static Eigen::VectorXd clamp_in_range(const Eigen::VectorXd& vector,
158 const Eigen::VectorXd& lower_limits,
159 const Eigen::VectorXd& upper_limits);
160
167 Eigen::MatrixXd cwln_weighted_matrix(const state_representation::JointPositions& joint_positions, double margin);
168
175 Eigen::VectorXd cwln_repulsive_potential_field(const state_representation::JointPositions& joint_positions,
176 double margin);
177
184 void check_inverse_velocity_arguments(const std::vector<state_representation::CartesianTwist>& cartesian_twists,
185 const state_representation::JointPositions& joint_positions,
186 const std::vector<std::string>& frames);
187
188public:
192 explicit Model(const std::string& robot_name, const std::string& urdf_path);
193
198 Model(const Model& model);
199
205 friend void swap(Model& model1, Model& model2);
206
212 Model& operator=(const Model& Model);
213
221 static bool create_urdf_from_string(const std::string& urdf_string, const std::string& desired_path);
222
227 const std::string& get_robot_name() const;
228
233 void set_robot_name(const std::string& robot_name);
234
239 const std::string& get_urdf_path() const;
240
245 unsigned int get_number_of_joints() const;
246
251 std::vector<std::string> get_joint_frames() const;
252
257 std::vector<std::string> get_frames() const;
258
263 const std::string& get_base_frame() const;
264
269 Eigen::Vector3d get_gravity_vector() const;
270
275 void set_gravity_vector(const Eigen::Vector3d& gravity);
276
281 const pinocchio::Model& get_pinocchio_model() const;
282
289 state_representation::Jacobian compute_jacobian(const state_representation::JointPositions& joint_positions,
290 const std::string& frame = "");
291
299 Eigen::MatrixXd compute_jacobian_time_derivative(const state_representation::JointPositions& joint_positions,
300 const state_representation::JointVelocities& joint_velocities,
301 const std::string& frame = "");
302
308 Eigen::MatrixXd compute_inertia_matrix(const state_representation::JointPositions& joint_positions);
309
317
323 Eigen::MatrixXd compute_coriolis_matrix(const state_representation::JointState& joint_state);
324
332
339
346 std::vector<state_representation::CartesianPose> forward_kinematics(const state_representation::JointPositions& joint_positions,
347 const std::vector<std::string>& frames);
348
355 state_representation::CartesianPose forward_kinematics(const state_representation::JointPositions& joint_positions,
356 const std::string& frame = "");
357
368 const std::string& frame = "");
369
380 const state_representation::JointPositions& joint_positions,
382 const std::string& frame = "");
383
390 std::vector<state_representation::CartesianTwist> forward_velocity(const state_representation::JointState& joint_state,
391 const std::vector<std::string>& frames);
392
400 const std::string& frame = "");
401
411 state_representation::JointVelocities inverse_velocity(const std::vector<state_representation::CartesianTwist>& cartesian_twists,
412 const state_representation::JointPositions& joint_positions,
413 const std::vector<std::string>& frames,
414 const double dls_lambda = 0.0);
415
428 const state_representation::JointPositions& joint_positions,
429 const std::string& frame = "",
430 const double dls_lambda = 0.0);
431
442 state_representation::JointVelocities inverse_velocity(const std::vector<state_representation::CartesianTwist>& cartesian_twists,
443 const state_representation::JointPositions& joint_positions,
444 const QPInverseVelocityParameters& parameters,
445 const std::vector<std::string>& frames);
446
459 const state_representation::JointPositions& joint_positions,
460 const QPInverseVelocityParameters& parameters,
461 const std::string& frame = "");
462
466 void print_qp_problem();
467
473 bool in_range(const state_representation::JointPositions& joint_positions) const;
474
480 bool in_range(const state_representation::JointVelocities& joint_velocities) const;
481
487 bool in_range(const state_representation::JointTorques& joint_torques) const;
488
495 bool in_range(const state_representation::JointState& joint_state) const;
496
503 state_representation::JointState clamp_in_range(const state_representation::JointState& joint_state) const;
504};
505
506inline void swap(Model& model1, Model& model2) {
507 std::swap(model1.robot_name_, model2.robot_name_);
508 std::swap(model1.urdf_path_, model2.urdf_path_);
509 // initialize both models
510 model1.init_model();
511 model2.init_model();
512}
513
514inline Model& Model::operator=(const Model& model) {
515 Model tmp(model);
516 swap(*this, tmp);
517 return *this;
518}
519
520
521inline const std::string& Model::get_robot_name() const {
522 return this->robot_name_->get_value();
523}
524
525inline void Model::set_robot_name(const std::string& robot_name) {
526 this->robot_name_->set_value(robot_name);
527}
528
529inline const std::string& Model::get_urdf_path() const {
530 return this->urdf_path_->get_value();
531}
532
533inline unsigned int Model::get_number_of_joints() const {
534 return this->robot_model_.nq;
535}
536
537inline std::vector<std::string> Model::get_joint_frames() const {
538 // model contains a first joint called universe that needs to be discarded
539 std::vector<std::string> joint_frames(this->robot_model_.names.begin() + 1, this->robot_model_.names.end());
540 return joint_frames;
541}
542
543inline const std::string& Model::get_base_frame() const {
544 return this->frames_.front();
545}
546
547inline std::vector<std::string> Model::get_frames() const {
548 return this->frames_;
549}
550
551inline Eigen::Vector3d Model::get_gravity_vector() const {
552 return this->robot_model_.gravity.linear();
553}
554
555inline void Model::set_gravity_vector(const Eigen::Vector3d& gravity) {
556 this->robot_model_.gravity.linear(gravity);
557}
558
559inline const pinocchio::Model& Model::get_pinocchio_model() const {
560 return this->robot_model_;
561}
562}// namespace robot_model
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:533
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
Model & operator=(const Model &Model)
Copy assignment operator that have to be defined due to the custom assignment operator.
Definition Model.hpp:514
Eigen::Vector3d get_gravity_vector() const
Getter of the gravity vector.
Definition Model.hpp:551
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, const double dls_lambda=0.0)
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:543
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:555
Eigen::MatrixXd compute_inertia_matrix(const state_representation::JointPositions &joint_positions)
Compute the Inertia matrix from a given joint positions.
Definition Model.cpp:185
friend void swap(Model &model1, Model &model2)
Swap the values of the two Model.
Definition Model.hpp:506
const std::string & get_urdf_path() const
Getter of the URDF path.
Definition Model.hpp:529
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:547
void set_robot_name(const std::string &robot_name)
Setter of the robot name.
Definition Model.hpp:525
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:529
const pinocchio::Model & get_pinocchio_model() const
Getter of the pinocchio model.
Definition Model.hpp:559
const std::string & get_robot_name() const
Getter of the robot name.
Definition Model.hpp:521
std::vector< std::string > get_joint_frames() const
Getter of the joint frames from the model.
Definition Model.hpp:537
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 Cartesian pose in Cartesian space as 3D position and quaternion based orientation.
Class to define twist in Cartesian space as 3D linear and angular velocity vectors.
Class to define a robot Jacobian matrix.
Definition Jacobian.hpp:21
Class to define positions of the joints.
Class to define a state in joint space.
Class to define torques of the joints.
Class to define velocities of the joints.
Robot kinematics and dynamics.
void swap(Model &model1, Model &model2)
Definition Model.hpp:506
parameters for the inverse kinematics function
Definition Model.hpp:32
parameters for the inverse velocity kinematics function
Definition Model.hpp:49