-
Notifications
You must be signed in to change notification settings - Fork 171
/
Copy pathrobot_state_publisher.cpp
131 lines (117 loc) · 5.56 KB
/
robot_state_publisher.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Wim Meeussen */
#include <kdl/frames_io.hpp>
#include <geometry_msgs/TransformStamped.h>
#include <tf2_kdl/tf2_kdl.h>
#include "robot_state_publisher/robot_state_publisher.h"
using namespace std;
using namespace ros;
namespace robot_state_publisher {
RobotStatePublisher::RobotStatePublisher(const KDL::Tree& tree, const urdf::Model& model)
: model_(model)
{
// walk the tree and add segments to segments_
addChildren(tree.getRootSegment());
}
// add children to correct maps
void RobotStatePublisher::addChildren(const KDL::SegmentMap::const_iterator segment)
{
const std::string& root = GetTreeElementSegment(segment->second).getName();
const std::vector<KDL::SegmentMap::const_iterator>& children = GetTreeElementChildren(segment->second);
for (unsigned int i=0; i<children.size(); i++) {
const KDL::Segment& child = GetTreeElementSegment(children[i]->second);
SegmentPair s(GetTreeElementSegment(children[i]->second), root, child.getName());
if (child.getJoint().getType() == KDL::Joint::None) {
if (model_.getJoint(child.getJoint().getName()) && model_.getJoint(child.getJoint().getName())->type == urdf::Joint::FLOATING) {
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());
}
else {
segments_fixed_.insert(make_pair(child.getJoint().getName(), s));
ROS_DEBUG("Adding fixed segment from %s to %s", root.c_str(), child.getName().c_str());
}
}
else {
segments_.insert(make_pair(child.getJoint().getName(), s));
ROS_DEBUG("Adding moving segment from %s to %s", root.c_str(), child.getName().c_str());
}
addChildren(children[i]);
}
}
// publish moving transforms
void RobotStatePublisher::publishTransforms(const map<string, double>& joint_positions, const Time& time, const std::string& tf_prefix)
{
ROS_DEBUG("Publishing transforms for moving joints");
std::vector<geometry_msgs::TransformStamped> tf_transforms;
// loop over all joints
for (map<string, double>::const_iterator jnt=joint_positions.begin(); jnt != joint_positions.end(); jnt++) {
std::map<std::string, SegmentPair>::const_iterator seg = segments_.find(jnt->first);
if (seg != segments_.end()) {
geometry_msgs::TransformStamped tf_transform = tf2::kdlToTransform(seg->second.segment.pose(jnt->second));
tf_transform.header.stamp = time;
tf_transform.header.frame_id = tf::resolve(tf_prefix, seg->second.root);
tf_transform.child_frame_id = tf::resolve(tf_prefix, seg->second.tip);
tf_transforms.push_back(tf_transform);
}
else {
ROS_WARN_THROTTLE(10, "Joint state with name: \"%s\" was received but not found in URDF", jnt->first.c_str());
}
}
tf_broadcaster_.sendTransform(tf_transforms);
}
// publish fixed transforms
void RobotStatePublisher::publishFixedTransforms(const std::string& tf_prefix, bool use_tf_static)
{
ROS_DEBUG("Publishing transforms for fixed joints");
std::vector<geometry_msgs::TransformStamped> tf_transforms;
geometry_msgs::TransformStamped tf_transform;
// loop over all fixed segments
for (map<string, SegmentPair>::const_iterator seg=segments_fixed_.begin(); seg != segments_fixed_.end(); seg++) {
geometry_msgs::TransformStamped tf_transform = tf2::kdlToTransform(seg->second.segment.pose(0));
tf_transform.header.stamp = ros::Time::now();
if (!use_tf_static) {
tf_transform.header.stamp += ros::Duration(0.5);
}
tf_transform.header.frame_id = tf::resolve(tf_prefix, seg->second.root);
tf_transform.child_frame_id = tf::resolve(tf_prefix, seg->second.tip);
tf_transforms.push_back(tf_transform);
}
if (use_tf_static) {
static_tf_broadcaster_.sendTransform(tf_transforms);
}
else {
tf_broadcaster_.sendTransform(tf_transforms);
}
}
}