wbc
wbc::RobotModel Class Referenceabstract

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

#include <RobotModel.hpp>

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

Classes

struct  Matrix
 
struct  Pose
 
struct  RigidBodyState
 
struct  SpatialAcceleration
 
struct  Twist
 
struct  Vector
 

Public Member Functions

 RobotModel ()
 
virtual ~RobotModel ()
 
virtual bool configure (const RobotModelConfig &cfg)=0
 This will read the robot model from the given URDF file and initialize all members accordingly.
 
void update (const Eigen::VectorXd &joint_positions, const Eigen::VectorXd &joint_velocities)
 Update kinematics/dynamics for fixed base robots. Joint acceleration will be assumed zero.
 
virtual void update (const Eigen::VectorXd &joint_positions, const Eigen::VectorXd &joint_velocities, const Eigen::VectorXd &joint_accelerations)
 Update kinematics/dynamics for fixed base robots.
 
void update (const Eigen::VectorXd &joint_positions, const Eigen::VectorXd &joint_velocities, const types::Pose &fb_pose, const types::Twist &fb_twist)
 Update kinematics/dynamics for floating base robots. Joint and spatial acceleration will be assumed zero.
 
virtual void update (const Eigen::VectorXd &joint_positions, const Eigen::VectorXd &joint_velocities, const Eigen::VectorXd &joint_accelerations, const types::Pose &fb_pose, const types::Twist &fb_twist, const types::SpatialAcceleration &fb_acc)=0
 Update kinematics/dynamics.
 
const types::JointStatejointState ()
 
virtual const types::Posepose (const std::string &frame_id)=0
 
virtual const types::Twisttwist (const std::string &frame_id)=0
 
virtual const types::SpatialAccelerationacceleration (const std::string &frame_id)=0
 
virtual const Eigen::MatrixXd & spaceJacobian (const std::string &frame_id)=0
 Returns the Space Jacobian for the given frame. The order of the Jacobian's columns will be the same as in the model (alphabetic). Note that the linear part of the jacobian will be aligned to world frame (floating base robot) or robot root link (fixed base), and the angular part will be in body coordinates. This is refered to as "hybrid" representation.
 
virtual const Eigen::MatrixXd & bodyJacobian (const std::string &frame_id)=0
 Returns the Body Jacobian for the given frame. The order of the Jacobian's columns will be the same as in the model (alphabetic).
 
virtual const Eigen::MatrixXd & comJacobian ()=0
 Returns the CoM Jacobian for the robot, which maps the robot joint velocities to linear spatial velocities of the CoM expressed in world frame (floating base robot) or robot root link (fixed base). The order of the columns will be the same as the configured joint order of the robot.
 
virtual const types::SpatialAccelerationspatialAccelerationBias (const std::string &frame_id)=0
 Returns the spatial acceleration bias, i.e. the term Jdot*qdot. The linear part of the acceleration will be aligned to world frame (floating base robot) or robot root link (fixed base), and the angular part will be in body coordinates. This is refered to as "hybrid" representation.
 
virtual const Eigen::MatrixXd & jointSpaceInertiaMatrix ()=0
 Returns the joint space mass-inertia matrix, which is nj x nj, where nj is the number of joints + number of floating coordinates, i.e. 6 in case of a floating base robot.
 
virtual const Eigen::VectorXd & biasForces ()=0
 Returns the bias force vector, which is nj x 1, where nj is the number of joints + number of floating coordinates, i.e. 6 in case of a floating base robot.
 
const std::vector< std::string > & jointNames ()
 Return all joint names excluding the floating base. This will be.
 
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 the internal index for a joint name.
 
const std::string & baseFrame ()
 Get the base frame of the robot, i.e. the root of the URDF model.
 
const std::string & worldFrame ()
 Get the world frame id. Will be "world" in case of floating base robot and equal to base_frame in case of fixed base robot.
 
const types::JointLimits jointLimits ()
 Return current joint limits.
 
const Eigen::MatrixXd & selectionMatrix ()
 Return current selection matrix, mapping actuated to all dof.
 
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.
 
virtual const types::RigidBodyStatecenterOfMass ()=0
 Return centers of mass expressed in world frame.
 
void setContacts (const std::vector< types::Contact > &contacts)
 Set new contact points.
 
const std::vector< types::Contact > & getContacts ()
 get current contact points
 
uint nj ()
 Return number of joints.
 
uint na ()
 Return number of actuated joints.
 
uint nfb ()
 Return dof of the floating base, will be either 0 (floating_base == false) or 6 (floating_base = = false)
 
uint nac ()
 
uint nc ()
 Return total number of contact points.
 
const Eigen::VectorXd & getQ ()
 Return full system position vector, incl. floating base. Convention [floating_base_pos, floating_base_ori, joint_positions]: [fb_x,fb_y,fb_z, fb_qx,fb_qy,fb_qz,fb_qw, q_1 ... q_n)].
 
const Eigen::VectorXd & getQd ()
 Return full system velocity vector, incl. floating base. Convention [floating_base_vel, floating_base_rot_vel, joint_velocities]: [fb_vx,fb_vx,fb_vx, fb_wx,fb_wy,fb_wz, qd_1 ... qd_n)].
 
const Eigen::VectorXd & getQdd ()
 Return full system acceleration vector, incl. floating base. Convention [floating_base_acc, floating_base_rot_acc, joint_accelerations]: [fb_dvx,fb_dvx,fb_dvx, fb_dwx,fb_dwy,fb_dwz, qdd_1 ... qdd_n)].
 
void setGravityVector (const Eigen::Vector3d &g)
 Set the current gravity vector. Default is (0,0,-9.81)
 
const types::RigidBodyStatefloatingBaseState ()
 Get current status of floating base.
 
const RobotModelConfiggetRobotModelConfig ()
 Get current robot model config.
 
bool hasFloatingBase ()
 Is is a floating base robot?
 
urdf::ModelInterfaceSharedPtr loadRobotURDF (const std::string &file_or_string)
 Load URDF model from either file or string.
 
urdf::ModelInterfaceSharedPtr getURDFModel ()
 Return current URDF model.
 
void setJointWeights (const Eigen::VectorXd &weights)
 set Joint weights by given name
 
const Eigen::VectorXd & getJointWeights () const
 Get Joint weights as Named vector.
 
virtual const Eigen::VectorXd & inverseDynamics (const Eigen::VectorXd &qdd_ref=Eigen::VectorXd(), const std::vector< types::Wrench > &f_ext=std::vector< types::Wrench >())=0
 Compute tau from internal state.
 

Protected Member Functions

void clear ()
 
void resetData ()
 
void updateData ()
 

Protected Attributes

std::vector< types::Contactcontacts
 
Eigen::Vector3d gravity
 
types::RigidBodyState floating_base_state
 
RobotModelConfig robot_model_config
 
std::string world_frame
 
std::string base_frame
 
types::JointLimits joint_limits
 
std::vector< std::string > actuated_joint_names
 
std::vector< std::string > independent_joint_names
 
std::vector< std::string > joint_names
 
urdf::ModelInterfaceSharedPtr robot_urdf
 
bool has_floating_base
 
types::JointState joint_state
 
Eigen::MatrixXd selection_matrix
 
Eigen::VectorXd q
 
Eigen::VectorXd qd
 
Eigen::VectorXd qdd
 
Eigen::VectorXd tau
 
Eigen::VectorXd zero_jnt
 
std::vector< Matrixcom_jac
 
std::vector< Matrixjoint_space_inertia_mat
 
std::vector< Vectorbias_forces
 
std::vector< RigidBodyStatecom_rbs
 
std::map< std::string, Matrixspace_jac_map
 
std::map< std::string, Matrixbody_jac_map
 
std::map< std::string, Posepose_map
 
std::map< std::string, Twisttwist_map
 
std::map< std::string, SpatialAccelerationacc_map
 
std::map< std::string, SpatialAccelerationspatial_acc_bias_map
 
bool fk_needs_recompute
 
bool fk_with_zero_acc_needs_recompute
 
Eigen::VectorXd joint_weights
 
types::SpatialAcceleration zero_acc
 
bool configured
 
bool updated
 

Detailed Description

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

  1. All quantities will be computed with respect to world coordinates (floating base robot) or robot root link (fixed base robot)
  2. Joint order is alphabetic, with the floating base being the first 6 joints: [floating_x,floating_y,floating_z,floating_rx,floating_rx,floating_rz, q1 ... qn] Call jointNames() to get the order of joints (without floating base)
  3. You have to call configure() once and update() in every cycle (to provide new position,velocity,accelerations readings) before you request any kinematics or dynamics data

Constructor & Destructor Documentation

◆ RobotModel()

wbc::RobotModel::RobotModel ( )

◆ ~RobotModel()

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

Member Function Documentation

◆ acceleration()

virtual const types::SpatialAcceleration & wbc::RobotModel::acceleration ( const std::string & frame_id)
pure virtual

Returns the spatial acceleration of the body defined by frame_id. Twist will be in "local-world-aligned" (hybrid) representation, i.e., with respect to a frame attached to the given body, but aligned to world coordinates (floating base robot) or robot root link (fixed base)

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

◆ 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, i.e. the root of the URDF model.

◆ biasForces()

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

Returns the bias force vector, which is nj x 1, where nj is the number of joints + number of floating coordinates, i.e. 6 in case of a floating base robot.

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

◆ bodyJacobian()

virtual const Eigen::MatrixXd & wbc::RobotModel::bodyJacobian ( const std::string & frame_id)
pure virtual

Returns the Body Jacobian for the given frame. The order of the Jacobian's columns will be the same as in the model (alphabetic).

Parameters
frame_idReference frame of the Jacobian. Has to be a valid link in the robot model.
Returns
A 6 x nj matrix, where nj is the number of joints + number of floating coordinates, i.e. 6 in case of a floating base robot.

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

◆ centerOfMass()

virtual const types::RigidBodyState & wbc::RobotModel::centerOfMass ( )
pure virtual

Return centers of mass expressed in world frame.

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

◆ clear()

void wbc::RobotModel::clear ( )
protected

◆ comJacobian()

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

Returns the CoM Jacobian for the robot, which maps the robot joint velocities to linear spatial velocities of the CoM expressed in world frame (floating base robot) or robot root link (fixed base). The order of the columns will be the same as the configured joint order of the robot.

Returns
A 3 x nj matrix, where nj is the number of joints + number of floating coordinates, i.e. 6 in case of a floating base robot.

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

◆ configure()

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

This will read the robot model from the given URDF file and initialize all members accordingly.

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 types::RigidBodyState & wbc::RobotModel::floatingBaseState ( )
inline

Get current status of floating base.

◆ getContacts()

const std::vector< types::Contact > & wbc::RobotModel::getContacts ( )
inline

get current contact points

◆ getJointWeights()

const Eigen::VectorXd & wbc::RobotModel::getJointWeights ( ) const
inline

Get Joint weights as Named vector.

◆ getQ()

const Eigen::VectorXd & wbc::RobotModel::getQ ( )
inline

Return full system position vector, incl. floating base. Convention [floating_base_pos, floating_base_ori, joint_positions]: [fb_x,fb_y,fb_z, fb_qx,fb_qy,fb_qz,fb_qw, q_1 ... q_n)].

◆ getQd()

const Eigen::VectorXd & wbc::RobotModel::getQd ( )
inline

Return full system velocity vector, incl. floating base. Convention [floating_base_vel, floating_base_rot_vel, joint_velocities]: [fb_vx,fb_vx,fb_vx, fb_wx,fb_wy,fb_wz, qd_1 ... qd_n)].

◆ getQdd()

const Eigen::VectorXd & wbc::RobotModel::getQdd ( )
inline

Return full system acceleration vector, incl. floating base. Convention [floating_base_acc, floating_base_rot_acc, joint_accelerations]: [fb_dvx,fb_dvx,fb_dvx, fb_dwx,fb_dwy,fb_dwz, qdd_1 ... qdd_n)].

◆ getRobotModelConfig()

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

Get current robot model config.

◆ getURDFModel()

urdf::ModelInterfaceSharedPtr wbc::RobotModel::getURDFModel ( )
inline

Return current URDF model.

◆ 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 is a 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.

◆ inverseDynamics()

virtual const Eigen::VectorXd & wbc::RobotModel::inverseDynamics ( const Eigen::VectorXd & qdd_ref = Eigen::VectorXd(),
const std::vector< types::Wrench > & f_ext = std::vector< types::Wrench >() )
pure virtual

Compute tau from internal state.

Parameters
qdd_ref(Optional) Desired reference joint acceleration (including floating base), if empty actual acceleration will be used.
f_ext(Optional) Contact wrenches, if not empty, size has to match the number of contact points. All wrenches will be in local coordinates, but aligned wrt. world

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

◆ jointIndex()

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

Get the internal index for a joint name.

◆ jointLimits()

const types::JointLimits wbc::RobotModel::jointLimits ( )
inline

Return current joint limits.

◆ jointNames()

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

Return all joint names excluding the floating base. This will be.

  • The entire spanning tree if there are parallel loops
  • Same as independent joints in case of a serial robot
  • Same as actuated joint names in case of a fully actuated robot

◆ jointSpaceInertiaMatrix()

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

Returns the joint space mass-inertia matrix, which is nj x nj, where nj is the number of joints + number of floating coordinates, i.e. 6 in case of a floating base robot.

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

◆ jointState()

const types::JointState & wbc::RobotModel::jointState ( )
inline

Returns the current joint state (indepenent joints)

◆ loadRobotURDF()

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

Load URDF model from either file or string.

◆ na()

uint wbc::RobotModel::na ( )
inline

Return number of actuated joints.

◆ nac()

uint wbc::RobotModel::nac ( )

Return number of active contacts

◆ nc()

uint wbc::RobotModel::nc ( )
inline

Return total number of contact points.

◆ nfb()

uint wbc::RobotModel::nfb ( )
inline

Return dof of the floating base, will be either 0 (floating_base == false) or 6 (floating_base = = false)

◆ nj()

uint wbc::RobotModel::nj ( )
inline

Return number of joints.

◆ pose()

virtual const types::Pose & wbc::RobotModel::pose ( const std::string & frame_id)
pure virtual

Returns the pose of the body defined by frame_id. Pose will be computed with respect to world frame (floating base robot) or robot root link (fixed base)

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

◆ resetData()

void wbc::RobotModel::resetData ( )
protected

◆ selectionMatrix()

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

Return current selection matrix, mapping actuated to all dof.

◆ setContacts()

void wbc::RobotModel::setContacts ( const std::vector< types::Contact > & contacts)

Set new contact points.

◆ setGravityVector()

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

Set the current gravity vector. Default is (0,0,-9.81)

◆ setJointWeights()

void wbc::RobotModel::setJointWeights ( const Eigen::VectorXd & weights)

set Joint weights by given name

◆ spaceJacobian()

virtual const Eigen::MatrixXd & wbc::RobotModel::spaceJacobian ( const std::string & frame_id)
pure virtual

Returns the Space Jacobian for the given frame. The order of the Jacobian's columns will be the same as in the model (alphabetic). Note that the linear part of the jacobian will be aligned to world frame (floating base robot) or robot root link (fixed base), and the angular part will be in body coordinates. This is refered to as "hybrid" representation.

Parameters
frame_idTip frame of the Jacobian. Has to be a valid link in the robot model.
Returns
A 6 x nj matrix, where nj is the number of joints + number of floating coordinates, i.e. 6 in case of a floating base robot.

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

◆ spatialAccelerationBias()

virtual const types::SpatialAcceleration & wbc::RobotModel::spatialAccelerationBias ( const std::string & frame_id)
pure virtual

Returns the spatial acceleration bias, i.e. the term Jdot*qdot. The linear part of the acceleration will be aligned to world frame (floating base robot) or robot root link (fixed base), and the angular part will be in body coordinates. This is refered to as "hybrid" representation.

Parameters
frame_idReference frame of the spatial acceleration. Has to be a valid link in the robot model.
Returns
A 6 dof spatial acceleration.

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

◆ twist()

virtual const types::Twist & wbc::RobotModel::twist ( const std::string & frame_id)
pure virtual

Returns the twist of the body defined by frame_id. Twist will be in "local-world-aligned" (hybrid) representation, i.e., with respect to a frame attached to the given body, but aligned to world coordinates (floating base robot) or robot root link (fixed base)

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

◆ update() [1/4]

void wbc::RobotModel::update ( const Eigen::VectorXd & joint_positions,
const Eigen::VectorXd & joint_velocities )

Update kinematics/dynamics for fixed base robots. Joint acceleration will be assumed zero.

Parameters
joint_positionsPositions of all independent joints. These have to be in the same order as used by the model (alphabetic). For getting the joint order, call jointNames().
joint_velocitiesVelocities of all independent joints. These have to be in the same order as used by the model (alphabetic). For getting the joint order, call jointNames().

◆ update() [2/4]

void wbc::RobotModel::update ( const Eigen::VectorXd & joint_positions,
const Eigen::VectorXd & joint_velocities,
const Eigen::VectorXd & joint_accelerations )
virtual

Update kinematics/dynamics for fixed base robots.

Parameters
joint_positionsPositions of all independent joints. These have to be in the same order as used by the model (alphabetic). For getting the joint order, call jointNames().
joint_velocitiesVelocities of all independent joints. These have to be in the same order as used by the model (alphabetic). For getting the joint order, call jointNames().
joint_accelerationsAccelerations of all independent joints. These have to be in the same order as used by the model (alphabetic). For getting the joint order, call jointNames().

◆ update() [3/4]

virtual void wbc::RobotModel::update ( const Eigen::VectorXd & joint_positions,
const Eigen::VectorXd & joint_velocities,
const Eigen::VectorXd & joint_accelerations,
const types::Pose & fb_pose,
const types::Twist & fb_twist,
const types::SpatialAcceleration & fb_acc )
pure virtual

Update kinematics/dynamics.

Parameters
joint_positionsPositions of all independent joints. These have to be in the same order as used by the model (alphabetic). For getting the joint order, call jointNames().
joint_velocitiesVelocities of all independent joints. These have to be in the same order as used by the model (alphabetic). For getting the joint order, call jointNames().
joint_accelerationVelocities of all independent joints. These have to be in the same order as used by the model (alphabetic). For getting the joint order, call jointNames().
fb_posePose of the floating base in world coordinates
fb_twistTwist of the floating base in "local-world-aligned" (hybrid) representation, i.e., with respect to a frame attached to the floating base (robot root), but aligned to world coordinates
fb_accSpatial accelerationof the floating base in "local-world-aligned" (hybrid) representation, i.e., with respect to a frame attached to the floating base (robot root), but aligned to world coordinates

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

◆ update() [4/4]

void wbc::RobotModel::update ( const Eigen::VectorXd & joint_positions,
const Eigen::VectorXd & joint_velocities,
const types::Pose & fb_pose,
const types::Twist & fb_twist )

Update kinematics/dynamics for floating base robots. Joint and spatial acceleration will be assumed zero.

Parameters
joint_positionsPositions of all independent joints. These have to be in the same order as used by the model (alphabetic). For getting the joint order, call jointNames().
joint_velocitiesVelocities of all independent joints. These have to be in the same order as used by the model (alphabetic). For getting the joint order, call jointNames().
fb_posePose of the floating base in world coordinates
fb_twistTwist of the floating base in "local-world-aligned" (hybrid) representation, i.e., the frame is attached to the floating base (robot root), but aligned to world coordinates

◆ updateData()

void wbc::RobotModel::updateData ( )
protected

◆ worldFrame()

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

Get the world frame id. Will be "world" in case of floating base robot and equal to base_frame in case of fixed base robot.

Member Data Documentation

◆ acc_map

std::map<std::string,SpatialAcceleration> wbc::RobotModel::acc_map
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

std::vector<Vector> wbc::RobotModel::bias_forces
protected

◆ body_jac_map

std::map<std::string,Matrix> wbc::RobotModel::body_jac_map
protected

◆ com_jac

std::vector<Matrix> wbc::RobotModel::com_jac
protected

◆ com_rbs

std::vector<RigidBodyState> wbc::RobotModel::com_rbs
protected

◆ configured

bool wbc::RobotModel::configured
protected

◆ contacts

std::vector<types::Contact> wbc::RobotModel::contacts
protected

◆ fk_needs_recompute

bool wbc::RobotModel::fk_needs_recompute
protected

◆ fk_with_zero_acc_needs_recompute

bool wbc::RobotModel::fk_with_zero_acc_needs_recompute
protected

◆ floating_base_state

types::RigidBodyState wbc::RobotModel::floating_base_state
protected

◆ gravity

Eigen::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

◆ joint_limits

types::JointLimits wbc::RobotModel::joint_limits
protected

◆ joint_names

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

◆ joint_space_inertia_mat

std::vector<Matrix> wbc::RobotModel::joint_space_inertia_mat
protected

◆ joint_state

types::JointState wbc::RobotModel::joint_state
protected

◆ joint_weights

Eigen::VectorXd wbc::RobotModel::joint_weights
protected

◆ pose_map

std::map<std::string,Pose> wbc::RobotModel::pose_map
protected

◆ q

Eigen::VectorXd wbc::RobotModel::q
protected

◆ qd

Eigen::VectorXd wbc::RobotModel::qd
protected

◆ qdd

Eigen::VectorXd wbc::RobotModel::qdd
protected

◆ robot_model_config

RobotModelConfig wbc::RobotModel::robot_model_config
protected

◆ robot_urdf

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

◆ selection_matrix

Eigen::MatrixXd wbc::RobotModel::selection_matrix
protected

◆ space_jac_map

std::map<std::string,Matrix> wbc::RobotModel::space_jac_map
protected

◆ spatial_acc_bias_map

std::map<std::string,SpatialAcceleration> wbc::RobotModel::spatial_acc_bias_map
protected

◆ tau

Eigen::VectorXd wbc::RobotModel::tau
protected

◆ twist_map

std::map<std::string,Twist> wbc::RobotModel::twist_map
protected

◆ updated

bool wbc::RobotModel::updated
protected

◆ world_frame

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

◆ zero_acc

types::SpatialAcceleration wbc::RobotModel::zero_acc
protected

◆ zero_jnt

Eigen::VectorXd wbc::RobotModel::zero_jnt
protected

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