Control Libraries 6.3.4
|
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. More... | |
Model (const Model &model) | |
Copy constructor. More... | |
Model & | operator= (const Model &Model) |
Copy assignment operator that have to be defined due to the custom assignment operator. More... | |
const std::string & | get_robot_name () const |
Getter of the robot name. More... | |
void | set_robot_name (const std::string &robot_name) |
Setter of the robot name. More... | |
const std::string & | get_urdf_path () const |
Getter of the URDF path. More... | |
unsigned int | get_number_of_joints () const |
Getter of the number of joints. More... | |
std::vector< std::string > | get_joint_frames () const |
Getter of the joint frames from the model. More... | |
std::vector< std::string > | get_frames () const |
Getter of the frames from the model. More... | |
const std::string & | get_base_frame () const |
Getter of the base frame of the robot. More... | |
Eigen::Vector3d | get_gravity_vector () const |
Getter of the gravity vector. More... | |
void | set_gravity_vector (const Eigen::Vector3d &gravity) |
Setter of the gravity vector. More... | |
const pinocchio::Model & | get_pinocchio_model () const |
Getter of the pinocchio model. More... | |
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. More... | |
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. More... | |
Eigen::MatrixXd | compute_inertia_matrix (const state_representation::JointPositions &joint_positions) |
Compute the Inertia matrix from a given joint positions. More... | |
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. More... | |
Eigen::MatrixXd | compute_coriolis_matrix (const state_representation::JointState &joint_state) |
Compute the Coriolis matrix from a given joint state. More... | |
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. More... | |
state_representation::JointTorques | compute_gravity_torques (const state_representation::JointPositions &joint_positions) |
Compute the gravity torques. More... | |
std::vector< state_representation::CartesianPose > | 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. More... | |
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. More... | |
state_representation::JointPositions | inverse_kinematics (const state_representation::CartesianPose &cartesian_pose, const InverseKinematicsParameters ¶meters=InverseKinematicsParameters(), const std::string &frame="") |
Compute the inverse kinematics, i.e. joint positions from the pose of the end-effector in an iterative manner. More... | |
state_representation::JointPositions | inverse_kinematics (const state_representation::CartesianPose &cartesian_pose, const state_representation::JointPositions &joint_positions, const InverseKinematicsParameters ¶meters=InverseKinematicsParameters(), const std::string &frame="") |
Compute the inverse kinematics, i.e. joint positions from the pose of the end-effector. More... | |
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. More... | |
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. More... | |
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 parameter using the Jacobian. More... | |
state_representation::JointVelocities | inverse_velocity (const state_representation::CartesianTwist &cartesian_twist, const state_representation::JointPositions &joint_positions, const std::string &frame="") |
Compute the inverse velocity kinematics, i.e. joint velocities from the twist of the end-effector using the Jacobian. More... | |
state_representation::JointVelocities | inverse_velocity (const std::vector< state_representation::CartesianTwist > &cartesian_twists, const state_representation::JointPositions &joint_positions, const QPInverseVelocityParameters ¶meters, 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. More... | |
state_representation::JointVelocities | inverse_velocity (const state_representation::CartesianTwist &cartesian_twist, const state_representation::JointPositions &joint_positions, const QPInverseVelocityParameters ¶meters, 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. More... | |
void | print_qp_problem () |
Helper function to print the qp_problem (for debugging) More... | |
bool | in_range (const state_representation::JointPositions &joint_positions) const |
Check if the joint positions are inside the limits provided by the model. More... | |
bool | in_range (const state_representation::JointVelocities &joint_velocities) const |
Check if the joint velocities are inside the limits provided by the model. More... | |
bool | in_range (const state_representation::JointTorques &joint_torques) const |
Check if the joint torques are inside the limits provided by the model. More... | |
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. More... | |
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. More... | |
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) More... | |
Friends | |
void | swap (Model &model1, Model &model2) |
Swap the values of the two Model. More... | |
The Model class is a wrapper around pinocchio dynamic computation library with state_representation encapsulations.
|
explicit |
robot_model::Model::Model | ( | const Model & | model | ) |
state_representation::JointState robot_model::Model::clamp_in_range | ( | const state_representation::JointState & | joint_state | ) | const |
Eigen::MatrixXd robot_model::Model::compute_coriolis_matrix | ( | const state_representation::JointState & | joint_state | ) |
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.
joint_state | containing the joint positions & velocities values of the robot |
state_representation::JointTorques robot_model::Model::compute_gravity_torques | ( | const state_representation::JointPositions & | joint_positions | ) |
Eigen::MatrixXd robot_model::Model::compute_inertia_matrix | ( | const state_representation::JointPositions & | joint_positions | ) |
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.
joint_state | containing the joint positions and accelerations values of the robot |
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.
joint_positions | containing the joint positions of the robot |
frame | name of the frame at which to compute the Jacobian, if empty computed for the last frame |
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.
joint_positions | containing the joint positions of the robot |
joint_velocities | containing the joint positions of the robot |
frame | name of the frame at which to compute the Jacobian, if empty computed for the last frame |
|
static |
Creates a URDF file with desired path and name from a string (possibly the robot description string from the ROS parameter server)
urdf_string | string containing the URDF description of the robot |
desired_path | desired path and name of the created URDF file as string |
state_representation::CartesianPose robot_model::Model::forward_kinematics | ( | const state_representation::JointPositions & | joint_positions, |
const std::string & | frame = "" |
||
) |
std::vector< state_representation::CartesianPose > robot_model::Model::forward_kinematics | ( | const state_representation::JointPositions & | joint_positions, |
const std::vector< std::string > & | frames | ||
) |
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.
joint_state | the joint state of the robot with positions to compute the Jacobian and velocities for the twist |
frame | name of the frame at which to compute the twist |
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.
joint_state | the joint state of the robot with positions to compute the Jacobian and velocities for the twist |
frames | name of the frames at which to compute the twist |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
bool robot_model::Model::in_range | ( | const state_representation::JointPositions & | joint_positions | ) | const |
bool robot_model::Model::in_range | ( | const state_representation::JointState & | joint_state | ) | const |
bool robot_model::Model::in_range | ( | const state_representation::JointTorques & | joint_torques | ) | const |
bool robot_model::Model::in_range | ( | const state_representation::JointVelocities & | joint_velocities | ) | const |
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.
cartesian_pose | containing the desired pose of the end-effector |
parameters | parameters of the inverse kinematics algorithm (default is default values of the InverseKinematicsParameters structure) |
frame | name of the frame at which to extract the pose |
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.
cartesian_pose | containing the desired pose of the end-effector |
joint_positions | current state of the robot containing the generalized position |
parameters | parameters of the inverse kinematics algorithm (default is default values of the InverseKinematicsParameters structure) |
frame | name of the frame at which to extract the pose |
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.
cartesian_twist | containing the twist of the end-effector |
joint_positions | current joint positions, used to compute the Jacobian matrix |
joint_positions | current joint positions, used to compute the Jacobian matrix |
parameters | parameters of the inverse velocity kinematics algorithm (default is default values of the QPInverseVelocityParameters structure) |
frame | name of the frame at which to compute the twist |
state_representation::JointVelocities robot_model::Model::inverse_velocity | ( | const state_representation::CartesianTwist & | cartesian_twist, |
const state_representation::JointPositions & | joint_positions, | ||
const std::string & | frame = "" |
||
) |
Compute the inverse velocity kinematics, i.e. joint velocities from the twist of the end-effector using the Jacobian.
cartesian_twist | containing the twist of the end-effector |
joint_positions | current joint positions, used to compute the Jacobian matrix |
frame | name of the frame at which to compute the twist |
parameters | parameters of the inverse velocity kinematics algorithm (default is default values of the QPInverseVelocityParameters structure) |
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.
cartesian_twists | vector of twist |
joint_positions | current joint positions, used to compute the jacobian matrix |
parameters | parameters of the inverse velocity kinematics algorithm (default is default values of the QPInverseVelocityParameters structure) |
frames | names of the frames at which to compute the twists |
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 | ||
) |
Compute the inverse velocity kinematics, i.e. joint velocities from the velocities of the frames in parameter using the Jacobian.
cartesian_twists | vector of twist |
joint_positions | current joint positions, used to compute the Jacobian matrix |
frames | names of the frames at which to compute the twists |
void robot_model::Model::print_qp_problem | ( | ) |
|
inline |
|
inline |