Classes | Typedefs | Functions
robot_state Namespace Reference

This namespace includes the classes in the robot_state library. More...

Classes

class  AttachedBody
 Object defining bodies that can be attached to robot links. This is useful when handling objects picked up by the robot. More...
class  JointState
 Definition of a joint state - representation of state for a single joint. More...
class  JointStateGroup
 The joint state corresponding to a group. More...
class  LinkState
 The state corresponding to a link. More...
class  RobotState
 Definition of a kinematic state - the parts of the robot state which can change. Const members are thread safe. More...
class  StateTransforms
class  Transforms
 Provides an implementation of a snapshot of a transform tree that can be easily queried for transforming different quantities. Transforms are maintained as a list of transforms to a particular frame. All stored transforms are considered fixed. More...

Typedefs

typedef boost::function< void(AttachedBody
*body, bool attached) 
AttachedBodyCallback )
typedef std::map< std::string,
Eigen::Affine3d, std::less
< std::string >
, Eigen::aligned_allocator
< std::pair< const std::string,
Eigen::Affine3d > > > 
FixedTransformsMap
 Map frame names to the transformation matrix that can transform objects from the frame name to the planning frame.
typedef boost::shared_ptr
< const RobotState
RobotStateConstPtr
typedef boost::shared_ptr
< RobotState
RobotStatePtr
typedef boost::function< bool(const
JointStateGroup
*joint_state_group,
Eigen::VectorXd &stvector) 
SecondaryTaskFn )
typedef boost::function< bool(JointStateGroup
*joint_state_group, const
std::vector< double >
&joint_group_variable_values) 
StateValidityCallbackFn )

Functions

bool jointStateToRobotState (const sensor_msgs::JointState &joint_state, RobotState &state)
 Convert a joint state to a kinematic state.
 MOVEIT_CLASS_FORWARD (RobotState)
 MOVEIT_CLASS_FORWARD (Transforms)
bool robotStateMsgToRobotState (const Transforms &tf, const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
 Convert a robot state (with accompanying extra transforms) to a kinematic state.
bool robotStateMsgToRobotState (const moveit_msgs::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
 Convert a robot state (with accompanying extra transforms) to a kinematic state.
void robotStateToJointStateMsg (const RobotState &state, sensor_msgs::JointState &joint_state)
 Convert a kinematic state to a joint state message.
void robotStateToRobotStateMsg (const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
 Convert a kinematic state to a robot state message.

Detailed Description

This namespace includes the classes in the robot_state library.


Typedef Documentation

typedef boost::function<void(AttachedBody *body, bool attached) robot_state::AttachedBodyCallback)

Definition at line 50 of file robot_state.h.

typedef std::map<std::string, Eigen::Affine3d, std::less<std::string>, Eigen::aligned_allocator<std::pair<const std::string, Eigen::Affine3d> > > robot_state::FixedTransformsMap

Map frame names to the transformation matrix that can transform objects from the frame name to the planning frame.

Definition at line 54 of file transforms.h.

typedef boost::shared_ptr<const RobotState> robot_state::RobotStateConstPtr

Definition at line 333 of file robot_state.h.

typedef boost::shared_ptr<RobotState> robot_state::RobotStatePtr

Definition at line 332 of file robot_state.h.

typedef boost::function<bool(const JointStateGroup *joint_state_group, Eigen::VectorXd &stvector) robot_state::SecondaryTaskFn)

Definition at line 55 of file joint_state_group.h.

typedef boost::function<bool(JointStateGroup *joint_state_group, const std::vector<double> &joint_group_variable_values) robot_state::StateValidityCallbackFn)

Definition at line 52 of file joint_state_group.h.


Function Documentation

bool robot_state::jointStateToRobotState ( const sensor_msgs::JointState &  joint_state,
RobotState &  state 
)

Convert a joint state to a kinematic state.

Parameters:
joint_stateThe input joint state to be converted
stateThe resultant kinematic state
Returns:
True if successful, false if failed for any reason

Definition at line 392 of file conversions.cpp.

bool robot_state::robotStateMsgToRobotState ( const Transforms &  tf,
const moveit_msgs::RobotState &  robot_state,
RobotState &  state,
bool  copy_attached_bodies = true 
)

Convert a robot state (with accompanying extra transforms) to a kinematic state.

Parameters:
tfAn instance of a transforms object
robot_stateThe input robot state
stateThe resultant kinematic state
Returns:
True if successful, false if failed for any reason

Definition at line 404 of file conversions.cpp.

bool robot_state::robotStateMsgToRobotState ( const moveit_msgs::RobotState &  robot_state,
RobotState &  state,
bool  copy_attached_bodies = true 
)

Convert a robot state (with accompanying extra transforms) to a kinematic state.

Parameters:
robot_stateThe input robot state
stateThe resultant kinematic state
Returns:
True if successful, false if failed for any reason

Definition at line 399 of file conversions.cpp.

void robot_state::robotStateToJointStateMsg ( const RobotState &  state,
sensor_msgs::JointState &  joint_state 
)

Convert a kinematic state to a joint state message.

Parameters:
stateThe input kinematic state object
robot_stateThe resultant JointState message

Definition at line 423 of file conversions.cpp.

void robot_state::robotStateToRobotStateMsg ( const RobotState &  state,
moveit_msgs::RobotState &  robot_state,
bool  copy_attached_bodies = true 
)

Convert a kinematic state to a robot state message.

Parameters:
stateThe input kinematic state object
robot_stateThe resultant RobotState *message

Definition at line 409 of file conversions.cpp.



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