Control Libraries 7.4.0
Loading...
Searching...
No Matches
Public Member Functions | Static Public Member Functions | Friends | List of all members
robot_model::Model Class Reference

The Model class is a wrapper around pinocchio dynamic computation library with state_representation encapsulations. More...

#include <Model.hpp>

Public Member Functions

 Model (const std::string &robot_name, const std::string &urdf_path)
 Constructor with robot name and path to URDF file.
 
 Model (const Model &model)
 Copy constructor.
 
Modeloperator= (const Model &Model)
 Copy assignment operator that have to be defined due to the custom assignment operator.
 
const std::string & get_robot_name () const
 Getter of the robot name.
 
void set_robot_name (const std::string &robot_name)
 Setter of the robot name.
 
const std::string & get_urdf_path () const
 Getter of the URDF path.
 
unsigned int get_number_of_joints () const
 Getter of the number of joints.
 
std::vector< std::string > get_joint_frames () const
 Getter of the joint frames from the model.
 
std::vector< std::string > get_frames () const
 Getter of the frames from the model.
 
const std::string & get_base_frame () const
 Getter of the base frame of the robot.
 
Eigen::Vector3d get_gravity_vector () const
 Getter of the gravity vector.
 
void set_gravity_vector (const Eigen::Vector3d &gravity)
 Setter of the gravity vector.
 
const pinocchio::Model & get_pinocchio_model () const
 Getter of the pinocchio model.
 
state_representation::Jacobian compute_jacobian (const state_representation::JointPositions &joint_positions, const std::string &frame="")
 Compute the Jacobian from a given joint state at the frame given in parameter.
 
Eigen::MatrixXd compute_jacobian_time_derivative (const state_representation::JointPositions &joint_positions, const state_representation::JointVelocities &joint_velocities, const std::string &frame="")
 Compute the time derivative of the Jacobian from given joint positions and velocities at the frame in parameter.
 
Eigen::MatrixXd compute_inertia_matrix (const state_representation::JointPositions &joint_positions)
 Compute the Inertia matrix from a given joint positions.
 
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. Joint positions are needed as well for computations of the inertia matrix.
 
Eigen::MatrixXd compute_coriolis_matrix (const state_representation::JointState &joint_state)
 Compute the Coriolis matrix from a given joint state.
 
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 the result as a JointTorques.
 
state_representation::JointTorques compute_gravity_torques (const state_representation::JointPositions &joint_positions)
 Compute the gravity torques.
 
std::vector< state_representation::CartesianPoseforward_kinematics (const state_representation::JointPositions &joint_positions, const std::vector< std::string > &frames)
 Compute the forward kinematics, i.e. the pose of certain frames from the joint positions.
 
state_representation::CartesianPose forward_kinematics (const state_representation::JointPositions &joint_positions, const std::string &frame="")
 Compute the forward kinematics, i.e. the pose of the frame from the joint positions.
 
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 iterative manner.
 
state_representation::JointPositions inverse_kinematics (const state_representation::CartesianPose &cartesian_pose, const state_representation::JointPositions &joint_positions, const InverseKinematicsParameters &parameters=InverseKinematicsParameters(), const std::string &frame="")
 Compute the inverse kinematics, i.e. joint positions from the pose of the end-effector.
 
std::vector< state_representation::CartesianTwistforward_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.
 
state_representation::CartesianTwist forward_velocity (const state_representation::JointState &joint_state, const std::string &frame="")
 Compute the forward velocity kinematics, i.e. the twist of the end-effector from the joint velocities.
 
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 parameter using the Jacobian.
 
state_representation::JointVelocities inverse_velocity (const state_representation::CartesianTwist &cartesian_twist, const state_representation::JointPositions &joint_positions, const std::string &frame="", const double dls_lambda=0.0)
 Compute the inverse velocity kinematics, i.e. joint velocities from the twist of the end-effector using the Jacobian.
 
state_representation::JointVelocities inverse_velocity (const std::vector< state_representation::CartesianTwist > &cartesian_twists, const state_representation::JointPositions &joint_positions, const QPInverseVelocityParameters &parameters, const std::vector< std::string > &frames)
 Compute the inverse velocity kinematics, i.e. joint velocities from the velocities of the frames in parameter using the QP optimization method.
 
state_representation::JointVelocities inverse_velocity (const state_representation::CartesianTwist &cartesian_twist, const state_representation::JointPositions &joint_positions, const QPInverseVelocityParameters &parameters, const std::string &frame="")
 Compute the inverse velocity kinematics, i.e. joint velocities from the twist of the end-effector using the QP optimization method.
 
void print_qp_problem ()
 Helper function to print the qp_problem (for debugging)
 
bool in_range (const state_representation::JointPositions &joint_positions) const
 Check if the joint positions are inside the limits provided by the model.
 
bool in_range (const state_representation::JointVelocities &joint_velocities) const
 Check if the joint velocities are inside the limits provided by the model.
 
bool in_range (const state_representation::JointTorques &joint_torques) const
 Check if the joint torques are inside the limits provided by the model.
 
bool in_range (const state_representation::JointState &joint_state) const
 Check if the joint state variables (positions, velocities & torques) are inside the limits provided by the model.
 
state_representation::JointState clamp_in_range (const state_representation::JointState &joint_state) const
 Clamp the joint state variables (positions, velocities & torques) according to the limits provided by the model.
 

Static Public Member Functions

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 from the ROS parameter server)
 

Friends

void swap (Model &model1, Model &model2)
 Swap the values of the two Model.
 

Detailed Description

The Model class is a wrapper around pinocchio dynamic computation library with state_representation encapsulations.

Definition at line 62 of file Model.hpp.

Constructor & Destructor Documentation

◆ Model() [1/2]

robot_model::Model::Model ( const std::string &  robot_name,
const std::string &  urdf_path 
)
explicit

Constructor with robot name and path to URDF file.

Definition at line 10 of file Model.cpp.

◆ Model() [2/2]

robot_model::Model::Model ( const Model model)

Copy constructor.

Parameters
modelthe model to copy

Definition at line 16 of file Model.cpp.

Member Function Documentation

◆ clamp_in_range()

state_representation::JointState robot_model::Model::clamp_in_range ( const state_representation::JointState joint_state) const

Clamp the joint state variables (positions, velocities & torques) according to the limits provided by the model.

Parameters
joint_statethe joint state to be clamped
Returns
the clamped joint states

Definition at line 581 of file Model.cpp.

◆ compute_coriolis_matrix()

Eigen::MatrixXd robot_model::Model::compute_coriolis_matrix ( const state_representation::JointState joint_state)

Compute the Coriolis matrix from a given joint state.

Parameters
joint_statecontaining the joint positions & velocities values of the robot
Returns
the Coriolis matrix

Definition at line 201 of file Model.cpp.

◆ compute_coriolis_torques()

state_representation::JointTorques robot_model::Model::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 the result as a JointTorques.

Parameters
joint_statecontaining the joint positions & velocities values of the robot
Returns
the Coriolis torques as a JointTorques

Definition at line 209 of file Model.cpp.

◆ compute_gravity_torques()

state_representation::JointTorques robot_model::Model::compute_gravity_torques ( const state_representation::JointPositions joint_positions)

Compute the gravity torques.

Parameters
joint_positionscontaining the joint positions of the robot
Returns
the gravity torque as a JointTorques

Definition at line 217 of file Model.cpp.

◆ compute_inertia_matrix()

Eigen::MatrixXd robot_model::Model::compute_inertia_matrix ( const state_representation::JointPositions joint_positions)

Compute the Inertia matrix from a given joint positions.

Parameters
joint_positionscontaining the joint positions values of the robot
Returns
the inertia matrix

Definition at line 185 of file Model.cpp.

◆ compute_inertia_torques()

state_representation::JointTorques robot_model::Model::compute_inertia_torques ( const state_representation::JointState joint_state)

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.

Parameters
joint_statecontaining the joint positions and accelerations values of the robot
Returns
the inertia torques as a JointTorques

Definition at line 194 of file Model.cpp.

◆ compute_jacobian()

state_representation::Jacobian robot_model::Model::compute_jacobian ( const state_representation::JointPositions joint_positions,
const std::string &  frame = "" 
)

Compute the Jacobian from a given joint state at the frame given in parameter.

Parameters
joint_positionscontaining the joint positions of the robot
framename of the frame at which to compute the Jacobian, if empty computed for the last frame
Returns
the Jacobian matrix

Definition at line 148 of file Model.cpp.

◆ compute_jacobian_time_derivative()

Eigen::MatrixXd robot_model::Model::compute_jacobian_time_derivative ( const state_representation::JointPositions joint_positions,
const state_representation::JointVelocities joint_velocities,
const std::string &  frame = "" 
)

Compute the time derivative of the Jacobian from given joint positions and velocities at the frame in parameter.

Parameters
joint_positionscontaining the joint positions of the robot
joint_velocitiescontaining the joint positions of the robot
framename of the frame at which to compute the Jacobian, if empty computed for the last frame
Returns
the time derivative of Jacobian matrix

Definition at line 178 of file Model.cpp.

◆ create_urdf_from_string()

bool robot_model::Model::create_urdf_from_string ( const std::string &  urdf_string,
const std::string &  desired_path 
)
static

Creates a URDF file with desired path and name from a string (possibly the robot description string from the ROS parameter server)

Parameters
urdf_stringstring containing the URDF description of the robot
desired_pathdesired path and name of the created URDF file as string
Returns
bool if operation was successful

Definition at line 22 of file Model.cpp.

◆ forward_kinematics() [1/2]

state_representation::CartesianPose robot_model::Model::forward_kinematics ( const state_representation::JointPositions joint_positions,
const std::string &  frame = "" 
)

Compute the forward kinematics, i.e. the pose of the frame from the joint positions.

Parameters
joint_positionsthe joint state of the robot
framename of the frame at which to extract the pose
Returns
the pose of the desired frame

Definition at line 253 of file Model.cpp.

◆ forward_kinematics() [2/2]

std::vector< state_representation::CartesianPose > robot_model::Model::forward_kinematics ( const state_representation::JointPositions joint_positions,
const std::vector< std::string > &  frames 
)

Compute the forward kinematics, i.e. the pose of certain frames from the joint positions.

Parameters
joint_positionsthe joint state of the robot
framesnames of the frames at which to extract the poses
Returns
the pose of desired frames

Definition at line 259 of file Model.cpp.

◆ forward_velocity() [1/2]

state_representation::CartesianTwist robot_model::Model::forward_velocity ( const state_representation::JointState joint_state,
const std::string &  frame = "" 
)

Compute the forward velocity kinematics, i.e. the twist of the end-effector from the joint velocities.

Parameters
joint_statethe joint state of the robot with positions to compute the Jacobian and velocities for the twist
framename of the frame at which to compute the twist
Returns
the twist of the frame in parameter

Definition at line 372 of file Model.cpp.

◆ forward_velocity() [2/2]

std::vector< state_representation::CartesianTwist > robot_model::Model::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.

Parameters
joint_statethe joint state of the robot with positions to compute the Jacobian and velocities for the twist
framesname of the frames at which to compute the twist
Returns
the twists of the frames in parameter

Definition at line 362 of file Model.cpp.

◆ get_base_frame()

const std::string & robot_model::Model::get_base_frame ( ) const
inline

Getter of the base frame of the robot.

Returns
the base frame

Definition at line 543 of file Model.hpp.

◆ get_frames()

std::vector< std::string > robot_model::Model::get_frames ( ) const
inline

Getter of the frames from the model.

Returns
the frame names

Definition at line 547 of file Model.hpp.

◆ get_gravity_vector()

Eigen::Vector3d robot_model::Model::get_gravity_vector ( ) const
inline

Getter of the gravity vector.

Returns
Eigen::Vector3d the gravity vector

Definition at line 551 of file Model.hpp.

◆ get_joint_frames()

std::vector< std::string > robot_model::Model::get_joint_frames ( ) const
inline

Getter of the joint frames from the model.

Returns
the joint frames

Definition at line 537 of file Model.hpp.

◆ get_number_of_joints()

unsigned int robot_model::Model::get_number_of_joints ( ) const
inline

Getter of the number of joints.

Returns
the number of joints

Definition at line 533 of file Model.hpp.

◆ get_pinocchio_model()

const pinocchio::Model & robot_model::Model::get_pinocchio_model ( ) const
inline

Getter of the pinocchio model.

Returns
the pinocchio model

Definition at line 559 of file Model.hpp.

◆ get_robot_name()

const std::string & robot_model::Model::get_robot_name ( ) const
inline

Getter of the robot name.

Returns
the robot name

Definition at line 521 of file Model.hpp.

◆ get_urdf_path()

const std::string & robot_model::Model::get_urdf_path ( ) const
inline

Getter of the URDF path.

Returns
the URDF path

Definition at line 529 of file Model.hpp.

◆ in_range() [1/4]

bool robot_model::Model::in_range ( const state_representation::JointPositions joint_positions) const

Check if the joint positions are inside the limits provided by the model.

Parameters
joint_positionsthe joint positions to check
Returns
true if the positions are inside their limits, false otherwise.

Definition at line 553 of file Model.cpp.

◆ in_range() [2/4]

bool robot_model::Model::in_range ( const state_representation::JointState joint_state) const

Check if the joint state variables (positions, velocities & torques) are inside the limits provided by the model.

Parameters
joint_statethe joint state to check
Returns
true if the state variables are inside the limits, false otherwise.

Definition at line 569 of file Model.cpp.

◆ in_range() [3/4]

bool robot_model::Model::in_range ( const state_representation::JointTorques joint_torques) const

Check if the joint torques are inside the limits provided by the model.

Parameters
joint_torquesthe joint torques to check
Returns
true if the torques are inside their limits, false otherwise.

Definition at line 565 of file Model.cpp.

◆ in_range() [4/4]

bool robot_model::Model::in_range ( const state_representation::JointVelocities joint_velocities) const

Check if the joint velocities are inside the limits provided by the model.

Parameters
joint_velocitiesthe joint velocities to check
Returns
true if the velocities are inside their limits, false otherwise.

Definition at line 559 of file Model.cpp.

◆ inverse_kinematics() [1/2]

state_representation::JointPositions robot_model::Model::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 iterative manner.

Parameters
cartesian_posecontaining the desired pose of the end-effector
parametersparameters of the inverse kinematics algorithm (default is default values of the InverseKinematicsParameters structure)
framename of the frame at which to extract the pose
Returns
the joint positions of the robot

Definition at line 353 of file Model.cpp.

◆ inverse_kinematics() [2/2]

state_representation::JointPositions robot_model::Model::inverse_kinematics ( const state_representation::CartesianPose cartesian_pose,
const state_representation::JointPositions joint_positions,
const InverseKinematicsParameters parameters = InverseKinematicsParameters(),
const std::string &  frame = "" 
)

Compute the inverse kinematics, i.e. joint positions from the pose of the end-effector.

Parameters
cartesian_posecontaining the desired pose of the end-effector
joint_positionscurrent state of the robot containing the generalized position
parametersparameters of the inverse kinematics algorithm (default is default values of the InverseKinematicsParameters structure)
framename of the frame at which to extract the pose
Returns
the joint positions of the robot

Definition at line 308 of file Model.cpp.

◆ inverse_velocity() [1/4]

state_representation::JointVelocities robot_model::Model::inverse_velocity ( const state_representation::CartesianTwist cartesian_twist,
const state_representation::JointPositions joint_positions,
const QPInverseVelocityParameters parameters,
const std::string &  frame = "" 
)

Compute the inverse velocity kinematics, i.e. joint velocities from the twist of the end-effector using the QP optimization method.

Parameters
cartesian_twistcontaining the twist of the end-effector
joint_positionscurrent joint positions, used to compute the Jacobian matrix
joint_positionscurrent joint positions, used to compute the Jacobian matrix
parametersparameters of the inverse velocity kinematics algorithm (default is default values of the QPInverseVelocityParameters structure)
framename of the frame at which to compute the twist
Returns
the joint velocities of the robot

Definition at line 518 of file Model.cpp.

◆ inverse_velocity() [2/4]

state_representation::JointVelocities robot_model::Model::inverse_velocity ( const state_representation::CartesianTwist cartesian_twist,
const state_representation::JointPositions joint_positions,
const std::string &  frame = "",
const double  dls_lambda = 0.0 
)

Compute the inverse velocity kinematics, i.e. joint velocities from the twist of the end-effector using the Jacobian.

Parameters
cartesian_twistcontaining the twist of the end-effector
joint_positionscurrent joint positions, used to compute the Jacobian matrix
framename of the frame at which to compute the twist
parametersparameters of the inverse velocity kinematics algorithm (default is default values of the QPInverseVelocityParameters structure)
dls_lambdadamped least square term
Returns
the joint velocities of the robot

Definition at line 437 of file Model.cpp.

◆ inverse_velocity() [3/4]

state_representation::JointVelocities robot_model::Model::inverse_velocity ( const std::vector< state_representation::CartesianTwist > &  cartesian_twists,
const state_representation::JointPositions joint_positions,
const QPInverseVelocityParameters parameters,
const std::vector< std::string > &  frames 
)

Compute the inverse velocity kinematics, i.e. joint velocities from the velocities of the frames in parameter using the QP optimization method.

Parameters
cartesian_twistsvector of twist
joint_positionscurrent joint positions, used to compute the jacobian matrix
parametersparameters of the inverse velocity kinematics algorithm (default is default values of the QPInverseVelocityParameters structure)
framesnames of the frames at which to compute the twists
Returns
the joint velocities of the robot

Definition at line 449 of file Model.cpp.

◆ inverse_velocity() [4/4]

state_representation::JointVelocities robot_model::Model::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 parameter using the Jacobian.

Parameters
cartesian_twistsvector of twist
joint_positionscurrent joint positions, used to compute the Jacobian matrix
framesnames of the frames at which to compute the twists
dls_lambdadamped least square term
Returns
the joint velocities of the robot

Definition at line 394 of file Model.cpp.

◆ operator=()

Model & robot_model::Model::operator= ( const Model Model)
inline

Copy assignment operator that have to be defined due to the custom assignment operator.

Parameters
modelthe model with value to assign
Returns
reference to the current model with new values

Definition at line 514 of file Model.hpp.

◆ print_qp_problem()

void robot_model::Model::print_qp_problem ( )

Helper function to print the qp_problem (for debugging)

Definition at line 529 of file Model.cpp.

◆ set_gravity_vector()

void robot_model::Model::set_gravity_vector ( const Eigen::Vector3d &  gravity)
inline

Setter of the gravity vector.

Parameters
gravitythe gravity vector

Definition at line 555 of file Model.hpp.

◆ set_robot_name()

void robot_model::Model::set_robot_name ( const std::string &  robot_name)
inline

Setter of the robot name.

Parameters
robot_namethe new value of the robot name

Definition at line 525 of file Model.hpp.

Friends And Related Symbol Documentation

◆ swap

void swap ( Model model1,
Model model2 
)
friend

Swap the values of the two Model.

Parameters
model1Model to be swapped with 2
model2Model to be swapped with 1

Definition at line 506 of file Model.hpp.


The documentation for this class was generated from the following files: