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
00036
00037 #include <cstdio>
00038 #include <laser_joint_projector/laser_joint_projector.h>
00039 #include <calibration_msgs/JointStateCalibrationPattern.h>
00040
00041 using namespace laser_joint_projector;
00042 using namespace std;
00043
00044 LaserJointProjector::LaserJointProjector()
00045 {
00046
00047 }
00048
00049 void LaserJointProjector::configure(const KDL::Tree& tree,
00050 const std::string& root, const std::string& tip)
00051 {
00052 bool success;
00053 success = tree.getChain(root, tip, chain_);
00054 if (!success)
00055 ROS_ERROR("Error extracting chain from [%s] to [%s]\n", root.c_str(), tip.c_str());
00056
00057 KDL::Segment angle_segment("laser_angle_segment",
00058 KDL::Joint("laser_angle_joint", KDL::Joint::RotZ));
00059 KDL::Segment range_segment("laser_range_segment",
00060 KDL::Joint("laser_range_joint", KDL::Joint::TransX));
00061
00062 chain_.addSegment(angle_segment);
00063 chain_.addSegment(range_segment);
00064
00065 for (unsigned int i=0; i < chain_.segments.size(); i++)
00066 {
00067 printf("%2u) %s -> %s\n", i, chain_.segments[i].getName().c_str(),
00068 chain_.segments[i].getJoint().getName().c_str());
00069 }
00070
00071 solver_.reset(new KDL::ChainFkSolverPos_recursive(chain_));
00072 }
00073
00074 sensor_msgs::PointCloud LaserJointProjector::project(const vector<sensor_msgs::JointState>& joint_state_vec, const ros::Duration& time_shift)
00075 {
00076 sensor_msgs::PointCloud cloud;
00077 cloud.points.clear();
00078
00079 for (unsigned int i=0; i<joint_state_vec.size(); i++)
00080 {
00081 map<string, double> joint_map;
00082 for (unsigned int j=0; j<joint_state_vec[i].name.size(); j++)
00083 {
00084 joint_map.insert(make_pair(joint_state_vec[i].name[j],
00085 joint_state_vec[i].position[j] + joint_state_vec[i].velocity[j]*time_shift.toSec()));
00086 }
00087 geometry_msgs::Point32 pt = project(joint_map);
00088 cloud.points.push_back(pt);
00089 }
00090
00091 return cloud;
00092 }
00093
00094
00095 geometry_msgs::Point32 LaserJointProjector::project(const map<string, double>& joint_map)
00096 {
00097 KDL::JntArray joint_pos_array(chain_.getNrOfJoints());
00098
00099
00100 unsigned int cur_joint_num=0;
00101 for (unsigned int i=0; i<chain_.getNrOfSegments(); i++)
00102 {
00103 if (chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
00104 {
00105 string joint_name = chain_.getSegment(i).getJoint().getName();
00106 map<string, double>::const_iterator it = joint_map.find(joint_name);
00107
00108 if (it == joint_map.end())
00109 {
00110 ROS_ERROR("Couldn't find joint [%s] in map", joint_name.c_str());
00111 joint_pos_array(cur_joint_num, 0) = 0.0;
00112 }
00113 else
00114 {
00115 joint_pos_array(cur_joint_num, 0) = (*it).second;
00116 }
00117 cur_joint_num++;
00118 }
00119 }
00120
00121 KDL::Frame out_frame;
00122 solver_->JntToCart(joint_pos_array, out_frame);
00123
00124 geometry_msgs::Point32 pt;
00125 pt.x = out_frame.p.data[0];
00126 pt.y = out_frame.p.data[1];
00127 pt.z = out_frame.p.data[2];
00128
00129 return pt;
00130 }