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

Kinematic chain useful for a robot abstraction. More...

#include <RobotChain.h>

+ Inheritance diagram for XBot::RobotChain:
+ Collaboration diagram for XBot::RobotChain:

Public Types

typedef std::shared_ptr< RobotChainPtr
 
- Public Types inherited from XBot::KinematicChain
typedef std::shared_ptr< KinematicChainPtr
 
typedef std::shared_ptr< const KinematicChainConstPtr
 

Public Member Functions

 RobotChain ()
 
template<typename... SyncFlags>
bool setReferenceFrom (const ModelChain &model_chain, SyncFlags... flags)
 Setter for the robot chain references using a model chain. More...
 
bool getJointPosition (Eigen::VectorXd &q) const
 
bool getJointPosition (JointIdMap &q) const
 
bool getJointPosition (JointNameMap &q) const
 
double getJointPosition (int index) const
 
bool getMotorPosition (Eigen::VectorXd &q) const
 
bool getMotorPosition (JointIdMap &q) const
 
bool getMotorPosition (JointNameMap &q) const
 
double getMotorPosition (int index) const
 
bool getJointVelocity (Eigen::VectorXd &qdot) const
 
bool getJointVelocity (JointIdMap &qdot) const
 
bool getJointVelocity (JointNameMap &qdot) const
 
double getJointVelocity (int index) const
 
bool getMotorVelocity (Eigen::VectorXd &qdot) const
 
bool getMotorVelocity (JointIdMap &qdot) const
 
bool getMotorVelocity (JointNameMap &qdot) const
 
double getMotorVelocity (int index) const
 
bool getJointEffort (Eigen::VectorXd &tau) const
 
bool getJointEffort (JointIdMap &tau) const
 
bool getJointEffort (JointNameMap &tau) const
 
double getJointEffort (int index) const
 
bool getTemperature (Eigen::VectorXd &temp) const
 
bool getTemperature (JointIdMap &temp) const
 
bool getTemperature (JointNameMap &temp) const
 
double getTemperature (int index) const
 
bool getPositionReference (Eigen::VectorXd &q) const
 
bool getPositionReference (JointIdMap &q) const
 
bool getPositionReference (JointNameMap &q) const
 
double getPositionReference (int index) const
 
bool getVelocityReference (Eigen::VectorXd &qdot) const
 
bool getVelocityReference (JointIdMap &qdot) const
 
bool getVelocityReference (JointNameMap &qdot) const
 
double getVelocityReference (int index) const
 
bool getEffortReference (Eigen::VectorXd &tau) const
 
bool getEffortReference (JointIdMap &tau) const
 
bool getEffortReference (JointNameMap &tau) const
 
double getEffortReference (int index) const
 
bool getStiffness (Eigen::VectorXd &K) const
 
bool getStiffness (JointIdMap &K) const
 
bool getStiffness (JointNameMap &K) const
 
double getStiffness (int index) const
 
bool getDamping (Eigen::VectorXd &D) const
 
bool getDamping (JointIdMap &D) const
 
bool getDamping (JointNameMap &D) const
 
double getDamping (int index) const
 
bool setPositionReference (const Eigen::VectorXd &q)
 
bool setPositionReference (const JointIdMap &q)
 
bool setPositionReference (const JointNameMap &q)
 
bool setPositionReference (int i, double q)
 
bool setVelocityReference (const Eigen::VectorXd &qdot)
 
bool setVelocityReference (const JointIdMap &qdot)
 
bool setVelocityReference (const JointNameMap &qdot)
 
bool setVelocityReference (int i, double qdot)
 
bool setEffortReference (const Eigen::VectorXd &tau)
 
bool setEffortReference (const JointIdMap &tau)
 
bool setEffortReference (const JointNameMap &tau)
 
bool setEffortReference (int i, double tau)
 
bool setStiffness (const Eigen::VectorXd &K)
 
bool setStiffness (const JointIdMap &K)
 
bool setStiffness (const JointNameMap &K)
 
bool setStiffness (int i, double K)
 
bool setDamping (const Eigen::VectorXd &D)
 
bool setDamping (const JointIdMap &D)
 
bool setDamping (const JointNameMap &D)
 
bool setDamping (int i, double D)
 
- Public Member Functions inherited from XBot::KinematicChain
 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...
 

Additional Inherited Members

- Protected Member Functions inherited from XBot::KinematicChain
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 inherited from XBot::KinematicChain
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
 

Detailed Description

Kinematic chain useful for a robot abstraction.

Member Typedef Documentation

◆ Ptr

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

Constructor & Destructor Documentation

◆ RobotChain()

XBot::RobotChain::RobotChain ( )

Member Function Documentation

◆ getDamping() [1/4]

bool XBot::KinematicChain::getDamping

◆ getDamping() [2/4]

double XBot::KinematicChain::getDamping

◆ getDamping() [3/4]

bool XBot::KinematicChain::getDamping

◆ getDamping() [4/4]

bool XBot::KinematicChain::getDamping

◆ getEffortReference() [1/4]

bool XBot::KinematicChain::getEffortReference

◆ getEffortReference() [2/4]

double XBot::KinematicChain::getEffortReference

◆ getEffortReference() [3/4]

bool XBot::KinematicChain::getEffortReference

◆ getEffortReference() [4/4]

bool XBot::KinematicChain::getEffortReference

◆ getJointEffort() [1/4]

bool XBot::KinematicChain::getJointEffort

◆ getJointEffort() [2/4]

double XBot::KinematicChain::getJointEffort

◆ getJointEffort() [3/4]

bool XBot::KinematicChain::getJointEffort

◆ getJointEffort() [4/4]

bool XBot::KinematicChain::getJointEffort

◆ getJointPosition() [1/4]

bool XBot::KinematicChain::getJointPosition

◆ getJointPosition() [2/4]

double XBot::KinematicChain::getJointPosition

◆ getJointPosition() [3/4]

bool XBot::KinematicChain::getJointPosition

◆ getJointPosition() [4/4]

bool XBot::KinematicChain::getJointPosition

◆ getJointVelocity() [1/4]

bool XBot::KinematicChain::getJointVelocity

◆ getJointVelocity() [2/4]

double XBot::KinematicChain::getJointVelocity

◆ getJointVelocity() [3/4]

bool XBot::KinematicChain::getJointVelocity

◆ getJointVelocity() [4/4]

bool XBot::KinematicChain::getJointVelocity

◆ getMotorPosition() [1/4]

bool XBot::KinematicChain::getMotorPosition

◆ getMotorPosition() [2/4]

double XBot::KinematicChain::getMotorPosition

◆ getMotorPosition() [3/4]

bool XBot::KinematicChain::getMotorPosition

◆ getMotorPosition() [4/4]

bool XBot::KinematicChain::getMotorPosition

◆ getMotorVelocity() [1/4]

bool XBot::KinematicChain::getMotorVelocity

◆ getMotorVelocity() [2/4]

double XBot::KinematicChain::getMotorVelocity

◆ getMotorVelocity() [3/4]

bool XBot::KinematicChain::getMotorVelocity

◆ getMotorVelocity() [4/4]

bool XBot::KinematicChain::getMotorVelocity

◆ getPositionReference() [1/4]

bool XBot::KinematicChain::getPositionReference

◆ getPositionReference() [2/4]

double XBot::KinematicChain::getPositionReference

◆ getPositionReference() [3/4]

bool XBot::KinematicChain::getPositionReference

◆ getPositionReference() [4/4]

bool XBot::KinematicChain::getPositionReference

◆ getStiffness() [1/4]

bool XBot::KinematicChain::getStiffness

◆ getStiffness() [2/4]

double XBot::KinematicChain::getStiffness

◆ getStiffness() [3/4]

bool XBot::KinematicChain::getStiffness

◆ getStiffness() [4/4]

bool XBot::KinematicChain::getStiffness

◆ getTemperature() [1/4]

bool XBot::KinematicChain::getTemperature

◆ getTemperature() [2/4]

double XBot::KinematicChain::getTemperature

◆ getTemperature() [3/4]

bool XBot::KinematicChain::getTemperature

◆ getTemperature() [4/4]

bool XBot::KinematicChain::getTemperature

◆ getVelocityReference() [1/4]

bool XBot::KinematicChain::getVelocityReference

◆ getVelocityReference() [2/4]

double XBot::KinematicChain::getVelocityReference

◆ getVelocityReference() [3/4]

bool XBot::KinematicChain::getVelocityReference

◆ getVelocityReference() [4/4]

bool XBot::KinematicChain::getVelocityReference

◆ setDamping() [1/4]

bool XBot::KinematicChain::setDamping

◆ setDamping() [2/4]

bool XBot::KinematicChain::setDamping

◆ setDamping() [3/4]

bool XBot::KinematicChain::setDamping

◆ setDamping() [4/4]

bool XBot::KinematicChain::setDamping

◆ setEffortReference() [1/4]

bool XBot::KinematicChain::setEffortReference

◆ setEffortReference() [2/4]

bool XBot::KinematicChain::setEffortReference

◆ setEffortReference() [3/4]

bool XBot::KinematicChain::setEffortReference

◆ setEffortReference() [4/4]

bool XBot::KinematicChain::setEffortReference

◆ setPositionReference() [1/4]

bool XBot::KinematicChain::setPositionReference

◆ setPositionReference() [2/4]

bool XBot::KinematicChain::setPositionReference

◆ setPositionReference() [3/4]

bool XBot::KinematicChain::setPositionReference

◆ setPositionReference() [4/4]

bool XBot::KinematicChain::setPositionReference

◆ setReferenceFrom()

template<typename... SyncFlags>
bool XBot::RobotChain::setReferenceFrom ( const ModelChain model_chain,
SyncFlags...  flags 
)

Setter for the robot chain references using a model chain.

Parameters
model_chainthe model chain reference to set on the current robot chain
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
true on success, false otherwise

◆ setStiffness() [1/4]

bool XBot::KinematicChain::setStiffness

◆ setStiffness() [2/4]

bool XBot::KinematicChain::setStiffness

◆ setStiffness() [3/4]

bool XBot::KinematicChain::setStiffness

◆ setStiffness() [4/4]

bool XBot::KinematicChain::setStiffness

◆ setVelocityReference() [1/4]

bool XBot::KinematicChain::setVelocityReference

◆ setVelocityReference() [2/4]

bool XBot::KinematicChain::setVelocityReference

◆ setVelocityReference() [3/4]

bool XBot::KinematicChain::setVelocityReference

◆ setVelocityReference() [4/4]

bool XBot::KinematicChain::setVelocityReference

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