laser_joint_projector.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
36 
37 #include <cstdio>
38 #include <ros/console.h>
40 #include <calibration_msgs/JointStateCalibrationPattern.h>
41 
42 using namespace laser_joint_projector;
43 using namespace std;
44 
46 {
47 
48 }
49 
51  const std::string& root, const std::string& tip)
52 {
53  bool success;
54  success = tree.getChain(root, tip, chain_);
55  if (!success)
56  ROS_ERROR("Error extracting chain from [%s] to [%s]\n", root.c_str(), tip.c_str());
57 
58  KDL::Segment angle_segment("laser_angle_segment",
59  KDL::Joint("laser_angle_joint", KDL::Joint::RotZ));
60  KDL::Segment range_segment("laser_range_segment",
61  KDL::Joint("laser_range_joint", KDL::Joint::TransX));
62 
63  chain_.addSegment(angle_segment);
64  chain_.addSegment(range_segment);
65 
66  for (unsigned int i=0; i < chain_.segments.size(); i++)
67  {
68  printf("%2u) %s -> %s\n", i, chain_.segments[i].getName().c_str(),
69  chain_.segments[i].getJoint().getName().c_str());
70  }
71 
72  solver_.reset(new KDL::ChainFkSolverPos_recursive(chain_));
73 }
74 
75 sensor_msgs::PointCloud LaserJointProjector::project(const vector<sensor_msgs::JointState>& joint_state_vec, const ros::Duration& time_shift)
76 {
77  sensor_msgs::PointCloud cloud;
78  cloud.points.clear();
79 
80  for (unsigned int i=0; i<joint_state_vec.size(); i++)
81  {
82  map<string, double> joint_map;
83  for (unsigned int j=0; j<joint_state_vec[i].name.size(); j++)
84  {
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()));
87  }
88  geometry_msgs::Point32 pt = project(joint_map);
89  cloud.points.push_back(pt);
90  }
91 
92  return cloud;
93 }
94 
95 
96 geometry_msgs::Point32 LaserJointProjector::project(const map<string, double>& joint_map)
97 {
98  KDL::JntArray joint_pos_array(chain_.getNrOfJoints());
99 
100  // Populate the JntArray, by looking into map, based on joint names in chain
101  unsigned int cur_joint_num=0;
102  for (unsigned int i=0; i<chain_.getNrOfSegments(); i++)
103  {
104  if (chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
105  {
106  string joint_name = chain_.getSegment(i).getJoint().getName();
107  map<string, double>::const_iterator it = joint_map.find(joint_name);
108 
109  if (it == joint_map.end())
110  {
111  ROS_ERROR("Couldn't find joint [%s] in map", joint_name.c_str());
112  joint_pos_array(cur_joint_num, 0) = 0.0;
113  }
114  else
115  {
116  joint_pos_array(cur_joint_num, 0) = (*it).second;
117  }
118  cur_joint_num++;
119  }
120  }
121 
122  KDL::Frame out_frame;
123  solver_->JntToCart(joint_pos_array, out_frame);
124 
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];
129 
130  return pt;
131 }
double data[3]
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
#define ROS_ERROR(...)


laser_joint_projector
Author(s): Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:50:56