robot_state_publisher.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 
35 /* Author: Wim Meeussen */
36 
37 #include <map>
38 #include <string>
39 
40 #include <kdl/frames_io.hpp>
41 #include <geometry_msgs/TransformStamped.h>
42 #include <tf2_kdl/tf2_kdl.h>
43 
45 
46 namespace robot_state_publisher {
47 
48 RobotStatePublisher::RobotStatePublisher() : RobotStatePublisher(KDL::Tree())
49 {
50 }
51 
52 RobotStatePublisher::RobotStatePublisher(const KDL::Tree& tree, const urdf::Model& model)
53  : model_(model)
54 {
55  // walk the tree and add segments to segments_
56  addChildren(tree.getRootSegment());
57 }
58 
59 // add children to correct maps
60 void RobotStatePublisher::addChildren(const KDL::SegmentMap::const_iterator segment)
61 {
62  const std::string& root = GetTreeElementSegment(segment->second).getName();
63 
64  const std::vector<KDL::SegmentMap::const_iterator>& children = GetTreeElementChildren(segment->second);
65  for (size_t i = 0; i < children.size(); ++i) {
66  const KDL::Segment& child = GetTreeElementSegment(children[i]->second);
67  SegmentPair s(GetTreeElementSegment(children[i]->second), root, child.getName());
68  if (child.getJoint().getType() == KDL::Joint::None) {
69  if (model_.getJoint(child.getJoint().getName()) && model_.getJoint(child.getJoint().getName())->type == urdf::Joint::FLOATING) {
70  ROS_INFO("Floating joint. Not adding segment from %s to %s. This TF can not be published based on joint_states info", root.c_str(), child.getName().c_str());
71  }
72  else {
73  segments_fixed_.insert(make_pair(child.getJoint().getName(), s));
74  ROS_DEBUG("Adding fixed segment from %s to %s", root.c_str(), child.getName().c_str());
75  }
76  }
77  else {
78  segments_.insert(make_pair(child.getJoint().getName(), s));
79  ROS_DEBUG("Adding moving segment from %s to %s", root.c_str(), child.getName().c_str());
80  }
81  addChildren(children[i]);
82  }
83 }
84 
85 std::string stripSlash(const std::string & in)
86 {
87  if (in.size() && in[0] == '/')
88  {
89  return in.substr(1);
90  }
91  return in;
92 }
93 
94 // Replicate behavior of tf 1 tf_prefix
95 std::string prefix_frame(const std::string & tf_prefix, const std::string & frame)
96 {
97  // If the frame begins with a slash, remove the first slash and don't add prefix at all
98  if (frame.size() && frame[0] == '/') {
99  return frame.substr(1);
100  }
101 
102  std::string prefixed_frame;
103 
104  // If the prefix begins with a slash, remove it
105  if (tf_prefix.size() && tf_prefix[0] == '/') {
106  prefixed_frame = tf_prefix.substr(1);
107  } else {
108  prefixed_frame = tf_prefix;
109  }
110 
111  // Add a slash after a non-empty prefix
112  if (!tf_prefix.empty()) {
113  prefixed_frame += '/';
114  }
115 
116  prefixed_frame += frame;
117 
118  return prefixed_frame;
119 }
120 
121 // publish moving transforms
122 void RobotStatePublisher::publishTransforms(const std::map<std::string, double>& joint_positions, const ros::Time& time, const std::string & tf_prefix)
123 {
124  ROS_DEBUG("Publishing transforms for moving joints");
125  std::vector<geometry_msgs::TransformStamped> tf_transforms;
126 
127  // loop over all joints
128  for (std::map<std::string, double>::const_iterator jnt = joint_positions.begin(); jnt != joint_positions.end(); jnt++) {
129  std::map<std::string, SegmentPair>::const_iterator seg = segments_.find(jnt->first);
130  if (seg != segments_.end()) {
131  geometry_msgs::TransformStamped tf_transform = tf2::kdlToTransform(seg->second.segment.pose(jnt->second));
132  tf_transform.header.stamp = time;
133  tf_transform.header.frame_id = prefix_frame(tf_prefix, seg->second.root);
134  tf_transform.child_frame_id = prefix_frame(tf_prefix, seg->second.tip);
135  tf_transforms.push_back(tf_transform);
136  }
137  else {
138  ROS_WARN_THROTTLE(10, "Joint state with name: \"%s\" was received but not found in URDF", jnt->first.c_str());
139  }
140  }
141  tf_broadcaster_.sendTransform(tf_transforms);
142 }
143 
144 // publish fixed transforms
145 void RobotStatePublisher::publishFixedTransforms(const std::string & tf_prefix, bool use_tf_static)
146 {
147  ROS_DEBUG("Publishing transforms for fixed joints");
148  std::vector<geometry_msgs::TransformStamped> tf_transforms;
149  geometry_msgs::TransformStamped tf_transform;
150 
151  // loop over all fixed segments
152  for (std::map<std::string, SegmentPair>::const_iterator seg = segments_fixed_.begin(); seg != segments_fixed_.end(); seg++) {
153  geometry_msgs::TransformStamped tf_transform = tf2::kdlToTransform(seg->second.segment.pose(0));
154  tf_transform.header.stamp = ros::Time::now();
155  if (!use_tf_static) {
156  tf_transform.header.stamp += ros::Duration(0.5);
157  }
158  tf_transform.header.frame_id = prefix_frame(tf_prefix, seg->second.root);
159  tf_transform.child_frame_id = prefix_frame(tf_prefix, seg->second.tip);
160  tf_transforms.push_back(tf_transform);
161  }
162  if (use_tf_static) {
163  static_tf_broadcaster_.sendTransform(tf_transforms);
164  }
165  else {
166  tf_broadcaster_.sendTransform(tf_transforms);
167  }
168 }
169 
170 void RobotStatePublisher::publishTransforms(const std::map<std::string, double>& joint_positions, const ros::Time& time)
171 {
172  publishTransforms(joint_positions, time, "");
173 }
174 
175 void RobotStatePublisher::publishFixedTransforms(bool use_tf_static)
176 {
177  publishFixedTransforms("", use_tf_static);
178 }
179 
180 }
tf2_ros::StaticTransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
robot_state_publisher::stripSlash
std::string stripSlash(const std::string &in)
Definition: robot_state_publisher.cpp:117
robot_state_publisher::RobotStatePublisher::tf_broadcaster_
tf2_ros::TransformBroadcaster tf_broadcaster_
Definition: robot_state_publisher.h:128
robot_state_publisher::RobotStatePublisher::addChildren
virtual void addChildren(const KDL::SegmentMap::const_iterator segment)
Definition: robot_state_publisher.cpp:92
s
XmlRpcServer s
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
robot_state_publisher::RobotStatePublisher::publishFixedTransforms
virtual void publishFixedTransforms(bool use_tf_static=false)
Definition: robot_state_publisher.cpp:207
robot_state_publisher::prefix_frame
std::string prefix_frame(const std::string &tf_prefix, const std::string &frame)
Definition: robot_state_publisher.cpp:127
ROS_DEBUG
#define ROS_DEBUG(...)
urdf::Model
robot_state_publisher::RobotStatePublisher::segments_
std::map< std::string, SegmentPair > segments_
Definition: robot_state_publisher.h:126
tf2::kdlToTransform
geometry_msgs::TransformStamped kdlToTransform(const KDL::Frame &k)
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
tf2_kdl.h
robot_state_publisher::RobotStatePublisher::static_tf_broadcaster_
tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_
Definition: robot_state_publisher.h:129
robot_state_publisher
Definition: joint_state_listener.h:52
robot_state_publisher.h
ros::Time
robot_state_publisher::RobotStatePublisher::publishTransforms
virtual void publishTransforms(const std::map< std::string, double > &joint_positions, const ros::Time &time)
Definition: robot_state_publisher.cpp:202
robot_state_publisher::RobotStatePublisher::segments_fixed_
std::map< std::string, SegmentPair > segments_fixed_
Definition: robot_state_publisher.h:126
ROS_INFO
#define ROS_INFO(...)
ros::Duration
robot_state_publisher::RobotStatePublisher::RobotStatePublisher
RobotStatePublisher()
Definition: robot_state_publisher.cpp:80
robot_state_publisher::RobotStatePublisher::model_
urdf::Model model_
Definition: robot_state_publisher.h:127
ros::Time::now
static Time now()


robot_state_publisher
Author(s): Ioan Sucan , Jackie Kay , Wim Meeussen
autogenerated on Fri Nov 3 2023 02:08:42