-
Notifications
You must be signed in to change notification settings - Fork 332
/
joint_state_broadcaster.cpp
416 lines (365 loc) · 13.5 KB
/
joint_state_broadcaster.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
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
// Copyright 2021 ros2_control development team
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "joint_state_broadcaster/joint_state_broadcaster.hpp"
#include <cstddef>
#include <limits>
#include <memory>
#include <string>
#include <unordered_map>
#include <vector>
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/time.hpp"
#include "std_msgs/msg/header.hpp"
#include "urdf/model.h"
namespace rclcpp_lifecycle
{
class State;
} // namespace rclcpp_lifecycle
namespace joint_state_broadcaster
{
const auto kUninitializedValue = std::numeric_limits<double>::quiet_NaN();
using hardware_interface::HW_IF_EFFORT;
using hardware_interface::HW_IF_POSITION;
using hardware_interface::HW_IF_VELOCITY;
JointStateBroadcaster::JointStateBroadcaster() {}
controller_interface::CallbackReturn JointStateBroadcaster::on_init()
{
try
{
param_listener_ = std::make_shared<ParamListener>(get_node());
params_ = param_listener_->get_params();
}
catch (const std::exception & e)
{
fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
return CallbackReturn::ERROR;
}
return CallbackReturn::SUCCESS;
}
controller_interface::InterfaceConfiguration
JointStateBroadcaster::command_interface_configuration() const
{
return controller_interface::InterfaceConfiguration{
controller_interface::interface_configuration_type::NONE};
}
controller_interface::InterfaceConfiguration JointStateBroadcaster::state_interface_configuration()
const
{
controller_interface::InterfaceConfiguration state_interfaces_config;
if (use_all_available_interfaces())
{
state_interfaces_config.type = controller_interface::interface_configuration_type::ALL;
}
else
{
state_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL;
for (const auto & joint : params_.joints)
{
for (const auto & interface : params_.interfaces)
{
state_interfaces_config.names.push_back(joint + "/" + interface);
}
}
}
return state_interfaces_config;
}
controller_interface::CallbackReturn JointStateBroadcaster::on_configure(
const rclcpp_lifecycle::State & /*previous_state*/)
{
if (!param_listener_)
{
RCLCPP_ERROR(get_node()->get_logger(), "Error encountered during init");
return controller_interface::CallbackReturn::ERROR;
}
params_ = param_listener_->get_params();
if (use_all_available_interfaces())
{
RCLCPP_INFO(
get_node()->get_logger(),
"'joints' or 'interfaces' parameter is empty. "
"All available state interfaces will be published");
params_.joints.clear();
params_.interfaces.clear();
}
else
{
RCLCPP_INFO(
get_node()->get_logger(),
"Publishing state interfaces defined in 'joints' and 'interfaces' parameters.");
}
auto get_map_interface_parameter =
[&](std::string const & interface, std::string const & interface_to_map)
{
if (
std::find(params_.interfaces.begin(), params_.interfaces.end(), interface) !=
params_.interfaces.end())
{
map_interface_to_joint_state_[interface] = interface;
RCLCPP_WARN(
get_node()->get_logger(),
"Mapping from '%s' to interface '%s' will not be done, because '%s' is defined "
"in 'interface' parameter.",
interface_to_map.c_str(), interface.c_str(), interface.c_str());
}
else
{
map_interface_to_joint_state_[interface_to_map] = interface;
}
};
map_interface_to_joint_state_ = {};
get_map_interface_parameter(HW_IF_POSITION, params_.map_interface_to_joint_state.position);
get_map_interface_parameter(HW_IF_VELOCITY, params_.map_interface_to_joint_state.velocity);
get_map_interface_parameter(HW_IF_EFFORT, params_.map_interface_to_joint_state.effort);
try
{
const std::string topic_name_prefix = params_.use_local_topics ? "~/" : "";
joint_state_publisher_ = get_node()->create_publisher<sensor_msgs::msg::JointState>(
topic_name_prefix + "joint_states", rclcpp::SystemDefaultsQoS());
realtime_joint_state_publisher_ =
std::make_shared<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>(
joint_state_publisher_);
dynamic_joint_state_publisher_ =
get_node()->create_publisher<control_msgs::msg::DynamicJointState>(
topic_name_prefix + "dynamic_joint_states", rclcpp::SystemDefaultsQoS());
realtime_dynamic_joint_state_publisher_ =
std::make_shared<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>>(
dynamic_joint_state_publisher_);
}
catch (const std::exception & e)
{
// get_node() may throw, logging raw here
fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
return CallbackReturn::ERROR;
}
const std::string & urdf = get_robot_description();
is_model_loaded_ = !urdf.empty() && model_.initString(urdf);
if (!is_model_loaded_)
{
RCLCPP_ERROR(
get_node()->get_logger(),
"Failed to parse robot description. Will publish all the interfaces with '%s', '%s' and '%s'",
HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_EFFORT);
}
return CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn JointStateBroadcaster::on_activate(
const rclcpp_lifecycle::State & /*previous_state*/)
{
if (!init_joint_data())
{
RCLCPP_ERROR(
get_node()->get_logger(), "None of requested interfaces exist. Controller will not run.");
return CallbackReturn::ERROR;
}
init_joint_state_msg();
init_dynamic_joint_state_msg();
if (
!use_all_available_interfaces() &&
state_interfaces_.size() != (params_.joints.size() * params_.interfaces.size()))
{
RCLCPP_WARN(
get_node()->get_logger(),
"Not all requested interfaces exists. "
"Check ControllerManager output for more detailed information.");
}
return CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn JointStateBroadcaster::on_deactivate(
const rclcpp_lifecycle::State & /*previous_state*/)
{
joint_names_.clear();
name_if_value_mapping_.clear();
return CallbackReturn::SUCCESS;
}
template <typename T>
bool has_any_key(
const std::unordered_map<std::string, T> & map, const std::vector<std::string> & keys)
{
bool found_key = false;
for (const auto & key_item : map)
{
const auto & key = key_item.first;
if (std::find(keys.cbegin(), keys.cend(), key) != keys.cend())
{
found_key = true;
break;
}
}
return found_key;
}
bool JointStateBroadcaster::init_joint_data()
{
joint_names_.clear();
if (state_interfaces_.empty())
{
return false;
}
// loop in reverse order, this maintains the order of values at retrieval time
for (auto si = state_interfaces_.crbegin(); si != state_interfaces_.crend(); si++)
{
// initialize map if name is new
if (name_if_value_mapping_.count(si->get_prefix_name()) == 0)
{
name_if_value_mapping_[si->get_prefix_name()] = {};
}
// add interface name
std::string interface_name = si->get_interface_name();
if (map_interface_to_joint_state_.count(interface_name) > 0)
{
interface_name = map_interface_to_joint_state_[interface_name];
}
name_if_value_mapping_[si->get_prefix_name()][interface_name] = kUninitializedValue;
}
// filter state interfaces that have at least one of the joint_states fields,
// the rest will be ignored for this message
for (const auto & name_ifv : name_if_value_mapping_)
{
const auto & interfaces_and_values = name_ifv.second;
if (has_any_key(interfaces_and_values, {HW_IF_POSITION, HW_IF_VELOCITY, HW_IF_EFFORT}))
{
if (
!params_.use_urdf_to_filter || !params_.joints.empty() || !is_model_loaded_ ||
model_.getJoint(name_ifv.first))
{
joint_names_.push_back(name_ifv.first);
}
}
}
// Add extra joints from parameters, each joint will be added to joint_names_ and
// name_if_value_mapping_ if it is not already there
rclcpp::Parameter extra_joints;
if (get_node()->get_parameter("extra_joints", extra_joints))
{
const std::vector<std::string> & extra_joints_names = extra_joints.as_string_array();
for (const auto & extra_joint_name : extra_joints_names)
{
if (name_if_value_mapping_.count(extra_joint_name) == 0)
{
name_if_value_mapping_[extra_joint_name] = {
{HW_IF_POSITION, 0.0}, {HW_IF_VELOCITY, 0.0}, {HW_IF_EFFORT, 0.0}};
joint_names_.push_back(extra_joint_name);
}
}
}
return true;
}
void JointStateBroadcaster::init_joint_state_msg()
{
const size_t num_joints = joint_names_.size();
/// @note joint_state_msg publishes position, velocity and effort for all joints,
/// with at least one of these interfaces, the rest are omitted from this message
// default initialization for joint state message
auto & joint_state_msg = realtime_joint_state_publisher_->msg_;
joint_state_msg.name = joint_names_;
joint_state_msg.position.resize(num_joints, kUninitializedValue);
joint_state_msg.velocity.resize(num_joints, kUninitializedValue);
joint_state_msg.effort.resize(num_joints, kUninitializedValue);
}
void JointStateBroadcaster::init_dynamic_joint_state_msg()
{
auto & dynamic_joint_state_msg = realtime_dynamic_joint_state_publisher_->msg_;
dynamic_joint_state_msg.joint_names.clear();
dynamic_joint_state_msg.interface_values.clear();
for (const auto & name_ifv : name_if_value_mapping_)
{
const auto & name = name_ifv.first;
const auto & interfaces_and_values = name_ifv.second;
dynamic_joint_state_msg.joint_names.push_back(name);
control_msgs::msg::InterfaceValue if_value;
for (const auto & interface_and_value : interfaces_and_values)
{
if_value.interface_names.emplace_back(interface_and_value.first);
if_value.values.emplace_back(kUninitializedValue);
}
dynamic_joint_state_msg.interface_values.emplace_back(if_value);
}
}
bool JointStateBroadcaster::use_all_available_interfaces() const
{
return params_.joints.empty() || params_.interfaces.empty();
}
double get_value(
const std::unordered_map<std::string, std::unordered_map<std::string, double>> & map,
const std::string & name, const std::string & interface_name)
{
const auto & interfaces_and_values = map.at(name);
const auto interface_and_value = interfaces_and_values.find(interface_name);
if (interface_and_value != interfaces_and_values.cend())
{
return interface_and_value->second;
}
else
{
return kUninitializedValue;
}
}
controller_interface::return_type JointStateBroadcaster::update(
const rclcpp::Time & time, const rclcpp::Duration & /*period*/)
{
for (const auto & state_interface : state_interfaces_)
{
std::string interface_name = state_interface.get_interface_name();
if (map_interface_to_joint_state_.count(interface_name) > 0)
{
interface_name = map_interface_to_joint_state_[interface_name];
}
name_if_value_mapping_[state_interface.get_prefix_name()][interface_name] =
state_interface.get_value();
RCLCPP_DEBUG(
get_node()->get_logger(), "%s: %f\n", state_interface.get_name().c_str(),
state_interface.get_value());
}
if (realtime_joint_state_publisher_ && realtime_joint_state_publisher_->trylock())
{
auto & joint_state_msg = realtime_joint_state_publisher_->msg_;
joint_state_msg.header.stamp = time;
// update joint state message and dynamic joint state message
for (size_t i = 0; i < joint_names_.size(); ++i)
{
joint_state_msg.position[i] =
get_value(name_if_value_mapping_, joint_names_[i], HW_IF_POSITION);
joint_state_msg.velocity[i] =
get_value(name_if_value_mapping_, joint_names_[i], HW_IF_VELOCITY);
joint_state_msg.effort[i] = get_value(name_if_value_mapping_, joint_names_[i], HW_IF_EFFORT);
}
realtime_joint_state_publisher_->unlockAndPublish();
}
if (realtime_dynamic_joint_state_publisher_ && realtime_dynamic_joint_state_publisher_->trylock())
{
auto & dynamic_joint_state_msg = realtime_dynamic_joint_state_publisher_->msg_;
dynamic_joint_state_msg.header.stamp = time;
for (size_t joint_index = 0; joint_index < dynamic_joint_state_msg.joint_names.size();
++joint_index)
{
const auto & name = dynamic_joint_state_msg.joint_names[joint_index];
for (size_t interface_index = 0;
interface_index <
dynamic_joint_state_msg.interface_values[joint_index].interface_names.size();
++interface_index)
{
const auto & interface_name =
dynamic_joint_state_msg.interface_values[joint_index].interface_names[interface_index];
dynamic_joint_state_msg.interface_values[joint_index].values[interface_index] =
name_if_value_mapping_[name][interface_name];
}
}
realtime_dynamic_joint_state_publisher_->unlockAndPublish();
}
return controller_interface::return_type::OK;
}
} // namespace joint_state_broadcaster
#include "pluginlib/class_list_macros.hpp"
PLUGINLIB_EXPORT_CLASS(
joint_state_broadcaster::JointStateBroadcaster, controller_interface::ControllerInterface)