joint_states_settler::JointStatesDeflater Class Reference

Given a set a joint names, efficiently extracts a subset of joint positions. More...

#include <joint_states_deflater.h>

List of all members.

Public Member Functions

void deflate (const sensor_msgs::JointStateConstPtr &joint_states, DeflatedJointStates &deflated_elem)
 Perform the deflation on a joint_states message.
 JointStatesDeflater ()
void prune (const sensor_msgs::JointState &joint_states, sensor_msgs::JointState &pruned_joint_states)
 Remove all the joints that we don't care about.
void setDeflationJointNames (std::vector< std::string > joint_names)
 Specify which joints to extract.

Private Member Functions

void updateMapping (const sensor_msgs::JointState &joint_states)
 Given a stereotypical JointStates message, computes the mapping from JointStates to the deflated data.

Private Attributes

std::vector< std::string > joint_names_
std::vector< unsigned int > mapping_

Detailed Description

Given a set a joint names, efficiently extracts a subset of joint positions.

This class is generally more efficient than other methods, because it caches the the mapping from the incoming joint_states message to the deflated vector. It also updates the mapping whenever the ordering in joint_states changes

Definition at line 50 of file joint_states_deflater.h.


Constructor & Destructor Documentation

JointStatesDeflater::JointStatesDeflater (  ) 

Definition at line 40 of file joint_states_deflater.cpp.


Member Function Documentation

void JointStatesDeflater::deflate ( const sensor_msgs::JointStateConstPtr &  joint_states,
DeflatedJointStates deflated_elem 
)

Perform the deflation on a joint_states message.

Parameters:
joint_states Incoming JointStates message
Ouput datatype. Stores the deflated data, along with the original joint states message

Definition at line 51 of file joint_states_deflater.cpp.

void JointStatesDeflater::prune ( const sensor_msgs::JointState &  joint_states,
sensor_msgs::JointState &  pruned_joint_states 
)

Remove all the joints that we don't care about.

Parameters:
joint_states Input: The full vector of joint states
pruned_joint_states Output: The output vector with a subset of the joint states, in the requested order

Definition at line 79 of file joint_states_deflater.cpp.

void JointStatesDeflater::setDeflationJointNames ( std::vector< std::string >  joint_names  ) 

Specify which joints to extract.

Parameters:
joint_names Ordered list of joint names to extract

Definition at line 45 of file joint_states_deflater.cpp.

void JointStatesDeflater::updateMapping ( const sensor_msgs::JointState &  joint_states  )  [private]

Given a stereotypical JointStates message, computes the mapping from JointStates to the deflated data.

Definition at line 114 of file joint_states_deflater.cpp.


Member Data Documentation

std::vector<std::string> joint_states_settler::JointStatesDeflater::joint_names_ [private]

Definition at line 68 of file joint_states_deflater.h.

std::vector<unsigned int> joint_states_settler::JointStatesDeflater::mapping_ [private]

Definition at line 67 of file joint_states_deflater.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs


joint_states_settler
Author(s): Vijay Pradeep
autogenerated on Fri Jan 11 09:14:40 2013