wbc
wbc::RobotModel Class Referenceabstract

Interface for all robot models. This has to provide all kinematics and dynamics information that is required for WBC. More...

#include <RobotModel.hpp>

Inheritance diagram for wbc::RobotModel:
wbc::RobotModelHyrodyn wbc::RobotModelPinocchio wbc::RobotModelRBDL

Public Member Functions

 RobotModel ()
 
virtual ~RobotModel ()
 
virtual bool configure (const RobotModelConfig &cfg)=0
 Load and configure the robot model.
 
virtual void update (const base::samples::Joints &joint_state, const base::samples::RigidBodyStateSE3 &floating_base_state=base::samples::RigidBodyStateSE3())=0
 Update the robot configuration.
 
const base::samples::Joints & jointState (const std::vector< std::string > &joint_names)
 
virtual void systemState (base::VectorXd &q, base::VectorXd &qd, base::VectorXd &qdd)=0
 
virtual const base::samples::RigidBodyStateSE3 & rigidBodyState (const std::string &root_frame, const std::string &tip_frame)=0
 
virtual const base::MatrixXd & spaceJacobian (const std::string &root_frame, const std::string &tip_frame)=0
 Returns the Space Jacobian for the kinematic chain between root and the tip frame as full body Jacobian. Size of the Jacobian will be 6 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the configured joint order of the robot. The columns that correspond to joints that are not part of the kinematic chain will have only zeros as entries.
 
virtual const base::MatrixXd & bodyJacobian (const std::string &root_frame, const std::string &tip_frame)=0
 Returns the Body Jacobian for the kinematic chain between root and the tip frame as full body Jacobian. Size of the Jacobian will be 6 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the configured joint order of the robot. The columns that correspond to joints that are not part of the kinematic chain will have only zeros as entries.
 
virtual const base::MatrixXd & comJacobian ()=0
 Returns the CoM Jacobian for the entire robot, which maps the robot joint velocities to linear spatial velocities in robot base coordinates. Size of the Jacobian will be 3 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the configured joint order of the robot.
 
virtual const base::Acceleration & spatialAccelerationBias (const std::string &root_frame, const std::string &tip_frame)=0
 Returns the spatial acceleration bias, i.e. the term Jdot*qdot.
 
virtual const base::MatrixXd & jacobianDot (const std::string &root_frame, const std::string &tip_frame)=0
 Returns the derivative of the Jacobian for the kinematic chain between root and the tip frame as full body Jacobian. By convention reference frame & reference point of the Jacobian will be the root frame (corresponding to the body Jacobian). Size of the Jacobian will be 6 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the joint order of the robot. The columns that correspond to joints that are not part of the kinematic chain will have only zeros as entries.
 
virtual const base::MatrixXd & jointSpaceInertiaMatrix ()=0
 Compute and return the joint space mass-inertia matrix, which is nj x nj, where nj is the number of joints of the system.
 
virtual const base::VectorXd & biasForces ()=0
 Compute and return the bias force vector, which is nj x 1, where nj is the number of joints of the system.
 
const std::vector< std::string > & jointNames ()
 Return all joint names.
 
const std::vector< std::string > & actuatedJointNames ()
 Return only actuated joint names.
 
const std::vector< std::string > & independentJointNames ()
 Return only independent joint names.
 
uint jointIndex (const std::string &joint_name)
 Get index of joint name.
 
const std::string & baseFrame ()
 Get the base frame of the robot.
 
const std::string & worldFrame ()
 Get the world frame id.
 
const base::JointLimits & jointLimits ()
 Return current joint limits.
 
bool hasLink (const std::string &link_name)
 Return True if given link name is available in robot model, false otherwise.
 
bool hasJoint (const std::string &joint_name)
 Return True if given joint name is available in robot model, false otherwise.
 
bool hasActuatedJoint (const std::string &joint_name)
 Return True if given joint name is an actuated joint in robot model, false otherwise.
 
const base::MatrixXd & selectionMatrix ()
 Return current selection matrix S that maps complete joint vector to actuated joint vector: q_a = S * q. The matrix consists of only zeros and ones. Size is na x nq, where na is the number of actuated joints and nq the total number of joints.
 
virtual const base::samples::RigidBodyStateSE3 & centerOfMass ()=0
 Compute and return center of mass expressed in base frame.
 
void setActiveContacts (const ActiveContacts &contacts)
 Provide information about which link is currently in contact with the environment.
 
const ActiveContactsgetActiveContacts ()
 Provide links names that are possibly in contact with the environment (typically the end effector links)
 
uint noOfJoints ()
 Return number of joints.
 
uint noOfActuatedJoints ()
 Return number of actuated/active joints.
 
void setGravityVector (const base::Vector3d &g)
 Set the current gravity vector.
 
const base::samples::RigidBodyStateSE3 & floatingBaseState ()
 Get current status of floating base.
 
void setContactWrenches (const base::samples::Wrenches &wrenches)
 Set contact wrenches, names have to consistent with the configured contact points.
 
virtual void computeInverseDynamics (base::commands::Joints &solver_output)=0
 Compute and return the inverse dynamics solution.
 
const RobotModelConfiggetRobotModelConfig ()
 Get current robot model config.
 
bool hasFloatingBase ()
 Is floating base robot?
 
urdf::ModelInterfaceSharedPtr loadRobotURDF (const std::string &file_or_string)
 Load URDF model from either file or string.
 

Protected Types

typedef std::map< std::string, base::MatrixXd > JacobianMap
 

Protected Member Functions

void clear ()
 
const std::string chainID (const std::string &root, const std::string &tip)
 

Protected Attributes

ActiveContacts active_contacts
 
base::Vector3d gravity
 
base::samples::RigidBodyStateSE3 floating_base_state
 
base::samples::Wrenches contact_wrenches
 
RobotModelConfig robot_model_config
 
std::string world_frame
 
std::string base_frame
 
base::JointLimits joint_limits
 
std::vector< std::string > actuated_joint_names
 
std::vector< std::string > independent_joint_names
 
std::vector< std::string > joint_names
 
std::vector< std::string > joint_names_floating_base
 
urdf::ModelInterfaceSharedPtr robot_urdf
 
bool has_floating_base
 
base::samples::Joints joint_state
 
base::MatrixXd joint_space_inertia_mat
 
base::MatrixXd com_jac
 
base::VectorXd bias_forces
 
base::Acceleration spatial_acc_bias
 
base::MatrixXd selection_matrix
 
base::samples::RigidBodyStateSE3 com_rbs
 
base::samples::RigidBodyStateSE3 rbs
 
JacobianMap space_jac_map
 
JacobianMap body_jac_map
 
JacobianMap jac_dot_map
 
base::samples::Joints joint_state_out
 

Detailed Description

Interface for all robot models. This has to provide all kinematics and dynamics information that is required for WBC.

Member Typedef Documentation

◆ JacobianMap

std::map<std::string, base::MatrixXd > wbc::RobotModel::JacobianMap
protected

Constructor & Destructor Documentation

◆ RobotModel()

wbc::RobotModel::RobotModel ( )

◆ ~RobotModel()

virtual wbc::RobotModel::~RobotModel ( )
inlinevirtual

Member Function Documentation

◆ actuatedJointNames()

const std::vector< std::string > & wbc::RobotModel::actuatedJointNames ( )
inline

Return only actuated joint names.

◆ baseFrame()

const std::string & wbc::RobotModel::baseFrame ( )
inline

Get the base frame of the robot.

◆ biasForces()

virtual const base::VectorXd & wbc::RobotModel::biasForces ( )
pure virtual

Compute and return the bias force vector, which is nj x 1, where nj is the number of joints of the system.

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ bodyJacobian()

virtual const base::MatrixXd & wbc::RobotModel::bodyJacobian ( const std::string & root_frame,
const std::string & tip_frame )
pure virtual

Returns the Body Jacobian for the kinematic chain between root and the tip frame as full body Jacobian. Size of the Jacobian will be 6 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the configured joint order of the robot. The columns that correspond to joints that are not part of the kinematic chain will have only zeros as entries.

Parameters
root_frameRoot frame of the chain. Has to be a valid link in the robot model.
tip_frameTip frame of the chain. Has to be a valid link in the robot model.
Returns
A 6xN matrix, where N is the number of robot joints

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ centerOfMass()

virtual const base::samples::RigidBodyStateSE3 & wbc::RobotModel::centerOfMass ( )
pure virtual

Compute and return center of mass expressed in base frame.

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ chainID()

const std::string wbc::RobotModel::chainID ( const std::string & root,
const std::string & tip )
inlineprotected

ID of kinematic chain given root and tip

◆ clear()

void wbc::RobotModel::clear ( )
protected

◆ comJacobian()

virtual const base::MatrixXd & wbc::RobotModel::comJacobian ( )
pure virtual

Returns the CoM Jacobian for the entire robot, which maps the robot joint velocities to linear spatial velocities in robot base coordinates. Size of the Jacobian will be 3 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the configured joint order of the robot.

Returns
A 3xN matrix, where N is the number of robot joints

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ computeInverseDynamics()

virtual void wbc::RobotModel::computeInverseDynamics ( base::commands::Joints & solver_output)
pure virtual

Compute and return the inverse dynamics solution.

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ configure()

virtual bool wbc::RobotModel::configure ( const RobotModelConfig & cfg)
pure virtual

Load and configure the robot model.

Parameters
cfgModel configuration. See RobotModelConfig.hpp for details
Returns
True in case of success, else false

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ floatingBaseState()

const base::samples::RigidBodyStateSE3 & wbc::RobotModel::floatingBaseState ( )
inline

Get current status of floating base.

◆ getActiveContacts()

const ActiveContacts & wbc::RobotModel::getActiveContacts ( )
inline

Provide links names that are possibly in contact with the environment (typically the end effector links)

◆ getRobotModelConfig()

const RobotModelConfig & wbc::RobotModel::getRobotModelConfig ( )
inline

Get current robot model config.

◆ hasActuatedJoint()

bool wbc::RobotModel::hasActuatedJoint ( const std::string & joint_name)

Return True if given joint name is an actuated joint in robot model, false otherwise.

◆ hasFloatingBase()

bool wbc::RobotModel::hasFloatingBase ( )
inline

Is floating base robot?

◆ hasJoint()

bool wbc::RobotModel::hasJoint ( const std::string & joint_name)

Return True if given joint name is available in robot model, false otherwise.

◆ hasLink()

bool wbc::RobotModel::hasLink ( const std::string & link_name)

Return True if given link name is available in robot model, false otherwise.

◆ independentJointNames()

const std::vector< std::string > & wbc::RobotModel::independentJointNames ( )
inline

Return only independent joint names.

◆ jacobianDot()

virtual const base::MatrixXd & wbc::RobotModel::jacobianDot ( const std::string & root_frame,
const std::string & tip_frame )
pure virtual

Returns the derivative of the Jacobian for the kinematic chain between root and the tip frame as full body Jacobian. By convention reference frame & reference point of the Jacobian will be the root frame (corresponding to the body Jacobian). Size of the Jacobian will be 6 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the joint order of the robot. The columns that correspond to joints that are not part of the kinematic chain will have only zeros as entries.

Parameters
root_frameRoot frame of the chain. Has to be a valid link in the robot model.
tip_frameTip frame of the chain. Has to be a valid link in the robot model.
Returns
A 6xN matrix, where N is the number of robot joints

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ jointIndex()

uint wbc::RobotModel::jointIndex ( const std::string & joint_name)

Get index of joint name.

◆ jointLimits()

const base::JointLimits & wbc::RobotModel::jointLimits ( )
inline

Return current joint limits.

◆ jointNames()

const std::vector< std::string > & wbc::RobotModel::jointNames ( )
inline

Return all joint names.

◆ jointSpaceInertiaMatrix()

virtual const base::MatrixXd & wbc::RobotModel::jointSpaceInertiaMatrix ( )
pure virtual

Compute and return the joint space mass-inertia matrix, which is nj x nj, where nj is the number of joints of the system.

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ jointState()

const base::samples::Joints & wbc::RobotModel::jointState ( const std::vector< std::string > & joint_names)

Returns the current status of the given joint names

◆ loadRobotURDF()

urdf::ModelInterfaceSharedPtr wbc::RobotModel::loadRobotURDF ( const std::string & file_or_string)

Load URDF model from either file or string.

◆ noOfActuatedJoints()

uint wbc::RobotModel::noOfActuatedJoints ( )
inline

Return number of actuated/active joints.

◆ noOfJoints()

uint wbc::RobotModel::noOfJoints ( )
inline

Return number of joints.

◆ rigidBodyState()

virtual const base::samples::RigidBodyStateSE3 & wbc::RobotModel::rigidBodyState ( const std::string & root_frame,
const std::string & tip_frame )
pure virtual

Returns the pose, twist and spatial acceleration between the two given frames. All quantities are defined in root_frame coordinates

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ selectionMatrix()

const base::MatrixXd & wbc::RobotModel::selectionMatrix ( )
inline

Return current selection matrix S that maps complete joint vector to actuated joint vector: q_a = S * q. The matrix consists of only zeros and ones. Size is na x nq, where na is the number of actuated joints and nq the total number of joints.

◆ setActiveContacts()

void wbc::RobotModel::setActiveContacts ( const ActiveContacts & contacts)

Provide information about which link is currently in contact with the environment.

◆ setContactWrenches()

void wbc::RobotModel::setContactWrenches ( const base::samples::Wrenches & wrenches)
inline

Set contact wrenches, names have to consistent with the configured contact points.

◆ setGravityVector()

void wbc::RobotModel::setGravityVector ( const base::Vector3d & g)
inline

Set the current gravity vector.

◆ spaceJacobian()

virtual const base::MatrixXd & wbc::RobotModel::spaceJacobian ( const std::string & root_frame,
const std::string & tip_frame )
pure virtual

Returns the Space Jacobian for the kinematic chain between root and the tip frame as full body Jacobian. Size of the Jacobian will be 6 x nJoints, where nJoints is the number of joints of the whole robot. The order of the columns will be the same as the configured joint order of the robot. The columns that correspond to joints that are not part of the kinematic chain will have only zeros as entries.

Parameters
root_frameRoot frame of the chain. Has to be a valid link in the robot model.
tip_frameTip frame of the chain. Has to be a valid link in the robot model.
Returns
A 6xN matrix, where N is the number of robot joints

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ spatialAccelerationBias()

virtual const base::Acceleration & wbc::RobotModel::spatialAccelerationBias ( const std::string & root_frame,
const std::string & tip_frame )
pure virtual

Returns the spatial acceleration bias, i.e. the term Jdot*qdot.

Parameters
root_frameRoot frame of the chain. Has to be a valid link in the robot model.
tip_frameTip frame of the chain. Has to be a valid link in the robot model.
Returns
A Nx1 vector, where N is the number of robot joints

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ systemState()

virtual void wbc::RobotModel::systemState ( base::VectorXd & q,
base::VectorXd & qd,
base::VectorXd & qdd )
pure virtual

Return entire system state

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ update()

virtual void wbc::RobotModel::update ( const base::samples::Joints & joint_state,
const base::samples::RigidBodyStateSE3 & floating_base_state = base::samples::RigidBodyStateSE3() )
pure virtual

Update the robot configuration.

Parameters
joint_stateThe joint_state vector. Has to contain all robot joints that are configured in the model.
posesOptional, only for floating base robots: update the floating base state of the robot model.

Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.

◆ worldFrame()

const std::string & wbc::RobotModel::worldFrame ( )
inline

Get the world frame id.

Member Data Documentation

◆ active_contacts

ActiveContacts wbc::RobotModel::active_contacts
protected

◆ actuated_joint_names

std::vector<std::string> wbc::RobotModel::actuated_joint_names
protected

◆ base_frame

std::string wbc::RobotModel::base_frame
protected

◆ bias_forces

base::VectorXd wbc::RobotModel::bias_forces
protected

◆ body_jac_map

JacobianMap wbc::RobotModel::body_jac_map
protected

◆ com_jac

base::MatrixXd wbc::RobotModel::com_jac
protected

◆ com_rbs

base::samples::RigidBodyStateSE3 wbc::RobotModel::com_rbs
protected

◆ contact_wrenches

base::samples::Wrenches wbc::RobotModel::contact_wrenches
protected

◆ floating_base_state

base::samples::RigidBodyStateSE3 wbc::RobotModel::floating_base_state
protected

◆ gravity

base::Vector3d wbc::RobotModel::gravity
protected

◆ has_floating_base

bool wbc::RobotModel::has_floating_base
protected

◆ independent_joint_names

std::vector<std::string> wbc::RobotModel::independent_joint_names
protected

◆ jac_dot_map

JacobianMap wbc::RobotModel::jac_dot_map
protected

◆ joint_limits

base::JointLimits wbc::RobotModel::joint_limits
protected

◆ joint_names

std::vector<std::string> wbc::RobotModel::joint_names
protected

◆ joint_names_floating_base

std::vector<std::string> wbc::RobotModel::joint_names_floating_base
protected

◆ joint_space_inertia_mat

base::MatrixXd wbc::RobotModel::joint_space_inertia_mat
protected

◆ joint_state

base::samples::Joints wbc::RobotModel::joint_state
protected

◆ joint_state_out

base::samples::Joints wbc::RobotModel::joint_state_out
protected

◆ rbs

base::samples::RigidBodyStateSE3 wbc::RobotModel::rbs
protected

◆ robot_model_config

RobotModelConfig wbc::RobotModel::robot_model_config
protected

◆ robot_urdf

urdf::ModelInterfaceSharedPtr wbc::RobotModel::robot_urdf
protected

◆ selection_matrix

base::MatrixXd wbc::RobotModel::selection_matrix
protected

◆ space_jac_map

JacobianMap wbc::RobotModel::space_jac_map
protected

◆ spatial_acc_bias

base::Acceleration wbc::RobotModel::spatial_acc_bias
protected

◆ world_frame

std::string wbc::RobotModel::world_frame
protected

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