Public Member Functions | Private Attributes | List of all members
pr2_mechanism_model::Chain Class Reference

#include <chain.h>

Public Member Functions

void addEfforts (KDL::JntArray &)
 set the commanded joint efforts of the chain as a kdl jnt array More...
 
template<class Vec >
void addEfforts (const Vec &v)
 Adds efforts from any type that implements size() and [] lookup. More...
 
bool allCalibrated ()
 returns true if all the joints in the chain are calibrated More...
 
 Chain ()
 
void getEfforts (std::vector< double > &)
 get the measured joint efforts of the chain as a std vector More...
 
void getEfforts (KDL::JntArray &)
 get the measured joint efforts of the chain as a kdl jnt array More...
 
JointStategetJoint (unsigned int actuated_joint_i)
 get a joint state of an actuated joint of the chain. More...
 
void getPositions (std::vector< double > &)
 get the joint positions of the chain as a std vector More...
 
void getPositions (KDL::JntArray &)
 get the joint positions of the chain as a kdl jnt array More...
 
template<class Vec >
void getPositions (Vec &v)
 gets the joint positions of the chain as any type with size() and [] More...
 
void getVelocities (std::vector< double > &)
 get the joint velocities of the chain as a std vector More...
 
void getVelocities (KDL::JntArrayVel &)
 get the joint velocities and positoin of the chain as a kdl jnt array vel. Fills in the positions too. More...
 
template<class Vec >
void getVelocities (Vec &v)
 gets the joint velocities of the chain as any type with size() and [] More...
 
bool init (RobotState *robot_state, const std::string &root, const std::string &tip)
 initialize the chain object More...
 
void setEfforts (KDL::JntArray &)
 set the commanded joint efforts of the chain as a std vector More...
 
int size () const
 Returns the number of actuated joints in the chain. More...
 
void toKDL (KDL::Chain &chain)
 get a kdl chain object that respresents the chain from root to tip More...
 
 ~Chain ()
 

Private Attributes

std::vector< JointState *> joints_
 
KDL::Chain kdl_chain_
 
pr2_mechanism_model::RobotStaterobot_state_
 

Detailed Description

Definition at line 43 of file chain.h.

Constructor & Destructor Documentation

◆ Chain()

pr2_mechanism_model::Chain::Chain ( )
inline

Definition at line 46 of file chain.h.

◆ ~Chain()

pr2_mechanism_model::Chain::~Chain ( )
inline

Definition at line 47 of file chain.h.

Member Function Documentation

◆ addEfforts() [1/2]

void pr2_mechanism_model::Chain::addEfforts ( KDL::JntArray a)

set the commanded joint efforts of the chain as a kdl jnt array

Definition at line 157 of file chain.cpp.

◆ addEfforts() [2/2]

template<class Vec >
void pr2_mechanism_model::Chain::addEfforts ( const Vec &  v)
inline

Adds efforts from any type that implements size() and [] lookup.

Definition at line 99 of file chain.h.

◆ allCalibrated()

bool pr2_mechanism_model::Chain::allCalibrated ( )

returns true if all the joints in the chain are calibrated

Definition at line 110 of file chain.cpp.

◆ getEfforts() [1/2]

void pr2_mechanism_model::Chain::getEfforts ( std::vector< double > &  efforts)

get the measured joint efforts of the chain as a std vector

Definition at line 101 of file chain.cpp.

◆ getEfforts() [2/2]

void pr2_mechanism_model::Chain::getEfforts ( KDL::JntArray a)

get the measured joint efforts of the chain as a kdl jnt array

Definition at line 143 of file chain.cpp.

◆ getJoint()

JointState * pr2_mechanism_model::Chain::getJoint ( unsigned int  actuated_joint_i)

get a joint state of an actuated joint of the chain.

the actuated_joint_i index starts at zero fixed joints are ignored in the list of actuated joints

Definition at line 165 of file chain.cpp.

◆ getPositions() [1/3]

void pr2_mechanism_model::Chain::getPositions ( std::vector< double > &  positions)

get the joint positions of the chain as a std vector

Definition at line 83 of file chain.cpp.

◆ getPositions() [2/3]

void pr2_mechanism_model::Chain::getPositions ( KDL::JntArray a)

get the joint positions of the chain as a kdl jnt array

Definition at line 126 of file chain.cpp.

◆ getPositions() [3/3]

template<class Vec >
void pr2_mechanism_model::Chain::getPositions ( Vec &  v)
inline

gets the joint positions of the chain as any type with size() and []

Definition at line 64 of file chain.h.

◆ getVelocities() [1/3]

void pr2_mechanism_model::Chain::getVelocities ( std::vector< double > &  velocities)

get the joint velocities of the chain as a std vector

Definition at line 92 of file chain.cpp.

◆ getVelocities() [2/3]

void pr2_mechanism_model::Chain::getVelocities ( KDL::JntArrayVel a)

get the joint velocities and positoin of the chain as a kdl jnt array vel. Fills in the positions too.

Definition at line 133 of file chain.cpp.

◆ getVelocities() [3/3]

template<class Vec >
void pr2_mechanism_model::Chain::getVelocities ( Vec &  v)
inline

gets the joint velocities of the chain as any type with size() and []

Definition at line 77 of file chain.h.

◆ init()

bool pr2_mechanism_model::Chain::init ( RobotState robot_state,
const std::string &  root,
const std::string &  tip 
)

initialize the chain object

Parameters
robot_statethe robot state object containing the robot model and the state of each joint in the robot
rootthe name of the root link of the chain
tipthe name of the tip link of the chain

Definition at line 40 of file chain.cpp.

◆ setEfforts()

void pr2_mechanism_model::Chain::setEfforts ( KDL::JntArray a)

set the commanded joint efforts of the chain as a std vector

Definition at line 150 of file chain.cpp.

◆ size()

int pr2_mechanism_model::Chain::size ( ) const
inline

Returns the number of actuated joints in the chain.

Definition at line 120 of file chain.h.

◆ toKDL()

void pr2_mechanism_model::Chain::toKDL ( KDL::Chain chain)

get a kdl chain object that respresents the chain from root to tip

Definition at line 120 of file chain.cpp.

Member Data Documentation

◆ joints_

std::vector< JointState* > pr2_mechanism_model::Chain::joints_
private

Definition at line 126 of file chain.h.

◆ kdl_chain_

KDL::Chain pr2_mechanism_model::Chain::kdl_chain_
private

Definition at line 124 of file chain.h.

◆ robot_state_

pr2_mechanism_model::RobotState* pr2_mechanism_model::Chain::robot_state_
private

Definition at line 123 of file chain.h.


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


pr2_mechanism_model
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Tue Mar 7 2023 03:54:53