XBotInterface  2.4.1
XBotInterface provides a generic API to model and control a robot.
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
XBot::KinematicChain Class Reference

Kinematic chain abstraction as a set of joints and sensors. More...

#include <KinematicChain.h>

+ Inheritance diagram for XBot::KinematicChain:
+ Collaboration diagram for XBot::KinematicChain:

Public Types

typedef std::shared_ptr< KinematicChainPtr
 
typedef std::shared_ptr< const KinematicChainConstPtr
 

Public Member Functions

 KinematicChain ()
 Default constructor. More...
 
 KinematicChain (const std::string &chain_name, const XBot::XBotCoreModel &XBotModel)
 Construct a Kinematic Chain using the chain name and the XBotCoreModel. More...
 
 KinematicChain (const std::string &chain_name)
 Construct a Kinematic Chain using the chain name. More...
 
 KinematicChain (const KinematicChain &other)
 Custom copy constructor, which guarantees independence between copies by performing a deep copy. More...
 
KinematicChainoperator= (const KinematicChain &rhs)
 Custom copy assignment, which guarantees independence between copies by performing a deep copy. More...
 
bool getChainState (const std::string &state_name, JointIdMap &q) const
 Gets the chain joints group state configuration as specified in the robot SRDF. More...
 
bool getChainState (const std::string &state_name, JointNameMap &q) const
 Gets the chain joints group state configuration as specified in the robot SRDF. More...
 
bool getChainState (const std::string &state_name, Eigen::VectorXd &q) const
 Gets the chain joints group state configuration as specified in the robot SRDF. More...
 
std::map< std::string, ForceTorqueSensor::ConstPtrgetForceTorque () const
 Getter for the force-torque sensor map pertaining to the chain. More...
 
std::map< std::string, ImuSensor::ConstPtrgetImu () const
 Getter for the IMU sensor map pertaining to the chain. More...
 
ForceTorqueSensor::ConstPtr getForceTorque (const std::string &parent_link_name) const
 Returns a force-torque sensor given its parent-link name. More...
 
ImuSensor::ConstPtr getImu (const std::string &parent_link_name) const
 Returns an IMU sensor given its parent-link name. More...
 
void getJointLimits (Eigen::VectorXd &q_min, Eigen::VectorXd &q_max) const
 Gets a vector of the chain joint limits, as specified in the URDF file. More...
 
void getVelocityLimits (Eigen::VectorXd &qdot_max) const
 Gets a vector of the chain joint velocity limits, as specified in the URDF file. More...
 
void getEffortLimits (Eigen::VectorXd &tau_max) const
 Gets a vector of the chain joint effort limits, as specified in the URDF file. More...
 
void getJointLimits (int i, double &q_min, double &q_max) const
 Gets the lower and upper joint limits of the i-th joint in the chain (from base link to tip link) More...
 
void getVelocityLimits (int i, double &qdot_max) const
 Gets the velocity limit of the i-th joint in the chain (from base link to tip link) More...
 
void getEffortLimits (int i, double &tau_max) const
 Gets the effort limit of the i-th joint in the chain (from base link to tip link) More...
 
bool checkJointLimits (const Eigen::VectorXd &q, std::vector< std::string > &violating_joints) const
 Check the input joint position vector against joint limits. More...
 
bool checkVelocityLimits (const Eigen::VectorXd &qdot, std::vector< std::string > &violating_joints) const
 Check the input joint velocity vector against joint limits. More...
 
bool checkEffortLimits (const Eigen::VectorXd &tau, std::vector< std::string > &violating_joints) const
 Check the input joint effort vector against joint limits. More...
 
bool checkJointLimits (const Eigen::VectorXd &q) const
 Check the input joint position vector against joint limits. More...
 
bool checkVelocityLimits (const Eigen::VectorXd &qdot) const
 Check the input joint velocity vector against joint limits. More...
 
bool checkEffortLimits (const Eigen::VectorXd &tau) const
 Check the input joint effort vector against joint limits. More...
 
bool enforceJointLimits (Eigen::VectorXd &q) const
 Modifies the input joint position vector by enforcing joint limits. More...
 
bool enforceVelocityLimit (Eigen::VectorXd &qdot) const
 Modifies the input joint velcoity vector by enforcing joint limits. More...
 
bool enforceEffortLimit (Eigen::VectorXd &tau) const
 Modifies the input joint effort vector by enforcing effort limits. More...
 
bool mapToEigen (const JointIdMap &id_map, Eigen::VectorXd &eigen_vector) const
 Converts a state vector for an arbitrary subset of the chain state (specified as a JointIdMap) to its Eigen representation. More...
 
bool mapToEigen (const JointNameMap &name_map, Eigen::VectorXd &eigen_vector) const
 Converts a state vector for an arbitrary subset of the chain state (specified as a JointNameMap) to its Eigen representation. More...
 
bool eigenToMap (const Eigen::VectorXd &eigen_vector, JointIdMap &id_map) const
 Converts a state vector for the whole chain to its JointIdMap representation. More...
 
bool eigenToMap (const Eigen::VectorXd &eigen_vector, JointNameMap &name_map) const
 Converts a state vector for the whole chain to its JointNameMap representation. More...
 
void pushBackJoint (Joint::Ptr joint)
 add a joint in the kinematic chain pushing it in the end of the chain More...
 
void removeJoint (int i)
 remove the i-th joint in the kinematic chain More...
 
bool isVirtual () const
 Method for determining whether a chain is virtual, i.e. More...
 
const std::string & getChainName () const
 Method returning the name of the chain. More...
 
const std::string & getBaseLinkName () const
 Method returning the name of the chain base link. More...
 
const std::string & getTipLinkName () const
 Method returning the name of the chain tip link. More...
 
const std::string & getChildLinkName (int i) const
 Method returning the name of the child link corresponding to the i-th joint of the chain. More...
 
const std::string & getParentLinkName (int i) const
 Method returning the name of the parent link corresponding to the i-th joint of the chain. More...
 
const std::string & getJointName (int i) const
 Method returning the name of the i-th joint of the chain. More...
 
const std::vector< std::string > & getJointNames () const
 Returns a vector containing the namess of all joints in the chain, from base link to tip link. More...
 
int getJointId (int i) const
 Method returning the ID of the i-th joint of the chain. More...
 
int getChainDofIndex (int joint_id) const
 Getter for the chain dof index (local index of a joint inside a chain, this means that the base link of the chain has dof index = 0, tip link of the chain has dof index = getJointNum()-1 ) of a joint with the requested joint id. More...
 
int getChainDofIndex (const std::string &joint_name) const
 Getter for the chain dof index (local index of a joint inside a chain, this means that the base link of the chain has dof index = 0, tip link of the chain has dof index = getJointNum()-1 ) of a joint with the requested joint name. More...
 
bool hasJoint (int joint_id) const
 check if the chain has a joint with a certain id More...
 
bool hasJoint (const std::string &joint_name) const
 check if the chain has a joint with a certain name More...
 
const std::vector< int > & getJointIds () const
 Returns a vector containing the IDs of all joints in the chain, from base link to tip link. More...
 
int getJointNum () const
 Method returning the number of enabled joints belonging to the chain. More...
 
const std::vector< urdf::JointConstSharedPtr > & getUrdfJoints () const
 Method returning the vector of urdf::Joints corresponding to the chain. More...
 
const std::vector< urdf::LinkConstSharedPtr > & getUrdfLinks () const
 Method returning the vector of urdf::Links corresponding to the chain. More...
 
void shallowCopy (const KinematicChain &chain)
 Updates the current object (this) by performing a shallow copy with the chain passed as argument. More...
 
Joint::ConstPtr getJoint (int i) const
 Getter for the i-th Joint Ptr. More...
 
bool getJointPosition (Eigen::VectorXd &q) const
 
bool getMotorPosition (Eigen::VectorXd &q) const
 
bool getJointVelocity (Eigen::VectorXd &qdot) const
 
bool getMotorVelocity (Eigen::VectorXd &qdot) const
 
bool getJointAcceleration (Eigen::VectorXd &qddot) const
 
bool getJointEffort (Eigen::VectorXd &tau) const
 
bool getTemperature (Eigen::VectorXd &temp) const
 
bool getJointPosition (JointIdMap &q) const
 
bool getMotorPosition (JointIdMap &q) const
 
bool getJointVelocity (JointIdMap &qdot) const
 
bool getMotorVelocity (JointIdMap &qdot) const
 
bool getJointAcceleration (JointIdMap &qddot) const
 
bool getJointEffort (JointIdMap &tau) const
 
bool getTemperature (JointIdMap &temp) const
 
bool getJointPosition (JointNameMap &q) const
 
bool getMotorPosition (JointNameMap &q) const
 
bool getJointVelocity (JointNameMap &qdot) const
 
bool getMotorVelocity (JointNameMap &qdot) const
 
bool getJointAcceleration (JointNameMap &qddot) const
 
bool getJointEffort (JointNameMap &tau) const
 
bool getTemperature (JointNameMap &temp) const
 
double getJointPosition (int index) const
 
double getMotorPosition (int index) const
 
double getJointVelocity (int index) const
 
double getMotorVelocity (int index) const
 
double getJointAcceleration (int index) const
 
double getJointEffort (int index) const
 
double getTemperature (int index) const
 
bool setJointPosition (const Eigen::VectorXd &q)
 
bool setMotorPosition (const Eigen::VectorXd &q)
 
bool setJointVelocity (const Eigen::VectorXd &qdot)
 
bool setMotorVelocity (const Eigen::VectorXd &qdot)
 
bool setJointAcceleration (const Eigen::VectorXd &qddot)
 
bool setJointEffort (const Eigen::VectorXd &tau)
 
bool setTemperature (const Eigen::VectorXd &temp)
 
bool setJointPosition (const JointIdMap &q)
 
bool setMotorPosition (const JointIdMap &q)
 
bool setJointVelocity (const JointIdMap &qdot)
 
bool setMotorVelocity (const JointIdMap &qdot)
 
bool setJointAcceleration (const JointIdMap &qddot)
 
bool setJointEffort (const JointIdMap &tau)
 
bool setTemperature (const JointIdMap &temp)
 
bool setJointPosition (const JointNameMap &q)
 
bool setMotorPosition (const JointNameMap &q)
 
bool setJointVelocity (const JointNameMap &qdot)
 
bool setMotorVelocity (const JointNameMap &qdot)
 
bool setJointAcceleration (const JointNameMap &qddot)
 
bool setJointEffort (const JointNameMap &tau)
 
bool setTemperature (const JointNameMap &temp)
 
bool setJointPosition (int i, double q)
 
bool setMotorPosition (int i, double q)
 
bool setJointVelocity (int i, double qdot)
 
bool setMotorVelocity (int i, double qdot)
 
bool setJointAcceleration (int i, double qddot)
 
bool setJointEffort (int i, double tau)
 
bool setTemperature (int i, double temp)
 
bool getPositionReference (Eigen::VectorXd &q) const
 
bool getVelocityReference (Eigen::VectorXd &qdot) const
 
bool getEffortReference (Eigen::VectorXd &tau) const
 
bool getStiffness (Eigen::VectorXd &K) const
 
bool getDamping (Eigen::VectorXd &D) const
 
bool getPositionReference (JointIdMap &q) const
 
bool getVelocityReference (JointIdMap &qdot) const
 
bool getEffortReference (JointIdMap &tau) const
 
bool getStiffness (JointIdMap &K) const
 
bool getDamping (JointIdMap &D) const
 
bool getPositionReference (JointNameMap &q) const
 
bool getVelocityReference (JointNameMap &qdot) const
 
bool getEffortReference (JointNameMap &tau) const
 
bool getStiffness (JointNameMap &K) const
 
bool getDamping (JointNameMap &D) const
 
double getPositionReference (int index) const
 
double getVelocityReference (int index) const
 
double getEffortReference (int index) const
 
double getStiffness (int index) const
 
double getDamping (int index) const
 
bool setPositionReference (const Eigen::VectorXd &q)
 
bool setVelocityReference (const Eigen::VectorXd &qdot)
 
bool setEffortReference (const Eigen::VectorXd &tau)
 
bool setStiffness (const Eigen::VectorXd &K)
 
bool setDamping (const Eigen::VectorXd &D)
 
bool setPositionReference (const JointIdMap &q)
 
bool setVelocityReference (const JointIdMap &qdot)
 
bool setEffortReference (const JointIdMap &tau)
 
bool setStiffness (const JointIdMap &K)
 
bool setDamping (const JointIdMap &D)
 
bool setPositionReference (const JointNameMap &q)
 
bool setVelocityReference (const JointNameMap &qdot)
 
bool setEffortReference (const JointNameMap &tau)
 
bool setStiffness (const JointNameMap &K)
 
bool setDamping (const JointNameMap &D)
 
bool setPositionReference (int i, double q)
 
bool setVelocityReference (int i, double qdot)
 
bool setEffortReference (int i, double tau)
 
bool setStiffness (int i, double K)
 
bool setDamping (int i, double D)
 
template<typename... SyncFlags>
bool syncFrom (const KinematicChain &other, SyncFlags... flags)
 Synchronize the current KinematicChain with another KinematicChain object. More...
 
void print () const
 Prints a pretty table about chain state. More...
 
void printTracking () const
 Prints a pretty table about chain tracking. More...
 

Protected Member Functions

Joint::Ptr getJointInternal (int i) const
 Getter for the i-th Joint Ptr. More...
 
std::map< std::string, ForceTorqueSensor::PtrgetForceTorqueInternal () const
 
std::map< std::string, ImuSensor::PtrgetImuInternal () const
 

Protected Attributes

std::map< std::string, XBot::Joint::Ptr_joint_name_map
 
std::map< int, XBot::Joint::Ptr_joint_id_map
 
std::vector< XBot::Joint::Ptr_joint_vector
 
std::vector< ForceTorqueSensor::Ptr_ft_vector
 
std::map< std::string, ForceTorqueSensor::Ptr_ft_map
 
std::vector< ImuSensor::Ptr_imu_vector
 
std::map< std::string, ImuSensor::Ptr_imu_map
 

Friends

std::ostream & operator<< (std::ostream &os, const XBot::KinematicChain &c)
 

Detailed Description

Kinematic chain abstraction as a set of joints and sensors.

Member Typedef Documentation

◆ ConstPtr

typedef std::shared_ptr<const KinematicChain> XBot::KinematicChain::ConstPtr

◆ Ptr

typedef std::shared_ptr<KinematicChain> XBot::KinematicChain::Ptr

Constructor & Destructor Documentation

◆ KinematicChain() [1/4]

XBot::KinematicChain::KinematicChain ( )

Default constructor.

◆ KinematicChain() [2/4]

XBot::KinematicChain::KinematicChain ( const std::string &  chain_name,
const XBot::XBotCoreModel XBotModel 
)

Construct a Kinematic Chain using the chain name and the XBotCoreModel.

Parameters
chain_namethe name of the chain
XBotModelthe model built using XBotModel

◆ KinematicChain() [3/4]

XBot::KinematicChain::KinematicChain ( const std::string &  chain_name)
explicit

Construct a Kinematic Chain using the chain name.

Parameters
chain_namethe name of the chain

◆ KinematicChain() [4/4]

XBot::KinematicChain::KinematicChain ( const KinematicChain other)

Custom copy constructor, which guarantees independence between copies by performing a deep copy.

Member Function Documentation

◆ checkEffortLimits() [1/2]

bool XBot::KinematicChain::checkEffortLimits ( const Eigen::VectorXd &  tau) const

Check the input joint effort vector against joint limits.

Parameters
tauA joint effort vector to be checked against joint limits, ordered from base link to tip link.
Returns
True if all joints are within their limits.

◆ checkEffortLimits() [2/2]

bool XBot::KinematicChain::checkEffortLimits ( const Eigen::VectorXd &  tau,
std::vector< std::string > &  violating_joints 
) const

Check the input joint effort vector against joint limits.

The names of joints violating the limits are pushed into the violating_joints vector (which is not cleared before being filled)

Parameters
tauA joint effort vector to be checked against joint limits, ordered from base link to tip link.
violating_jointsThe vector of the names of joints violating the limits. Note that this is not cleared before use.
Returns
True if all joints are within their limits.

◆ checkJointLimits() [1/2]

bool XBot::KinematicChain::checkJointLimits ( const Eigen::VectorXd &  q) const

Check the input joint position vector against joint limits.

Parameters
qA joint position vector to be checked against joint limits, ordered from base link to tip link.
Returns
True if all joints are within their limits.

◆ checkJointLimits() [2/2]

bool XBot::KinematicChain::checkJointLimits ( const Eigen::VectorXd &  q,
std::vector< std::string > &  violating_joints 
) const

Check the input joint position vector against joint limits.

The names of joints violating the limits are pushed into the violating_joints vector (which is not cleared before being filled)

Parameters
qA joint position vector to be checked against joint limits, ordered from base link to tip link.
violating_jointsThe vector of the names of joints violating the limits. Note that this is not cleared before use.
Returns
True if all joints are within their limits.

◆ checkVelocityLimits() [1/2]

bool XBot::KinematicChain::checkVelocityLimits ( const Eigen::VectorXd &  qdot) const

Check the input joint velocity vector against joint limits.

Parameters
qdotA joint velocity vector to be checked against joint limits, ordered from base link to tip link.
Returns
True if all joints are within their limits.

◆ checkVelocityLimits() [2/2]

bool XBot::KinematicChain::checkVelocityLimits ( const Eigen::VectorXd &  qdot,
std::vector< std::string > &  violating_joints 
) const

Check the input joint velocity vector against joint limits.

The names of joints violating the limits are pushed into the violating_joints vector (which is not cleared before being filled)

Parameters
qdotA joint velocity vector to be checked against joint limits, ordered from base link to tip link.
violating_jointsThe vector of the names of joints violating the limits. Note that this is not cleared before use.
Returns
True if all joints are within their limits.

◆ eigenToMap() [1/2]

bool XBot::KinematicChain::eigenToMap ( const Eigen::VectorXd &  eigen_vector,
JointIdMap id_map 
) const

Converts a state vector for the whole chain to its JointIdMap representation.

Note that the output map is not cleared before it is filled. It is the responsibility of the user to do so if required.

Parameters
eigen_vectorA state vector for the whole robot (its size must match getJointNum())
id_mapThe output map to be filled
Returns
True if the input vector is valid.

◆ eigenToMap() [2/2]

bool XBot::KinematicChain::eigenToMap ( const Eigen::VectorXd &  eigen_vector,
JointNameMap name_map 
) const

Converts a state vector for the whole chain to its JointNameMap representation.

Note that the output map is not cleared before it is filled. It is the responsibility of the user to do so if required.

Parameters
eigen_vectorA state vector for the whole robot (its size must match getJointNum())
name_mapThe output map to be filled
Returns
True if the input vector is valid.

◆ enforceEffortLimit()

bool XBot::KinematicChain::enforceEffortLimit ( Eigen::VectorXd &  tau) const

Modifies the input joint effort vector by enforcing effort limits.

Parameters
tauThe input joint effort vector. Out-of-range components are set to the closest joint limit.
Returns
True if the provided vector has the correct size.

◆ enforceJointLimits()

bool XBot::KinematicChain::enforceJointLimits ( Eigen::VectorXd &  q) const

Modifies the input joint position vector by enforcing joint limits.

Parameters
qThe input joint position vector. Out-of-range components are set to the closest joint limit.
Returns
True if the provided vector has the correct size.

◆ enforceVelocityLimit()

bool XBot::KinematicChain::enforceVelocityLimit ( Eigen::VectorXd &  qdot) const

Modifies the input joint velcoity vector by enforcing joint limits.

Parameters
qdotThe input joint velocity vector. Out-of-range components are set to the closest joint limit.
Returns
True if the provided vector has the correct size.

◆ getBaseLinkName()

const std::string & XBot::KinematicChain::getBaseLinkName ( ) const

Method returning the name of the chain base link.

Returns
Base link name as const std::string&

◆ getChainDofIndex() [1/2]

int XBot::KinematicChain::getChainDofIndex ( const std::string &  joint_name) const

Getter for the chain dof index (local index of a joint inside a chain, this means that the base link of the chain has dof index = 0, tip link of the chain has dof index = getJointNum()-1 ) of a joint with the requested joint name.

Parameters
joint_namethe requested joint name
Returns
the chain dof index of a joint with the requested joint name

◆ getChainDofIndex() [2/2]

int XBot::KinematicChain::getChainDofIndex ( int  joint_id) const

Getter for the chain dof index (local index of a joint inside a chain, this means that the base link of the chain has dof index = 0, tip link of the chain has dof index = getJointNum()-1 ) of a joint with the requested joint id.

Parameters
joint_idthe requested joint id
Returns
the chain dof index of a joint with the requested joint id

◆ getChainName()

const std::string & XBot::KinematicChain::getChainName ( ) const

Method returning the name of the chain.

Returns
Chain name as const std::string&

◆ getChainState() [1/3]

bool XBot::KinematicChain::getChainState ( const std::string &  state_name,
Eigen::VectorXd &  q 
) const

Gets the chain joints group state configuration as specified in the robot SRDF.

Parameters
state_nameThe name of the requested group state.
qThe chain joint configuration as Eigen vector of joint positions, This is an output parameter; any contents present in the vector will be overwritten in this function.
Returns
True if the state_name exists in the SRDF, false otherwise.

◆ getChainState() [2/3]

bool XBot::KinematicChain::getChainState ( const std::string &  state_name,
JointIdMap q 
) const

Gets the chain joints group state configuration as specified in the robot SRDF.

Parameters
state_nameThe name of the requested group state.
qThe chain joint configuration as a map with key representing the joint ID (i.e. numerical name of the joint) and values representing joint positions. This is an output parameter; it will not be cleared before being filled.
Returns
True if the state_name exists in the SRDF, false otherwise.

◆ getChainState() [3/3]

bool XBot::KinematicChain::getChainState ( const std::string &  state_name,
JointNameMap q 
) const

Gets the chain joints group state configuration as specified in the robot SRDF.

Parameters
state_nameThe name of the requested group state.
qThe chain joint configuration as a map with key representing joint names and values representing joint positions. This is an output parameter; it will not be cleared before being filled.
Returns
True if the state_name exists in the SRDF, false otherwise.

◆ getChildLinkName()

const std::string & XBot::KinematicChain::getChildLinkName ( int  i) const

Method returning the name of the child link corresponding to the i-th joint of the chain.

Parameters
iThe position of the joint along the chain (i = 0 refers to the joint attached to the base link)
Returns
The name of the child link of joint n° i

◆ getDamping() [1/4]

bool XBot::KinematicChain::getDamping ( Eigen::VectorXd &  D) const

◆ getDamping() [2/4]

double XBot::KinematicChain::getDamping ( int  index) const

◆ getDamping() [3/4]

bool XBot::KinematicChain::getDamping ( JointIdMap D) const

◆ getDamping() [4/4]

bool XBot::KinematicChain::getDamping ( JointNameMap D) const

◆ getEffortLimits() [1/2]

void XBot::KinematicChain::getEffortLimits ( Eigen::VectorXd &  tau_max) const

Gets a vector of the chain joint effort limits, as specified in the URDF file.

The vector is ordered from the chain base link to its tip link.

Parameters
qdot_maxThe output vector of the chain joints effort limits
Returns
void

◆ getEffortLimits() [2/2]

void XBot::KinematicChain::getEffortLimits ( int  i,
double &  tau_max 
) const

Gets the effort limit of the i-th joint in the chain (from base link to tip link)

Parameters
iThe index of the joint along the chain for which the joint limit is requested.
tau_maxThe requested joint effort limit.
Returns
void

◆ getEffortReference() [1/4]

bool XBot::KinematicChain::getEffortReference ( Eigen::VectorXd &  tau) const

◆ getEffortReference() [2/4]

double XBot::KinematicChain::getEffortReference ( int  index) const

◆ getEffortReference() [3/4]

bool XBot::KinematicChain::getEffortReference ( JointIdMap tau) const

◆ getEffortReference() [4/4]

bool XBot::KinematicChain::getEffortReference ( JointNameMap tau) const

◆ getForceTorque() [1/2]

std::map< std::string, ForceTorqueSensor::ConstPtr > XBot::KinematicChain::getForceTorque ( ) const

Getter for the force-torque sensor map pertaining to the chain.

Returns
A map whose key is the sensor name (i.e. the name of the sensor link inside the URDF) and whose value is a shared pointer to the force torque sensor.

◆ getForceTorque() [2/2]

ForceTorqueSensor::ConstPtr XBot::KinematicChain::getForceTorque ( const std::string &  parent_link_name) const

Returns a force-torque sensor given its parent-link name.

Parameters
parent_link_nameName of the link to which the sensor is attached
Returns
A shared pointer to the required force-torque sensor. The returned pointer is null if the chain either does not contain a link named "parent_link_name" or such a link does not contain any FT.

◆ getForceTorqueInternal()

std::map< std::string, ForceTorqueSensor::Ptr > XBot::KinematicChain::getForceTorqueInternal ( ) const
protected

◆ getImu() [1/2]

std::map< std::string, ImuSensor::ConstPtr > XBot::KinematicChain::getImu ( ) const

Getter for the IMU sensor map pertaining to the chain.

Returns
A map whose key is the sensor name (i.e. the name of the sensor link inside the URDF) and whose value is a shared pointer to the IMU sensor.

◆ getImu() [2/2]

ImuSensor::ConstPtr XBot::KinematicChain::getImu ( const std::string &  parent_link_name) const

Returns an IMU sensor given its parent-link name.

Parameters
parent_link_nameName of the link to which the sensor is attached
Returns
A shared pointer to the required IMU sensor. The returned pointer is null if the chain either does not contain a link named "parent_link_name" or such a link does not contain any IMU.

◆ getImuInternal()

std::map< std::string, ImuSensor::Ptr > XBot::KinematicChain::getImuInternal ( ) const
protected

◆ getJoint()

Joint::ConstPtr XBot::KinematicChain::getJoint ( int  i) const

Getter for the i-th Joint Ptr.

Parameters
iindex inside the chain (i=0 is the child joint of base link)
Returns
A shared pointer to the requested joint

◆ getJointAcceleration() [1/4]

bool XBot::KinematicChain::getJointAcceleration ( Eigen::VectorXd &  qddot) const

◆ getJointAcceleration() [2/4]

double XBot::KinematicChain::getJointAcceleration ( int  index) const

◆ getJointAcceleration() [3/4]

bool XBot::KinematicChain::getJointAcceleration ( JointIdMap qddot) const

◆ getJointAcceleration() [4/4]

bool XBot::KinematicChain::getJointAcceleration ( JointNameMap qddot) const

◆ getJointEffort() [1/4]

bool XBot::KinematicChain::getJointEffort ( Eigen::VectorXd &  tau) const

◆ getJointEffort() [2/4]

double XBot::KinematicChain::getJointEffort ( int  index) const

◆ getJointEffort() [3/4]

bool XBot::KinematicChain::getJointEffort ( JointIdMap tau) const

◆ getJointEffort() [4/4]

bool XBot::KinematicChain::getJointEffort ( JointNameMap tau) const

◆ getJointId()

int XBot::KinematicChain::getJointId ( int  i) const

Method returning the ID of the i-th joint of the chain.

Parameters
iThe position of the joint whose ID is queried (i = 0 refers to the joint attached to the base link)
Returns
The ID of the joint n° i

◆ getJointIds()

const std::vector< int > & XBot::KinematicChain::getJointIds ( ) const

Returns a vector containing the IDs of all joints in the chain, from base link to tip link.

Returns
a const reference to the vector of joint IDs

◆ getJointInternal()

Joint::Ptr XBot::KinematicChain::getJointInternal ( int  i) const
protected

Getter for the i-th Joint Ptr.

Parameters
iindex inside the chain (i=0 is the child joint of base link)
Returns
A shared pointer to the requested joint

◆ getJointLimits() [1/2]

void XBot::KinematicChain::getJointLimits ( Eigen::VectorXd &  q_min,
Eigen::VectorXd &  q_max 
) const

Gets a vector of the chain joint limits, as specified in the URDF file.

The vector is ordered from the chain base link to its tip link.

Parameters
q_minThe output vector of the chain joints lower limits.
q_maxThe output vector of the chain joints upper limits.
Returns
void

◆ getJointLimits() [2/2]

void XBot::KinematicChain::getJointLimits ( int  i,
double &  q_min,
double &  q_max 
) const

Gets the lower and upper joint limits of the i-th joint in the chain (from base link to tip link)

Parameters
iThe index of the joint along the chain for which the joint limits are requested.
q_minThe required joint lower limit.
q_maxThe required joint upper limit.
Returns
void

◆ getJointName()

const std::string & XBot::KinematicChain::getJointName ( int  i) const

Method returning the name of the i-th joint of the chain.

Parameters
iThe position of the joint whose name is queried (i = 0 refers to the joint attached to the base link)
Returns
The name of the joint n° i

◆ getJointNames()

const std::vector< std::string > & XBot::KinematicChain::getJointNames ( ) const

Returns a vector containing the namess of all joints in the chain, from base link to tip link.

Returns
a const reference to the vector of joint names

◆ getJointNum()

int XBot::KinematicChain::getJointNum ( ) const

Method returning the number of enabled joints belonging to the chain.

Returns
The number of enabled joints belonging to the chain

◆ getJointPosition() [1/4]

bool XBot::KinematicChain::getJointPosition ( Eigen::VectorXd &  q) const

◆ getJointPosition() [2/4]

double XBot::KinematicChain::getJointPosition ( int  index) const

◆ getJointPosition() [3/4]

bool XBot::KinematicChain::getJointPosition ( JointIdMap q) const

◆ getJointPosition() [4/4]

bool XBot::KinematicChain::getJointPosition ( JointNameMap q) const

◆ getJointVelocity() [1/4]

bool XBot::KinematicChain::getJointVelocity ( Eigen::VectorXd &  qdot) const

◆ getJointVelocity() [2/4]

double XBot::KinematicChain::getJointVelocity ( int  index) const

◆ getJointVelocity() [3/4]

bool XBot::KinematicChain::getJointVelocity ( JointIdMap qdot) const

◆ getJointVelocity() [4/4]

bool XBot::KinematicChain::getJointVelocity ( JointNameMap qdot) const

◆ getMotorPosition() [1/4]

bool XBot::KinematicChain::getMotorPosition ( Eigen::VectorXd &  q) const

◆ getMotorPosition() [2/4]

double XBot::KinematicChain::getMotorPosition ( int  index) const

◆ getMotorPosition() [3/4]

bool XBot::KinematicChain::getMotorPosition ( JointIdMap q) const

◆ getMotorPosition() [4/4]

bool XBot::KinematicChain::getMotorPosition ( JointNameMap q) const

◆ getMotorVelocity() [1/4]

bool XBot::KinematicChain::getMotorVelocity ( Eigen::VectorXd &  qdot) const

◆ getMotorVelocity() [2/4]

double XBot::KinematicChain::getMotorVelocity ( int  index) const

◆ getMotorVelocity() [3/4]

bool XBot::KinematicChain::getMotorVelocity ( JointIdMap qdot) const

◆ getMotorVelocity() [4/4]

bool XBot::KinematicChain::getMotorVelocity ( JointNameMap qdot) const

◆ getParentLinkName()

const std::string & XBot::KinematicChain::getParentLinkName ( int  i) const

Method returning the name of the parent link corresponding to the i-th joint of the chain.

Parameters
iThe position of the joint along the chain (i = 0 refers to the joint attached to the base link)
Returns
The name of the parent link of joint n° i

◆ getPositionReference() [1/4]

bool XBot::KinematicChain::getPositionReference ( Eigen::VectorXd &  q) const

◆ getPositionReference() [2/4]

double XBot::KinematicChain::getPositionReference ( int  index) const

◆ getPositionReference() [3/4]

bool XBot::KinematicChain::getPositionReference ( JointIdMap q) const

◆ getPositionReference() [4/4]

bool XBot::KinematicChain::getPositionReference ( JointNameMap q) const

◆ getStiffness() [1/4]

bool XBot::KinematicChain::getStiffness ( Eigen::VectorXd &  K) const

◆ getStiffness() [2/4]

double XBot::KinematicChain::getStiffness ( int  index) const

◆ getStiffness() [3/4]

bool XBot::KinematicChain::getStiffness ( JointIdMap K) const

◆ getStiffness() [4/4]

bool XBot::KinematicChain::getStiffness ( JointNameMap K) const

◆ getTemperature() [1/4]

bool XBot::KinematicChain::getTemperature ( Eigen::VectorXd &  temp) const

◆ getTemperature() [2/4]

double XBot::KinematicChain::getTemperature ( int  index) const

◆ getTemperature() [3/4]

bool XBot::KinematicChain::getTemperature ( JointIdMap temp) const

◆ getTemperature() [4/4]

bool XBot::KinematicChain::getTemperature ( JointNameMap temp) const

◆ getTipLinkName()

const std::string & XBot::KinematicChain::getTipLinkName ( ) const

Method returning the name of the chain tip link.

Returns
Tip link name as const std::string&

◆ getUrdfJoints()

const std::vector< urdf::JointConstSharedPtr > & XBot::KinematicChain::getUrdfJoints ( ) const

Method returning the vector of urdf::Joints corresponding to the chain.

Returns
const std::vector< urdf::JointConstSharedPtr>&

◆ getUrdfLinks()

const std::vector< urdf::LinkConstSharedPtr > & XBot::KinematicChain::getUrdfLinks ( ) const

Method returning the vector of urdf::Links corresponding to the chain.

Returns
const std::vector< urdf::LinkConstSharedPtr>&

◆ getVelocityLimits() [1/2]

void XBot::KinematicChain::getVelocityLimits ( Eigen::VectorXd &  qdot_max) const

Gets a vector of the chain joint velocity limits, as specified in the URDF file.

The vector is ordered from the chain base link to its tip link.

Parameters
qdot_maxThe output vector of the chain joints velocity limits
Returns
void

◆ getVelocityLimits() [2/2]

void XBot::KinematicChain::getVelocityLimits ( int  i,
double &  qdot_max 
) const

Gets the velocity limit of the i-th joint in the chain (from base link to tip link)

Parameters
iThe index of the joint along the chain for which the joint limit is requested.
qdot_maxThe requested joint velocity limit.
Returns
void

◆ getVelocityReference() [1/4]

bool XBot::KinematicChain::getVelocityReference ( Eigen::VectorXd &  qdot) const

◆ getVelocityReference() [2/4]

double XBot::KinematicChain::getVelocityReference ( int  index) const

◆ getVelocityReference() [3/4]

bool XBot::KinematicChain::getVelocityReference ( JointIdMap qdot) const

◆ getVelocityReference() [4/4]

bool XBot::KinematicChain::getVelocityReference ( JointNameMap qdot) const

◆ hasJoint() [1/2]

bool XBot::KinematicChain::hasJoint ( const std::string &  joint_name) const

check if the chain has a joint with a certain name

Parameters
joint_namethe requested joint name
Returns
true if the joint with joint_name is present in the chain

◆ hasJoint() [2/2]

bool XBot::KinematicChain::hasJoint ( int  joint_id) const

check if the chain has a joint with a certain id

Parameters
joint_idthe requested joint id
Returns
true if the joint with with_id is present in the chain

◆ isVirtual()

bool XBot::KinematicChain::isVirtual ( ) const

Method for determining whether a chain is virtual, i.e.

contains all virtual joints

Returns
A boolean set to true if chain is virtual, false otherwise.

◆ mapToEigen() [1/2]

bool XBot::KinematicChain::mapToEigen ( const JointIdMap id_map,
Eigen::VectorXd &  eigen_vector 
) const

Converts a state vector for an arbitrary subset of the chain state (specified as a JointIdMap) to its Eigen representation.

Note that the output vector is resized and set to zero if its size does not match the number of joints. Otherwise, unspecified components are left untouched.

Parameters
id_mapA JointIdMap contaning the state of the robot (or a part of it)
eigen_vectorThe output vector to be filled.
Returns
True if the input map contains valid joints.

◆ mapToEigen() [2/2]

bool XBot::KinematicChain::mapToEigen ( const JointNameMap name_map,
Eigen::VectorXd &  eigen_vector 
) const

Converts a state vector for an arbitrary subset of the chain state (specified as a JointNameMap) to its Eigen representation.

Note that the output vector is resized and set to zero if its size does not match the number of joints. Otherwise, unspecified components are left untouched.

Parameters
name_mapA JointNameMap contaning the state of the robot (or a part of it)
eigen_vectorThe output vector to be filled.
Returns
True if the input map contains valid joints.

◆ operator=()

KinematicChain & XBot::KinematicChain::operator= ( const KinematicChain rhs)

Custom copy assignment, which guarantees independence between copies by performing a deep copy.

◆ print()

void XBot::KinematicChain::print ( ) const

Prints a pretty table about chain state.

Returns
void

◆ printTracking()

void XBot::KinematicChain::printTracking ( ) const

Prints a pretty table about chain tracking.

Returns
void

◆ pushBackJoint()

void XBot::KinematicChain::pushBackJoint ( Joint::Ptr  joint)

add a joint in the kinematic chain pushing it in the end of the chain

Parameters
jointthe joint to add
Returns
void

◆ removeJoint()

void XBot::KinematicChain::removeJoint ( int  i)

remove the i-th joint in the kinematic chain

Parameters
ithe joint i-th position
Returns
void

◆ setDamping() [1/4]

bool XBot::KinematicChain::setDamping ( const Eigen::VectorXd &  D)

◆ setDamping() [2/4]

bool XBot::KinematicChain::setDamping ( const JointIdMap D)

◆ setDamping() [3/4]

bool XBot::KinematicChain::setDamping ( const JointNameMap D)

◆ setDamping() [4/4]

bool XBot::KinematicChain::setDamping ( int  i,
double  D 
)

◆ setEffortReference() [1/4]

bool XBot::KinematicChain::setEffortReference ( const Eigen::VectorXd &  tau)

◆ setEffortReference() [2/4]

bool XBot::KinematicChain::setEffortReference ( const JointIdMap tau)

◆ setEffortReference() [3/4]

bool XBot::KinematicChain::setEffortReference ( const JointNameMap tau)

◆ setEffortReference() [4/4]

bool XBot::KinematicChain::setEffortReference ( int  i,
double  tau 
)

◆ setJointAcceleration() [1/4]

bool XBot::KinematicChain::setJointAcceleration ( const Eigen::VectorXd &  qddot)

◆ setJointAcceleration() [2/4]

bool XBot::KinematicChain::setJointAcceleration ( const JointIdMap qddot)

◆ setJointAcceleration() [3/4]

bool XBot::KinematicChain::setJointAcceleration ( const JointNameMap qddot)

◆ setJointAcceleration() [4/4]

bool XBot::KinematicChain::setJointAcceleration ( int  i,
double  qddot 
)

◆ setJointEffort() [1/4]

bool XBot::KinematicChain::setJointEffort ( const Eigen::VectorXd &  tau)

◆ setJointEffort() [2/4]

bool XBot::KinematicChain::setJointEffort ( const JointIdMap tau)

◆ setJointEffort() [3/4]

bool XBot::KinematicChain::setJointEffort ( const JointNameMap tau)

◆ setJointEffort() [4/4]

bool XBot::KinematicChain::setJointEffort ( int  i,
double  tau 
)

◆ setJointPosition() [1/4]

bool XBot::KinematicChain::setJointPosition ( const Eigen::VectorXd &  q)

◆ setJointPosition() [2/4]

bool XBot::KinematicChain::setJointPosition ( const JointIdMap q)

◆ setJointPosition() [3/4]

bool XBot::KinematicChain::setJointPosition ( const JointNameMap q)

◆ setJointPosition() [4/4]

bool XBot::KinematicChain::setJointPosition ( int  i,
double  q 
)

◆ setJointVelocity() [1/4]

bool XBot::KinematicChain::setJointVelocity ( const Eigen::VectorXd &  qdot)

◆ setJointVelocity() [2/4]

bool XBot::KinematicChain::setJointVelocity ( const JointIdMap qdot)

◆ setJointVelocity() [3/4]

bool XBot::KinematicChain::setJointVelocity ( const JointNameMap qdot)

◆ setJointVelocity() [4/4]

bool XBot::KinematicChain::setJointVelocity ( int  i,
double  qdot 
)

◆ setMotorPosition() [1/4]

bool XBot::KinematicChain::setMotorPosition ( const Eigen::VectorXd &  q)

◆ setMotorPosition() [2/4]

bool XBot::KinematicChain::setMotorPosition ( const JointIdMap q)

◆ setMotorPosition() [3/4]

bool XBot::KinematicChain::setMotorPosition ( const JointNameMap q)

◆ setMotorPosition() [4/4]

bool XBot::KinematicChain::setMotorPosition ( int  i,
double  q 
)

◆ setMotorVelocity() [1/4]

bool XBot::KinematicChain::setMotorVelocity ( const Eigen::VectorXd &  qdot)

◆ setMotorVelocity() [2/4]

bool XBot::KinematicChain::setMotorVelocity ( const JointIdMap qdot)

◆ setMotorVelocity() [3/4]

bool XBot::KinematicChain::setMotorVelocity ( const JointNameMap qdot)

◆ setMotorVelocity() [4/4]

bool XBot::KinematicChain::setMotorVelocity ( int  i,
double  qdot 
)

◆ setPositionReference() [1/4]

bool XBot::KinematicChain::setPositionReference ( const Eigen::VectorXd &  q)

◆ setPositionReference() [2/4]

bool XBot::KinematicChain::setPositionReference ( const JointIdMap q)

◆ setPositionReference() [3/4]

bool XBot::KinematicChain::setPositionReference ( const JointNameMap q)

◆ setPositionReference() [4/4]

bool XBot::KinematicChain::setPositionReference ( int  i,
double  q 
)

◆ setStiffness() [1/4]

bool XBot::KinematicChain::setStiffness ( const Eigen::VectorXd &  K)

◆ setStiffness() [2/4]

bool XBot::KinematicChain::setStiffness ( const JointIdMap K)

◆ setStiffness() [3/4]

bool XBot::KinematicChain::setStiffness ( const JointNameMap K)

◆ setStiffness() [4/4]

bool XBot::KinematicChain::setStiffness ( int  i,
double  K 
)

◆ setTemperature() [1/4]

bool XBot::KinematicChain::setTemperature ( const Eigen::VectorXd &  temp)

◆ setTemperature() [2/4]

bool XBot::KinematicChain::setTemperature ( const JointIdMap temp)

◆ setTemperature() [3/4]

bool XBot::KinematicChain::setTemperature ( const JointNameMap temp)

◆ setTemperature() [4/4]

bool XBot::KinematicChain::setTemperature ( int  i,
double  temp 
)

◆ setVelocityReference() [1/4]

bool XBot::KinematicChain::setVelocityReference ( const Eigen::VectorXd &  qdot)

◆ setVelocityReference() [2/4]

bool XBot::KinematicChain::setVelocityReference ( const JointIdMap qdot)

◆ setVelocityReference() [3/4]

bool XBot::KinematicChain::setVelocityReference ( const JointNameMap qdot)

◆ setVelocityReference() [4/4]

bool XBot::KinematicChain::setVelocityReference ( int  i,
double  qdot 
)

◆ shallowCopy()

void XBot::KinematicChain::shallowCopy ( const KinematicChain chain)

Updates the current object (this) by performing a shallow copy with the chain passed as argument.

Parameters
chainthe chain to shallow copy
Returns
void

◆ syncFrom()

template<typename... SyncFlags>
bool XBot::KinematicChain::syncFrom ( const KinematicChain other,
SyncFlags...  flags 
)

Synchronize the current KinematicChain with another KinematicChain object.

Parameters
otherThe KinematicChain object from which we synchronize the current object
flagsFlags to specify what part of the state must be synchronized. By default (i.e. if this argument is omitted) the whole state is synchronized. Otherwise, an arbitrary number of flags can be specified in order to select a subset of the state. The flags must be of the enum type XBot::Sync, which can take the following values:
Returns
bool

Friends And Related Function Documentation

◆ operator<<

std::ostream& operator<< ( std::ostream &  os,
const XBot::KinematicChain c 
)
friend

Member Data Documentation

◆ _ft_map

std::map<std::string, ForceTorqueSensor::Ptr> XBot::KinematicChain::_ft_map
protected

◆ _ft_vector

std::vector<ForceTorqueSensor::Ptr> XBot::KinematicChain::_ft_vector
protected

◆ _imu_map

std::map<std::string, ImuSensor::Ptr> XBot::KinematicChain::_imu_map
protected

◆ _imu_vector

std::vector<ImuSensor::Ptr> XBot::KinematicChain::_imu_vector
protected

◆ _joint_id_map

std::map<int, XBot::Joint::Ptr> XBot::KinematicChain::_joint_id_map
protected

◆ _joint_name_map

std::map<std::string, XBot::Joint::Ptr> XBot::KinematicChain::_joint_name_map
protected

◆ _joint_vector

std::vector<XBot::Joint::Ptr> XBot::KinematicChain::_joint_vector
protected

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