Public Member Functions | Private Attributes
pr2_mechanism_model::Tree Class Reference

#include <tree.h>

List of all members.

Public Member Functions

void addEfforts (const KDL::JntArray &)
 add to the commanded joint efforts of the tree's joints from a KDL::JntArray
template<class Vec >
void addEfforts (const Vec &)
 add to the commanded joint efforts of the tree's joints from any type that implements size() and [] lookup
bool allCalibrated () const
 returns true, if all the joints in the tree are calibrated
void getEfforts (KDL::JntArray &) const
 get the measured joint efforts of the tree's joints as a KDL::JntArray
template<class Vec >
void getEfforts (Vec &) const
 get the measured joint efforts of the tree's joints as any type with size() and [] lookup
JointStategetJoint (unsigned int) const
 returns a pointer to the joint state of a joint in the list of the tree's actuated joints (index starts at 0)
void getPositions (KDL::JntArray &) const
 get the position of the joints of the tree as a KDL::JntArray
template<class Vec >
void getPositions (Vec &) const
 get the position of the joints of the tree as any type with size() and [] lookup
void getVelocities (KDL::JntArrayVel &) const
 get the velocities of the joints of the tree as a KDL::JntArrayVel (fills in the positions, too)
template<class Vec >
void getVelocities (Vec &) const
 get the velocities of the joints of the tree as any type with size() and [] lookup
bool init (RobotState *robot_state)
 initializes the tree object The initializer's most important functionality is to create a vector of joints. This vector is ordered according to the joint's number given by KDL's tree class, which is used by the kdl_parser to create a KDL::Tree from the robot description. This structure is what a KDL tree solver expects. The vector of joints can later be used to read the joints' positions or to send efforts to them.
void setEfforts (const KDL::JntArray &)
 set the commanded joint efforts of the tree's joints from a KDL::JntArray
template<class Vec >
void setEfforts (const Vec &)
 set the commanded joint efforts of the tree's joints from any type that implements size() and [] lookup
int size () const
 returns the number of actuated joints in the tree
void toKdl (KDL::Tree &) const
 get a KDL::Tree object that respresents the tree
 Tree ()
 ~Tree ()

Private Attributes

std::vector< JointState * > joints_
 a vector of pointers to joint states; includes only the ones that can be actuated (not fixed joints)
KDL::Tree kdl_tree_

Detailed Description

Definition at line 52 of file tree.h.


Constructor & Destructor Documentation

Definition at line 55 of file tree.h.

Definition at line 56 of file tree.h.


Member Function Documentation

void pr2_mechanism_model::Tree::addEfforts ( const KDL::JntArray &  efforts) [inline]

add to the commanded joint efforts of the tree's joints from a KDL::JntArray

Definition at line 186 of file tree.h.

template<class Vec >
void pr2_mechanism_model::Tree::addEfforts ( const Vec &  v) [inline]

add to the commanded joint efforts of the tree's joints from any type that implements size() and [] lookup

Definition at line 194 of file tree.h.

returns true, if all the joints in the tree are calibrated

Definition at line 201 of file tree.h.

void pr2_mechanism_model::Tree::getEfforts ( KDL::JntArray &  efforts) const [inline]

get the measured joint efforts of the tree's joints as a KDL::JntArray

Definition at line 156 of file tree.h.

template<class Vec >
void pr2_mechanism_model::Tree::getEfforts ( Vec &  v) const [inline]

get the measured joint efforts of the tree's joints as any type with size() and [] lookup

Definition at line 164 of file tree.h.

JointState * pr2_mechanism_model::Tree::getJoint ( unsigned int  actuated_joint_i) const [inline]

returns a pointer to the joint state of a joint in the list of the tree's actuated joints (index starts at 0)

Definition at line 216 of file tree.h.

void pr2_mechanism_model::Tree::getPositions ( KDL::JntArray &  positions) const [inline]

get the position of the joints of the tree as a KDL::JntArray

Definition at line 122 of file tree.h.

template<class Vec >
void pr2_mechanism_model::Tree::getPositions ( Vec &  v) const [inline]

get the position of the joints of the tree as any type with size() and [] lookup

Definition at line 130 of file tree.h.

void pr2_mechanism_model::Tree::getVelocities ( KDL::JntArrayVel velocities) const [inline]

get the velocities of the joints of the tree as a KDL::JntArrayVel (fills in the positions, too)

Definition at line 137 of file tree.h.

template<class Vec >
void pr2_mechanism_model::Tree::getVelocities ( Vec &  v) const [inline]

get the velocities of the joints of the tree as any type with size() and [] lookup

Definition at line 149 of file tree.h.

initializes the tree object The initializer's most important functionality is to create a vector of joints. This vector is ordered according to the joint's number given by KDL's tree class, which is used by the kdl_parser to create a KDL::Tree from the robot description. This structure is what a KDL tree solver expects. The vector of joints can later be used to read the joints' positions or to send efforts to them.

Parameters:
robot_statethe robot state object containing the robot model and the state of each joint in the robot

Definition at line 45 of file tree.cpp.

void pr2_mechanism_model::Tree::setEfforts ( const KDL::JntArray &  efforts) [inline]

set the commanded joint efforts of the tree's joints from a KDL::JntArray

Definition at line 171 of file tree.h.

template<class Vec >
void pr2_mechanism_model::Tree::setEfforts ( const Vec &  v) [inline]

set the commanded joint efforts of the tree's joints from any type that implements size() and [] lookup

Definition at line 179 of file tree.h.

int pr2_mechanism_model::Tree::size ( ) const [inline]

returns the number of actuated joints in the tree

Definition at line 224 of file tree.h.

void pr2_mechanism_model::Tree::toKdl ( KDL::Tree tree) const [inline]

get a KDL::Tree object that respresents the tree

Definition at line 211 of file tree.h.


Member Data Documentation

a vector of pointers to joint states; includes only the ones that can be actuated (not fixed joints)

Definition at line 119 of file tree.h.

Definition at line 117 of file tree.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 Mon Dec 2 2013 13:13:02