$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00036 00037 #include <cstdio> 00038 #include <ros/console.h> 00039 #include <laser_joint_projector/laser_joint_projector.h> 00040 #include <calibration_msgs/JointStateCalibrationPattern.h> 00041 00042 using namespace laser_joint_projector; 00043 using namespace std; 00044 00045 LaserJointProjector::LaserJointProjector() 00046 { 00047 00048 } 00049 00050 void LaserJointProjector::configure(const KDL::Tree& tree, 00051 const std::string& root, const std::string& tip) 00052 { 00053 bool success; 00054 success = tree.getChain(root, tip, chain_); 00055 if (!success) 00056 ROS_ERROR("Error extracting chain from [%s] to [%s]\n", root.c_str(), tip.c_str()); 00057 00058 KDL::Segment angle_segment("laser_angle_segment", 00059 KDL::Joint("laser_angle_joint", KDL::Joint::RotZ)); 00060 KDL::Segment range_segment("laser_range_segment", 00061 KDL::Joint("laser_range_joint", KDL::Joint::TransX)); 00062 00063 chain_.addSegment(angle_segment); 00064 chain_.addSegment(range_segment); 00065 00066 for (unsigned int i=0; i < chain_.segments.size(); i++) 00067 { 00068 printf("%2u) %s -> %s\n", i, chain_.segments[i].getName().c_str(), 00069 chain_.segments[i].getJoint().getName().c_str()); 00070 } 00071 00072 solver_.reset(new KDL::ChainFkSolverPos_recursive(chain_)); 00073 } 00074 00075 sensor_msgs::PointCloud LaserJointProjector::project(const vector<sensor_msgs::JointState>& joint_state_vec, const ros::Duration& time_shift) 00076 { 00077 sensor_msgs::PointCloud cloud; 00078 cloud.points.clear(); 00079 00080 for (unsigned int i=0; i<joint_state_vec.size(); i++) 00081 { 00082 map<string, double> joint_map; 00083 for (unsigned int j=0; j<joint_state_vec[i].name.size(); j++) 00084 { 00085 joint_map.insert(make_pair(joint_state_vec[i].name[j], 00086 joint_state_vec[i].position[j] + joint_state_vec[i].velocity[j]*time_shift.toSec())); 00087 } 00088 geometry_msgs::Point32 pt = project(joint_map); 00089 cloud.points.push_back(pt); 00090 } 00091 00092 return cloud; 00093 } 00094 00095 00096 geometry_msgs::Point32 LaserJointProjector::project(const map<string, double>& joint_map) 00097 { 00098 KDL::JntArray joint_pos_array(chain_.getNrOfJoints()); 00099 00100 // Populate the JntArray, by looking into map, based on joint names in chain 00101 unsigned int cur_joint_num=0; 00102 for (unsigned int i=0; i<chain_.getNrOfSegments(); i++) 00103 { 00104 if (chain_.getSegment(i).getJoint().getType() != KDL::Joint::None) 00105 { 00106 string joint_name = chain_.getSegment(i).getJoint().getName(); 00107 map<string, double>::const_iterator it = joint_map.find(joint_name); 00108 00109 if (it == joint_map.end()) 00110 { 00111 ROS_ERROR("Couldn't find joint [%s] in map", joint_name.c_str()); 00112 joint_pos_array(cur_joint_num, 0) = 0.0; 00113 } 00114 else 00115 { 00116 joint_pos_array(cur_joint_num, 0) = (*it).second; 00117 } 00118 cur_joint_num++; 00119 } 00120 } 00121 00122 KDL::Frame out_frame; 00123 solver_->JntToCart(joint_pos_array, out_frame); 00124 00125 geometry_msgs::Point32 pt; 00126 pt.x = out_frame.p.data[0]; 00127 pt.y = out_frame.p.data[1]; 00128 pt.z = out_frame.p.data[2]; 00129 00130 return pt; 00131 }