RML  1.0
Robotics Mathematical Library
Loading...
Searching...
No Matches
rml::RobotModel Class Reference

Robot Model class, to evaluate either mobile or fixed manipulators total transformation matrices and jacobians. More...

#include <RobotModel.h>

Public Member Functions

 RobotModel (Eigen::TransformationMatrix inertialF_T_bodyF, std::string bodyFrameID)
 Constructor for fixed robot model.
 
 RobotModel (Eigen::TransformationMatrix inertialF_T_bodyF, std::string bodyFrameID, Eigen::MatrixXd bodyF_JBodyFrame)
 Constructor for mobile robot model.
 
virtual ~RobotModel ()
 Default deconstructor.
 
auto Dof () const -> int
 Returns the number of total degrees of fredoom of the system composed (both of the base if mobile and the arms).
 
bool LoadArm (const std::shared_ptr< ArmModel > &arm, const Eigen::TransformationMatrix &bodyFrameToArm) noexcept(false)
 Loads an arm in the robot model.
 
auto BodyFrameID () const -> const std::string &
 Method to get the body Frame id.
 
void PositionOnInertialFrame (const Eigen::TransformationMatrix &inertialF_T_bodyF)
 Method to set the new body Frame position.
 
void AttachRigidBodyFrame (const std::string &frameID, const std::string &attachedFrameID, const Eigen::TransformationMatrix &frameToAttachID_T_frameID) noexcept(false)
 Method adding a rigid body frame attached to the input frame id .
 
bool CheckArm (const std::string &armID) const
 
auto IsMobile () const -> bool
 Method checking whether the robot model has a mobile body Frame .
 
Eigen::MatrixXd CartesianJacobian (const std::string &frameID) noexcept(false)
 Method computing the jacobian observed by the world frame and projected on the body Frame of the input frameID.
 
Eigen::MatrixXd JointSpaceJacobian (const std::string &armID) noexcept(false)
 Method computing the joint space jacobian of the input arm ID.
 
Eigen::MatrixXd ManipulabilityJacobian (const std::string &frameID) noexcept(false)
 Method computing the manipulability jacobian of the input arm ID.
 
double Manipulability (const std::string &frameID) noexcept(false)
 Method returning the manipulabity value for the jacobian related to the input frameID.
 
Eigen::MatrixXd DexterityJacobian (const std::string &frameID) noexcept(false)
 Method computing the dexterity jacobian of the input arm ID.
 
double Dexterity (const std::string &frameID) noexcept(false)
 Method returning the dexterity value for the jacobian related to the input frameID.
 
Eigen::TransformationMatrix TransformationMatrix (const std::string &frameID) noexcept(false)
 Method returning a transformation matrix of the robot model.
.
 
Eigen::TransformationMatrix TransformationMatrix (const std::string &frameID_j, const std::string &frameID_k)
 Method returing a transformation matrix from frameID_j to frameID_k, i.e. jTk.
.
 
const std::shared_ptr< ArmModel > & Arm (const std::string &ID) const noexcept(false)
 Method returning shared pointer to one of the loaded arm.
 
void PositionVector (Eigen::VectorXd &position) noexcept(false)
 Method setting the position vector of the whole robot model.
 
Eigen::VectorXd PositionVector ()
 Method returning the position vector of the whole robot model.
 
void VelocityVector (const Eigen::VectorXd &velocity) noexcept(false)
 Method setting the velocity vector of the whole robot model.
 
Eigen::VectorXd VelocityVector ()
 Method returning the velocity vector of the whole robot model.
 
Eigen::VectorXd AccelerationVector ()
 Method returning the acceleration vector of the whole robot model.
 
void AccelerationVector (const Eigen::VectorXd &acceleration) noexcept(false)
 Method setting the acceleration vector of the whole robot model.
 
void PositionVector (const std::string &partID, const Eigen::VectorXd &position) noexcept(false)
 Method setting the position vector for a robot part (joint postion for arm and cartesian position in case of mobile body Frame).
 
Eigen::VectorXd PositionVector (const std::string &partID) noexcept(false)
 Method returning the position of the input part (i.e. joint position for arm and cartesian position in case if of mobile body Frame)
 
void VelocityVector (const std::string &partID, const Eigen::VectorXd &velocity) noexcept(false)
 Method setting the velocity vector for a robot part (joint velocity for arm and cartesian velocity in case of mobile body Frame ).
 
Eigen::VectorXd VelocityVector (const std::string &partID) noexcept(false)
 GetVelocityVector Method returning the velocity of the input part (i.e. joints velocity for arm and cartesian velocity in case of mobile body Frame )
 
void AccelerationVector (const std::string &partID, const Eigen::VectorXd &acceleration) noexcept(false)
 Method setting the acceleration vector for a robot part (joints acceleration for arm and cartesian acceleration in case of mobile body Frame ).
 
Eigen::VectorXd AccelerationVector (const std::string &partID) noexcept(false)
 Method returning the position of the input part (i.e. joint acceleration for arm and cartesian acceleration in case of mobile body Frame)
 
void ControlVector (const Eigen::VectorXd &y) noexcept(false)
 Method setting the control vector of the whole robot model.
 
Eigen::VectorXd ControlVector (const std::string &partID) noexcept(false)
 Method returning the control vector of the input part of robot model.
 

Protected Member Functions

Eigen::MatrixXd ArmJacobian (const std::string &frameID) const noexcept(false)
 Method returning the isolated arm jacobian for the input frameID.
 
Eigen::Matrix6d BaseJacobian (const std::string &frameID) const
 Method returning the isolated body Frame jacobian for the input frameID.
 

Protected Attributes

std::shared_ptr< VehicleModelrobotBase_
 the model of the body Frame;
 
std::map< std::string, std::shared_ptr< ArmModel > > armsModel_
 map of the loaded map
 
std::unordered_map< std::string, Eigen::TransformationMatrixbodyFrameToArm_
 map of the transformation matrix from the arm bases to the body Frame
 
std::string bodyFrameID_
 ID of the body Frame.
 
Eigen::TransformationMatrix inertialF_T_bodyF_
 body Frame transformaion matrix
 
int DoF_
 total degrees of freedom of the robot
 
bool isMobileRobot_
 boolean stating wheter the robot is a mobile one
 

Detailed Description

Robot Model class, to evaluate either mobile or fixed manipulators total transformation matrices and jacobians.

This class provides a container for storing a multi-arm robot model. The robot could either be mobile one (hence characterized by a moving body Frame) or a static one (hence with a fixed body frame). Use the constructor a Jacobian for the body Frame is provided as input in the constructor).

In order to add arm to the robot the method LoadArm() is provided. It is in addition possible to add rigid body frames to the robot frames by using the method AttachedRigidBodyFrame().

The robot model contains an internal unique representation of the whole system, hence all the information about the robot model are given by organizing the vectors in an order a priori defined, where the moving body frame, if present, corresponds to the first 6 position of the vector. It is possible to obtain unified information about the robot position, velocity, acceleration and control by using the given methods (e.g. PositionVector() to know the position of the whole system) but methods to obtain information of a single part of the robot model are provided (e.g. PositionVector(partId) for the position of a part of the robot method, such function takes as input the id of the desired part).

The user must update the feedback for the arms and the mobile platform, if present, by using the methods PositionVector() = feedbackVector if the feedback for the whole robot are in a unique vector or PositionVector(partID) = part_feedbackVecotr if the data are separated into vectors. Similar methods are provided also with the purpose of setting the feedback in velocity and acceleration and control. For setting uniquely the body frame position, the dedicated method PositionOnInertialFrame() is provided.

By exploiting the methods provided in the ArmModel and VehicleModel class, the robot model is able to provide the transformation matrices and the jacobians for all the frames defined in the robot. For this purpose the methods TransformationMatrix() and CartesianJacobian() are provided. These methods take as input the id of the frame for which computing the matrices.

The id must be provieded according the following logic:

  • joint n-th: armID + rml::FrameID::Joint + "n"
  • rigidBody attached on arm: armID + "_" + "rigidBodyID"
  • rigid body attached on body frame: robotName + "_" + rigidBodyID

It is worth noticing that the transformation matrices are expressed wrt to the world frame meanwhile the jacobians are observed by the inertial frame and expressed wrt to the body frame. In addition the method TransformationMatrix() is provided in order to compute the transformation matrices in between the two frames identified by the input ids.
Furthermore the two methods JointSpaceJacobian() and ManipulabilityJacobian() are provided.
The former takes as input the armID and returns the related joint space jacobian. The latter takes as input a frame id and returns the related manipulability jacobian. In order to obtain the manipulability value for a frame the method Manipulability() must be used
It is worth noticing that the jacobians given by the RobotModel takes into account the degrees of freedom of the whole robot (hence of all the arms and of the moving platform, if present) in the aforementioned a priori defined order.

Example of frame id:

  • "youbot_Joint_0" for the first joint of the arm "youbot"
  • "youbot_tool0" for a rigid body frame "tool0" attached to the arm "youbot"

Constructor & Destructor Documentation

◆ RobotModel() [1/2]

rml::RobotModel::RobotModel ( Eigen::TransformationMatrix  inertialF_T_bodyF,
std::string  bodyFrameID 
)

Constructor for fixed robot model.

Parameters
[in]inertialF_T_bodyFtransformation matrix from the world frame to body Frame.
[in]bodyFrameIDid of the body Frame

◆ RobotModel() [2/2]

rml::RobotModel::RobotModel ( Eigen::TransformationMatrix  inertialF_T_bodyF,
std::string  bodyFrameID,
Eigen::MatrixXd  bodyF_JBodyFrame 
)

Constructor for mobile robot model.

Parameters
[in]inertialF_T_bodyFtransformation matrix from the world frame to body Frame.
[in]bodyFrameIDid of the body Frame
[in]JBodyFramejacobian of the bodyFrame in the body frame

◆ ~RobotModel()

virtual rml::RobotModel::~RobotModel ( )
virtual

Default deconstructor.

Member Function Documentation

◆ AccelerationVector() [1/4]

Eigen::VectorXd rml::RobotModel::AccelerationVector ( )

Method returning the acceleration vector of the whole robot model.

Returns
acceleration vector.

◆ AccelerationVector() [2/4]

void rml::RobotModel::AccelerationVector ( const Eigen::VectorXd &  acceleration)

Method setting the acceleration vector of the whole robot model.

Parameters
[in]accelerationvector.

◆ AccelerationVector() [3/4]

Eigen::VectorXd rml::RobotModel::AccelerationVector ( const std::string &  partID)

Method returning the position of the input part (i.e. joint acceleration for arm and cartesian acceleration in case of mobile body Frame)

Parameters
[in]partID
Returns
position vector, either cartesian position or joint position

◆ AccelerationVector() [4/4]

void rml::RobotModel::AccelerationVector ( const std::string &  partID,
const Eigen::VectorXd &  acceleration 
)

Method setting the acceleration vector for a robot part (joints acceleration for arm and cartesian acceleration in case of mobile body Frame ).

Parameters
[in]partID.

◆ Arm()

const std::shared_ptr< ArmModel > & rml::RobotModel::Arm ( const std::string &  ID) const

Method returning shared pointer to one of the loaded arm.

Parameters
[in]IDarm id.
Returns
shared ptr to the arm.

◆ ArmJacobian()

Eigen::MatrixXd rml::RobotModel::ArmJacobian ( const std::string &  frameID) const
protected

Method returning the isolated arm jacobian for the input frameID.

Parameters
[in]IDframe id
Returns
isolated jacobian

◆ AttachRigidBodyFrame()

void rml::RobotModel::AttachRigidBodyFrame ( const std::string &  frameID,
const std::string &  attachedFrameID,
const Eigen::TransformationMatrix frameToAttachID_T_frameID 
)

Method adding a rigid body frame attached to the input frame id .

Parameters
[in]IDId of the frame.
[in]TMatTransformation matrix of the frame.

◆ BaseJacobian()

Eigen::Matrix6d rml::RobotModel::BaseJacobian ( const std::string &  frameID) const
protected

Method returning the isolated body Frame jacobian for the input frameID.

Parameters
[in]IDframeID
Returns
Jacobian

◆ BodyFrameID()

auto rml::RobotModel::BodyFrameID ( ) const -> const std::string&
inline

Method to get the body Frame id.

Method to get the id for the body Frame, hence the frame common to all the arms.

Returns
body Frame id

◆ CartesianJacobian()

Eigen::MatrixXd rml::RobotModel::CartesianJacobian ( const std::string &  frameID)

Method computing the jacobian observed by the world frame and projected on the body Frame of the input frameID.

Parameters
[in]IDframeID :
Returns
Jacobian observed by the world frame, projected on the body Frame.

◆ CheckArm()

bool rml::RobotModel::CheckArm ( const std::string &  armID) const

Checks whether the arm identified by the input id is present in the robot.

Parameters
[in]armIDthe arm id
Returns
true if the arm is part of the robot, false otherwise

◆ ControlVector() [1/2]

void rml::RobotModel::ControlVector ( const Eigen::VectorXd &  y)

Method setting the control vector of the whole robot model.

Parameters
[in]ycontrol vector.

◆ ControlVector() [2/2]

Eigen::VectorXd rml::RobotModel::ControlVector ( const std::string &  partID)

Method returning the control vector of the input part of robot model.

Parameters
[in]partIDeither armModelID or robotFrameID
Returns
control vector.

◆ Dexterity()

double rml::RobotModel::Dexterity ( const std::string &  frameID)

Method returning the dexterity value for the jacobian related to the input frameID.

Parameters
[in]frameID
Returns
dexterity

◆ DexterityJacobian()

Eigen::MatrixXd rml::RobotModel::DexterityJacobian ( const std::string &  frameID)

Method computing the dexterity jacobian of the input arm ID.

Parameters
[in]IDarmID
Returns
Jacobian

◆ Dof()

auto rml::RobotModel::Dof ( ) const -> int
inline

Returns the number of total degrees of fredoom of the system composed (both of the base if mobile and the arms).

Returns
The total number of DOFs (mobile base + arms)

◆ IsMobile()

auto rml::RobotModel::IsMobile ( ) const -> bool
inline

Method checking whether the robot model has a mobile body Frame .

Returns
true if the body Frame is mobile, false otherwise.

◆ JointSpaceJacobian()

Eigen::MatrixXd rml::RobotModel::JointSpaceJacobian ( const std::string &  armID)

Method computing the joint space jacobian of the input arm ID.

Parameters
[in]IDarmID
Returns
Jacobian

◆ LoadArm()

bool rml::RobotModel::LoadArm ( const std::shared_ptr< ArmModel > &  arm,
const Eigen::TransformationMatrix bodyFrameToArm 
)

Loads an arm in the robot model.

Loads a arm in the robot model, there is no limit to the number of arms that can be loaded. The ArmModel must be initialized before loading, otherwise is not accepted. A <robotFrame-to-base> transformation must be specified, which tells the position of the arm's base frame with respect to the robotFrame.

Parameters
[in]armThe arm model
[in]bodyFrameToArmThe bodyFrame-to-Armbase trasnformation matrix
Returns
True if the arm has been loaded false otherwise

◆ Manipulability()

double rml::RobotModel::Manipulability ( const std::string &  frameID)

Method returning the manipulabity value for the jacobian related to the input frameID.

Parameters
[in]frameID
Returns
manipulability

◆ ManipulabilityJacobian()

Eigen::MatrixXd rml::RobotModel::ManipulabilityJacobian ( const std::string &  frameID)

Method computing the manipulability jacobian of the input arm ID.

Parameters
[in]IDarmID
Returns
Jacobian

◆ PositionOnInertialFrame()

void rml::RobotModel::PositionOnInertialFrame ( const Eigen::TransformationMatrix inertialF_T_bodyF)

Method to set the new body Frame position.

Parameters
[in]bodyFramebody Frame position wrt to the world frame

◆ PositionVector() [1/4]

Eigen::VectorXd rml::RobotModel::PositionVector ( )

Method returning the position vector of the whole robot model.

Returns
position vector.

◆ PositionVector() [2/4]

Eigen::VectorXd rml::RobotModel::PositionVector ( const std::string &  partID)

Method returning the position of the input part (i.e. joint position for arm and cartesian position in case if of mobile body Frame)

Parameters
[in]partID
Returns
position vector, either cartesian position or joint position

◆ PositionVector() [3/4]

void rml::RobotModel::PositionVector ( const std::string &  partID,
const Eigen::VectorXd &  position 
)

Method setting the position vector for a robot part (joint postion for arm and cartesian position in case of mobile body Frame).

Parameters
[in]partID.

◆ PositionVector() [4/4]

void rml::RobotModel::PositionVector ( Eigen::VectorXd &  position)

Method setting the position vector of the whole robot model.

Parameters
[in]positionvector.

◆ TransformationMatrix() [1/2]

Eigen::TransformationMatrix rml::RobotModel::TransformationMatrix ( const std::string &  frameID)

Method returning a transformation matrix of the robot model.
.

The methods returns a transformation matrix depending on the input string framID.

Parameters
[in]transformationID
Returns
Transformation Matrix.

◆ TransformationMatrix() [2/2]

Eigen::TransformationMatrix rml::RobotModel::TransformationMatrix ( const std::string &  frameID_j,
const std::string &  frameID_k 
)

Method returing a transformation matrix from frameID_j to frameID_k, i.e. jTk.
.

Parameters
[in]frameID_jfirst frame;
[in]framID_ksecond frame;
Returns
Transformation Matrix jTk.

◆ VelocityVector() [1/4]

Eigen::VectorXd rml::RobotModel::VelocityVector ( )

Method returning the velocity vector of the whole robot model.

Returns
velocity vector.

◆ VelocityVector() [2/4]

void rml::RobotModel::VelocityVector ( const Eigen::VectorXd &  velocity)

Method setting the velocity vector of the whole robot model.

Parameters
[in]positionvector.

◆ VelocityVector() [3/4]

Eigen::VectorXd rml::RobotModel::VelocityVector ( const std::string &  partID)

GetVelocityVector Method returning the velocity of the input part (i.e. joints velocity for arm and cartesian velocity in case of mobile body Frame )

Parameters
[in]partID
Returns
velocity vector, either cartesian velocity or joints velocity.

◆ VelocityVector() [4/4]

void rml::RobotModel::VelocityVector ( const std::string &  partID,
const Eigen::VectorXd &  velocity 
)

Method setting the velocity vector for a robot part (joint velocity for arm and cartesian velocity in case of mobile body Frame ).

Parameters
[in]partID.

Member Data Documentation

◆ armsModel_

std::map<std::string, std::shared_ptr<ArmModel> > rml::RobotModel::armsModel_
protected

map of the loaded map

◆ bodyFrameID_

std::string rml::RobotModel::bodyFrameID_
protected

ID of the body Frame.

◆ bodyFrameToArm_

std::unordered_map<std::string, Eigen::TransformationMatrix> rml::RobotModel::bodyFrameToArm_
protected

map of the transformation matrix from the arm bases to the body Frame

◆ DoF_

int rml::RobotModel::DoF_
protected

total degrees of freedom of the robot

◆ inertialF_T_bodyF_

Eigen::TransformationMatrix rml::RobotModel::inertialF_T_bodyF_
protected

body Frame transformaion matrix

◆ isMobileRobot_

bool rml::RobotModel::isMobileRobot_
protected

boolean stating wheter the robot is a mobile one

◆ robotBase_

std::shared_ptr<VehicleModel> rml::RobotModel::robotBase_
protected

the model of the body Frame;


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