wbc
|
Interface for all robot models. This has to provide all kinematics and dynamics information that is required for WBC. More...
#include <RobotModel.hpp>
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 ActiveContacts & | getActiveContacts () |
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 RobotModelConfig & | getRobotModelConfig () |
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 |
Interface for all robot models. This has to provide all kinematics and dynamics information that is required for WBC.
|
protected |
wbc::RobotModel::RobotModel | ( | ) |
|
inlinevirtual |
|
inline |
Return only actuated joint names.
|
inline |
Get the base frame of the robot.
|
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.
|
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.
root_frame | Root frame of the chain. Has to be a valid link in the robot model. |
tip_frame | Tip frame of the chain. Has to be a valid link in the robot model. |
Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.
|
pure virtual |
Compute and return center of mass expressed in base frame.
Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.
|
inlineprotected |
ID of kinematic chain given root and tip
|
protected |
|
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.
Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.
|
pure virtual |
Compute and return the inverse dynamics solution.
Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.
|
pure virtual |
Load and configure the robot model.
cfg | Model configuration. See RobotModelConfig.hpp for details |
Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.
|
inline |
Get current status of floating base.
|
inline |
Provide links names that are possibly in contact with the environment (typically the end effector links)
|
inline |
Get current robot model config.
bool wbc::RobotModel::hasActuatedJoint | ( | const std::string & | joint_name | ) |
Return True if given joint name is an actuated joint in robot model, false otherwise.
|
inline |
Is floating base robot?
bool wbc::RobotModel::hasJoint | ( | const std::string & | joint_name | ) |
Return True if given joint name is available in robot model, false otherwise.
bool wbc::RobotModel::hasLink | ( | const std::string & | link_name | ) |
Return True if given link name is available in robot model, false otherwise.
|
inline |
Return only independent joint names.
|
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.
root_frame | Root frame of the chain. Has to be a valid link in the robot model. |
tip_frame | Tip frame of the chain. Has to be a valid link in the robot model. |
Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.
uint wbc::RobotModel::jointIndex | ( | const std::string & | joint_name | ) |
Get index of joint name.
|
inline |
Return current joint limits.
|
inline |
Return all joint names.
|
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.
const base::samples::Joints & wbc::RobotModel::jointState | ( | const std::vector< std::string > & | joint_names | ) |
Returns the current status of the given joint names
urdf::ModelInterfaceSharedPtr wbc::RobotModel::loadRobotURDF | ( | const std::string & | file_or_string | ) |
Load URDF model from either file or string.
|
inline |
Return number of actuated/active joints.
|
inline |
Return number of joints.
|
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.
|
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.
void wbc::RobotModel::setActiveContacts | ( | const ActiveContacts & | contacts | ) |
Provide information about which link is currently in contact with the environment.
|
inline |
Set contact wrenches, names have to consistent with the configured contact points.
|
inline |
Set the current gravity vector.
|
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.
root_frame | Root frame of the chain. Has to be a valid link in the robot model. |
tip_frame | Tip frame of the chain. Has to be a valid link in the robot model. |
Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.
|
pure virtual |
Returns the spatial acceleration bias, i.e. the term Jdot*qdot.
root_frame | Root frame of the chain. Has to be a valid link in the robot model. |
tip_frame | Tip frame of the chain. Has to be a valid link in the robot model. |
Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.
|
pure virtual |
Return entire system state
Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.
|
pure virtual |
Update the robot configuration.
joint_state | The joint_state vector. Has to contain all robot joints that are configured in the model. |
poses | Optional, only for floating base robots: update the floating base state of the robot model. |
Implemented in wbc::RobotModelHyrodyn, wbc::RobotModelPinocchio, and wbc::RobotModelRBDL.
|
inline |
Get the world frame id.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |