Public Member Functions | Private Member Functions | Private Attributes | Friends
robot_state::LinkState Class Reference

The state corresponding to a link. More...

#include <link_state.h>

List of all members.

Public Member Functions

void computeGeometryTransforms ()
void computeTransform ()
 Recompute global_collision_body_transform and global_link_transform.
void computeTransformBackward (const Eigen::Affine3d &transform)
void computeTransformForward (const Eigen::Affine3d &transform)
void getAttachedBodies (std::vector< const AttachedBody * > &attached_bodies) const
 Get all the bodies attached to this link.
const AttachedBodygetAttachedBody (const std::string &id) const
 Get the attached body with name id.
const Eigen::Affine3d & getGlobalCollisionBodyTransform () const
 Get the global transform for the collision body associated with this link.
const Eigen::Affine3d & getGlobalLinkTransform () const
 Get the global transform for this link.
const robot_model::LinkModelgetLinkModel () const
 Get the link model corresponding to this state.
const std::string & getName () const
 Get the name of link corresponding to this state.
const JointStategetParentJointState () const
 Get the joint state corresponding to the parent joint of this link.
const LinkStategetParentLinkState () const
 Get the link state corresponding to the parent link of this link.
const RobotStategetRobotState () const
 Get the kinematic state that this link state is part of.
RobotStategetRobotState ()
 Get the kinematic state that this link state is part of.
bool hasAttachedBody (const std::string &id) const
 Check if an attached body named id exists in this group.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW LinkState (RobotState *state, const robot_model::LinkModel *lm)
 Constructor.
void updateAttachedBodies ()
 Update all attached bodies given set link transforms.
 ~LinkState ()

Private Member Functions

void computeTransformBackward (const LinkState *child_link)
void computeTransformForward (const LinkState *parent_link)

Private Attributes

std::map< std::string,
AttachedBody * > 
attached_body_map_
Eigen::Affine3d global_collision_body_transform_
 The global transform for this link (computed by forward kinematics)
Eigen::Affine3d global_link_transform_
 The global transform this link forwards (computed by forward kinematics)
const robot_model::LinkModellink_model_
JointStateparent_joint_state_
LinkStateparent_link_state_
RobotStaterobot_state_
 The robot state this link is part of.

Friends

class RobotState

Detailed Description

The state corresponding to a link.

Definition at line 51 of file link_state.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 40 of file link_state.cpp.

Definition at line 47 of file link_state.cpp.


Member Function Documentation

Definition at line 110 of file link_state.cpp.

Recompute global_collision_body_transform and global_link_transform.

Definition at line 116 of file link_state.cpp.

void robot_state::LinkState::computeTransformBackward ( const Eigen::Affine3d &  transform)

Definition at line 95 of file link_state.cpp.

void robot_state::LinkState::computeTransformBackward ( const LinkState child_link) [private]

Definition at line 75 of file link_state.cpp.

void robot_state::LinkState::computeTransformForward ( const Eigen::Affine3d &  transform)

Definition at line 51 of file link_state.cpp.

void robot_state::LinkState::computeTransformForward ( const LinkState parent_link) [private]

Definition at line 63 of file link_state.cpp.

void robot_state::LinkState::getAttachedBodies ( std::vector< const AttachedBody * > &  attached_bodies) const

Get all the bodies attached to this link.

Definition at line 146 of file link_state.cpp.

const robot_state::AttachedBody * robot_state::LinkState::getAttachedBody ( const std::string &  id) const

Get the attached body with name id.

Definition at line 134 of file link_state.cpp.

const Eigen::Affine3d& robot_state::LinkState::getGlobalCollisionBodyTransform ( ) const [inline]

Get the global transform for the collision body associated with this link.

Definition at line 126 of file link_state.h.

const Eigen::Affine3d& robot_state::LinkState::getGlobalLinkTransform ( ) const [inline]

Get the global transform for this link.

Definition at line 120 of file link_state.h.

Get the link model corresponding to this state.

Definition at line 93 of file link_state.h.

const std::string& robot_state::LinkState::getName ( ) const [inline]

Get the name of link corresponding to this state.

Definition at line 64 of file link_state.h.

Get the joint state corresponding to the parent joint of this link.

Definition at line 99 of file link_state.h.

Get the link state corresponding to the parent link of this link.

Definition at line 105 of file link_state.h.

Get the kinematic state that this link state is part of.

Definition at line 70 of file link_state.h.

Get the kinematic state that this link state is part of.

Definition at line 76 of file link_state.h.

bool robot_state::LinkState::hasAttachedBody ( const std::string &  id) const

Check if an attached body named id exists in this group.

Definition at line 129 of file link_state.cpp.

Update all attached bodies given set link transforms.

Definition at line 123 of file link_state.cpp.


Friends And Related Function Documentation

friend class RobotState [friend]

Definition at line 53 of file link_state.h.


Member Data Documentation

std::map<std::string, AttachedBody*> robot_state::LinkState::attached_body_map_ [private]

Definition at line 145 of file link_state.h.

The global transform for this link (computed by forward kinematics)

Definition at line 151 of file link_state.h.

The global transform this link forwards (computed by forward kinematics)

Definition at line 148 of file link_state.h.

Definition at line 139 of file link_state.h.

Definition at line 141 of file link_state.h.

Definition at line 143 of file link_state.h.

The robot state this link is part of.

Definition at line 137 of file link_state.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:48