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
00037 using namespace std;
00038 using namespace joint_states_settler;
00039
00040 JointStatesDeflater::JointStatesDeflater()
00041 {
00042 mapping_.clear();
00043 }
00044
00045 void JointStatesDeflater::setDeflationJointNames(std::vector<std::string> joint_names)
00046 {
00047 joint_names_ = joint_names;
00048 mapping_.resize(joint_names_.size());
00049 }
00050
00051 void JointStatesDeflater::deflate(const sensor_msgs::JointStateConstPtr& joint_states, DeflatedJointStates& deflated_elem)
00052 {
00053 if (joint_states->get_name_size() != joint_states->get_position_size()){
00054 ROS_ERROR("JointStatesDeflater got invalid joint state message");
00055 return;
00056 }
00057
00058 if (mapping_.size() != joint_names_.size())
00059 updateMapping(*joint_states);
00060
00061 const unsigned int N = joint_names_.size();
00062
00063 deflated_elem.channels_.resize(N);
00064
00065 for (unsigned int i=0; i<N; i++)
00066 {
00067 if ( mapping_[i] >= joint_states->name.size() )
00068 updateMapping(*joint_states);
00069
00070 if ( joint_states->name[mapping_[i]] != joint_names_[i])
00071 updateMapping(*joint_states);
00072
00073 deflated_elem.header = joint_states->header;
00074 deflated_elem.channels_[i] = joint_states->position[mapping_[i]];
00075 deflated_elem.msg_ = joint_states;
00076 }
00077 }
00078
00079 void JointStatesDeflater::prune(const sensor_msgs::JointState& joint_states, sensor_msgs::JointState& pruned_joint_states)
00080 {
00081 if (joint_states.get_name_size() != joint_states.get_position_size())
00082 {
00083 ROS_ERROR("JointStatesDeflater got invalid joint state message. name's size and position's size don't match.");
00084 return;
00085 }
00086
00087 if (mapping_.size() != joint_names_.size())
00088 updateMapping(joint_states);
00089
00090 const unsigned int N = joint_names_.size();
00091
00092
00093 pruned_joint_states.header.stamp = joint_states.header.stamp;
00094 pruned_joint_states.name.resize(N);
00095 pruned_joint_states.position.resize(N);
00096 pruned_joint_states.velocity.clear();
00097 pruned_joint_states.effort.clear();
00098
00099 for (unsigned int i=0; i<N; i++)
00100 {
00101 if ( mapping_[i] >= joint_states.name.size() )
00102 updateMapping(joint_states);
00103
00104 if ( joint_states.name[mapping_[i]] != joint_names_[i])
00105 updateMapping(joint_states);
00106
00107 pruned_joint_states.name[i] = joint_states.name[mapping_[i]];
00108 pruned_joint_states.position[i] = joint_states.position[mapping_[i]];
00109
00110
00111 }
00112 }
00113
00114 void JointStatesDeflater::updateMapping(const sensor_msgs::JointState& joint_states)
00115 {
00116 ROS_DEBUG("Updating the JointStates mapping");
00117
00118 const unsigned int N = joint_names_.size();
00119
00120 mapping_.resize(N);
00121
00122 for (unsigned int i=0; i<N; i++)
00123 {
00124 bool mapping_found = false;
00125 for (unsigned int j=0; j<joint_states.name.size(); j++)
00126 {
00127 if ( joint_names_[i] == joint_states.name[j])
00128 {
00129 mapping_[i] = j;
00130 mapping_found = true;
00131 }
00132 }
00133 ROS_ERROR_COND(!mapping_found, "Couldn't find mapping for [%s]", joint_names_[i].c_str());
00134 }
00135 }