Given a set a joint names, efficiently extracts a subset of joint positions. More...
#include <joint_states_deflater.h>
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_ |
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 52 of file joint_states_deflater.h.
Definition at line 41 of file joint_states_deflater.cpp.
void JointStatesDeflater::deflate | ( | const sensor_msgs::JointStateConstPtr & | joint_states, |
DeflatedJointStates & | deflated_elem | ||
) |
Perform the deflation on a joint_states message.
joint_states | Incoming JointStates message |
Ouput | datatype. Stores the deflated data, along with the original joint states message |
Definition at line 52 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.
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 80 of file joint_states_deflater.cpp.
void JointStatesDeflater::setDeflationJointNames | ( | std::vector< std::string > | joint_names | ) |
Specify which joints to extract.
joint_names | Ordered list of joint names to extract |
Definition at line 46 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 115 of file joint_states_deflater.cpp.
std::vector<std::string> joint_states_settler::JointStatesDeflater::joint_names_ [private] |
Definition at line 80 of file joint_states_deflater.h.
std::vector<unsigned int> joint_states_settler::JointStatesDeflater::mapping_ [private] |
Definition at line 79 of file joint_states_deflater.h.