Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "joint_states_settler/joint_states_deflater.h"
00036 #include <ros/console.h>
00037
00038 using namespace std;
00039 using namespace joint_states_settler;
00040
00041 JointStatesDeflater::JointStatesDeflater()
00042 {
00043 mapping_.clear();
00044 }
00045
00046 void JointStatesDeflater::setDeflationJointNames(std::vector<std::string> joint_names)
00047 {
00048 joint_names_ = joint_names;
00049 mapping_.resize(joint_names_.size());
00050 }
00051
00052 void JointStatesDeflater::deflate(const sensor_msgs::JointStateConstPtr& joint_states, DeflatedJointStates& deflated_elem)
00053 {
00054 if (joint_states->name.size() != joint_states->position.size()){
00055 ROS_ERROR("JointStatesDeflater got invalid joint state message");
00056 return;
00057 }
00058
00059 if (mapping_.size() != joint_names_.size())
00060 updateMapping(*joint_states);
00061
00062 const unsigned int N = joint_names_.size();
00063
00064 deflated_elem.channels_.resize(N);
00065
00066 for (unsigned int i=0; i<N; i++)
00067 {
00068 if ( mapping_[i] >= joint_states->name.size() )
00069 updateMapping(*joint_states);
00070
00071 if ( joint_states->name[mapping_[i]] != joint_names_[i])
00072 updateMapping(*joint_states);
00073
00074 deflated_elem.header = joint_states->header;
00075 deflated_elem.channels_[i] = joint_states->position[mapping_[i]];
00076 deflated_elem.msg_ = joint_states;
00077 }
00078 }
00079
00080 void JointStatesDeflater::prune(const sensor_msgs::JointState& joint_states, sensor_msgs::JointState& pruned_joint_states)
00081 {
00082 if (joint_states.name.size() != joint_states.position.size())
00083 {
00084 ROS_ERROR("JointStatesDeflater got invalid joint state message. name's size and position's size don't match.");
00085 return;
00086 }
00087
00088 if (mapping_.size() != joint_names_.size())
00089 updateMapping(joint_states);
00090
00091 const unsigned int N = joint_names_.size();
00092
00093
00094 pruned_joint_states.header.stamp = joint_states.header.stamp;
00095 pruned_joint_states.name.resize(N);
00096 pruned_joint_states.position.resize(N);
00097 pruned_joint_states.velocity.clear();
00098 pruned_joint_states.effort.clear();
00099
00100 for (unsigned int i=0; i<N; i++)
00101 {
00102 if ( mapping_[i] >= joint_states.name.size() )
00103 updateMapping(joint_states);
00104
00105 if ( joint_states.name[mapping_[i]] != joint_names_[i])
00106 updateMapping(joint_states);
00107
00108 pruned_joint_states.name[i] = joint_states.name[mapping_[i]];
00109 pruned_joint_states.position[i] = joint_states.position[mapping_[i]];
00110
00111
00112 }
00113 }
00114
00115 void JointStatesDeflater::updateMapping(const sensor_msgs::JointState& joint_states)
00116 {
00117 ROS_DEBUG("Updating the JointStates mapping");
00118
00119 const unsigned int N = joint_names_.size();
00120
00121 mapping_.resize(N);
00122
00123 for (unsigned int i=0; i<N; i++)
00124 {
00125 bool mapping_found = false;
00126 for (unsigned int j=0; j<joint_states.name.size(); j++)
00127 {
00128 if ( joint_names_[i] == joint_states.name[j])
00129 {
00130 mapping_[i] = j;
00131 mapping_found = true;
00132 }
00133 }
00134 ROS_ERROR_COND(!mapping_found, "Couldn't find mapping for [%s]", joint_names_[i].c_str());
00135 }
00136 }