40 #include <calibration_msgs/JointStateCalibrationPattern.h> 51 const std::string& root,
const std::string& tip)
54 success = tree.
getChain(root, tip, chain_);
56 ROS_ERROR(
"Error extracting chain from [%s] to [%s]\n", root.c_str(), tip.c_str());
63 chain_.addSegment(angle_segment);
64 chain_.addSegment(range_segment);
66 for (
unsigned int i=0; i < chain_.segments.size(); i++)
68 printf(
"%2u) %s -> %s\n", i, chain_.segments[i].getName().c_str(),
69 chain_.segments[i].getJoint().getName().c_str());
77 sensor_msgs::PointCloud cloud;
80 for (
unsigned int i=0; i<joint_state_vec.size(); i++)
82 map<string, double> joint_map;
83 for (
unsigned int j=0; j<joint_state_vec[i].name.size(); j++)
85 joint_map.insert(make_pair(joint_state_vec[i].name[j],
86 joint_state_vec[i].position[j] + joint_state_vec[i].velocity[j]*time_shift.
toSec()));
88 geometry_msgs::Point32 pt = project(joint_map);
89 cloud.points.push_back(pt);
101 unsigned int cur_joint_num=0;
102 for (
unsigned int i=0; i<chain_.getNrOfSegments(); i++)
106 string joint_name = chain_.getSegment(i).getJoint().getName();
107 map<string, double>::const_iterator it = joint_map.find(joint_name);
109 if (it == joint_map.end())
111 ROS_ERROR(
"Couldn't find joint [%s] in map", joint_name.c_str());
112 joint_pos_array(cur_joint_num, 0) = 0.0;
116 joint_pos_array(cur_joint_num, 0) = (*it).second;
123 solver_->JntToCart(joint_pos_array, out_frame);
125 geometry_msgs::Point32 pt;
126 pt.x = out_frame.
p.
data[0];
127 pt.y = out_frame.
p.
data[1];
128 pt.z = out_frame.
p.
data[2];
geometry_msgs::Point32 project(const std::map< std::string, double > &joint_map)
void configure(const KDL::Tree &tree, const std::string &root, const std::string &tip)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const