-
Notifications
You must be signed in to change notification settings - Fork 90
/
ignition_ros2_control_plugin.cpp
467 lines (401 loc) · 16.2 KB
/
ignition_ros2_control_plugin.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
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
// Copyright 2021 Open Source Robotics Foundation, Inc.
//
// 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 <controller_manager/controller_manager.hpp>
#include <hardware_interface/resource_manager.hpp>
#include <hardware_interface/component_parser.hpp>
#include <hardware_interface/types/hardware_interface_type_values.hpp>
#include <ignition/gazebo/components/Joint.hh>
#include <ignition/gazebo/components/JointType.hh>
#include <ignition/gazebo/components/Name.hh>
#include <ignition/gazebo/components/ParentEntity.hh>
#include <ignition/gazebo/components/World.hh>
#include <ignition/gazebo/Model.hh>
#include <ignition/plugin/Register.hh>
#include <pluginlib/class_loader.hpp>
#include <rclcpp/rclcpp.hpp>
#include <map>
#include <memory>
#include <string>
#include <utility>
#include <vector>
#include "ignition_ros2_control/ignition_ros2_control_plugin.hpp"
#include "ignition_ros2_control/ignition_system.hpp"
namespace ignition_ros2_control
{
//////////////////////////////////////////////////
class IgnitionROS2ControlPluginPrivate
{
public:
/// \brief Get the URDF XML from the parameter server
std::string getURDF() const;
/// \brief Get a list of enabled, unique, 1-axis joints of the model. If no
/// joint names are specified in the plugin configuration, all valid 1-axis
/// joints are returned
/// \param[in] _entity Entity of the model that the plugin is being
/// configured for
/// \param[in] _ecm Ignition Entity Component Manager
/// \return List of entities containinig all enabled joints
std::map<std::string, ignition::gazebo::Entity> GetEnabledJoints(
const ignition::gazebo::Entity & _entity,
ignition::gazebo::EntityComponentManager & _ecm) const;
/// \brief Entity ID for sensor within Gazebo.
ignition::gazebo::Entity entity_;
/// \brief Node Handles
std::shared_ptr<rclcpp::Node> node;
/// \brief Thread where the executor will sping
std::thread thread_executor_spin_;
/// \brief Flag to stop the executor thread when this plugin is exiting
bool stop_;
/// \brief Executor to spin the controller
rclcpp::executors::MultiThreadedExecutor::SharedPtr executor_;
/// \brief Timing
rclcpp::Duration control_period_ = rclcpp::Duration(1, 0);
/// \brief Interface loader
boost::shared_ptr<pluginlib::ClassLoader<
ignition_ros2_control::IgnitionSystemInterface>> robot_hw_sim_loader_;
/// \brief Controller manager
std::shared_ptr<controller_manager::ControllerManager> controller_manager_;
/// \brief String with the robot description param_name
// TODO(ahcorde): Add param in plugin tag
std::string robot_description_ = "robot_description";
/// \brief String with the name of the node that contains the robot_description
// TODO(ahcorde): Add param in plugin tag
std::string robot_description_node_ = "robot_state_publisher";
/// \brief Last time the update method was called
rclcpp::Time last_update_sim_time_ros_;
/// \brief ECM pointer
ignition::gazebo::EntityComponentManager * ecm;
};
//////////////////////////////////////////////////
std::map<std::string, ignition::gazebo::Entity>
IgnitionROS2ControlPluginPrivate::GetEnabledJoints(
const ignition::gazebo::Entity & _entity,
ignition::gazebo::EntityComponentManager & _ecm) const
{
std::map<std::string, ignition::gazebo::Entity> output;
std::vector<std::string> enabledJoints;
// Get all available joints
auto jointEntities = _ecm.ChildrenByComponents(_entity, ignition::gazebo::components::Joint());
// Iterate over all joints and verify whether they can be enabled or not
for (const auto & jointEntity : jointEntities) {
const auto jointName = _ecm.Component<ignition::gazebo::components::Name>(
jointEntity)->Data();
// Make sure the joint type is supported, i.e. it has exactly one
// actuated axis
const auto * jointType = _ecm.Component<ignition::gazebo::components::JointType>(jointEntity);
switch (jointType->Data()) {
case sdf::JointType::PRISMATIC:
case sdf::JointType::REVOLUTE:
case sdf::JointType::CONTINUOUS:
case sdf::JointType::GEARBOX:
{
// Supported joint type
break;
}
case sdf::JointType::FIXED:
{
RCLCPP_INFO(
node->get_logger(),
"[ignition_ros2_control] Fixed joint [%s] (Entity=%d)] is skipped",
jointName.c_str(), jointEntity);
continue;
}
case sdf::JointType::REVOLUTE2:
case sdf::JointType::SCREW:
case sdf::JointType::BALL:
case sdf::JointType::UNIVERSAL:
{
RCLCPP_WARN(
node->get_logger(),
"[ignition_ros2_control] Joint [%s] (Entity=%d)] is of unsupported type."
" Only joints with a single axis are supported.",
jointName.c_str(), jointEntity);
continue;
}
default:
{
RCLCPP_WARN(
node->get_logger(),
"[ignition_ros2_control] Joint [%s] (Entity=%d)] is of unknown type",
jointName.c_str(), jointEntity);
continue;
}
}
output[jointName] = jointEntity;
}
return output;
}
//////////////////////////////////////////////////
std::string IgnitionROS2ControlPluginPrivate::getURDF() const
{
std::string urdf_string;
using namespace std::chrono_literals;
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(
node, robot_description_node_);
while (!parameters_client->wait_for_service(0.5s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(
node->get_logger(), "Interrupted while waiting for %s service. Exiting.",
robot_description_node_.c_str());
return 0;
}
RCLCPP_ERROR(
node->get_logger(), "%s service not available, waiting again...",
robot_description_node_.c_str());
}
RCLCPP_INFO(
node->get_logger(), "connected to service!! %s asking for %s",
robot_description_node_.c_str(),
this->robot_description_.c_str());
// search and wait for robot_description on param server
while (urdf_string.empty()) {
RCLCPP_DEBUG(
node->get_logger(), "param_name %s",
this->robot_description_.c_str());
try {
auto f = parameters_client->get_parameters({this->robot_description_});
f.wait();
std::vector<rclcpp::Parameter> values = f.get();
urdf_string = values[0].as_string();
} catch (const std::exception & e) {
RCLCPP_ERROR(node->get_logger(), "%s", e.what());
}
if (!urdf_string.empty()) {
break;
} else {
RCLCPP_ERROR(
node->get_logger(), "ignition_ros2_control plugin is waiting for model"
" URDF in parameter [%s] on the ROS param server.",
this->robot_description_.c_str());
}
usleep(100000);
}
RCLCPP_INFO(node->get_logger(), "Received URDF from param server");
return urdf_string;
}
//////////////////////////////////////////////////
IgnitionROS2ControlPlugin::IgnitionROS2ControlPlugin()
: dataPtr(std::make_unique<IgnitionROS2ControlPluginPrivate>())
{
}
//////////////////////////////////////////////////
IgnitionROS2ControlPlugin::~IgnitionROS2ControlPlugin()
{
// Stop controller manager thread
this->dataPtr->stop_ = true;
this->dataPtr->executor_->remove_node(this->dataPtr->controller_manager_);
this->dataPtr->executor_->cancel();
this->dataPtr->thread_executor_spin_.join();
}
//////////////////////////////////////////////////
void IgnitionROS2ControlPlugin::Configure(
const ignition::gazebo::Entity & _entity,
const std::shared_ptr<const sdf::Element> & _sdf,
ignition::gazebo::EntityComponentManager & _ecm,
ignition::gazebo::EventManager &)
{
// Make sure the controller is attached to a valid model
const auto model = ignition::gazebo::Model(_entity);
if (!model.Valid(_ecm)) {
RCLCPP_ERROR(
this->dataPtr->node->get_logger(),
"[Ignition ROS 2 Control] Failed to initialize because [%s] (Entity=%u)] is not a model."
"Please make sure that Ignition ROS 2 Control is attached to a valid model.",
model.Name(_ecm).c_str(), _entity);
return;
}
// Get params from SDF
std::string paramFileName = _sdf->Get<std::string>("parameters");
if (paramFileName.empty()) {
RCLCPP_ERROR(
this->dataPtr->node->get_logger(),
"Ignition ros2 control found an empty parameters file. Failed to initialize.");
return;
}
std::vector<std::string> arguments = {"--ros-args", "--params-file", paramFileName};
auto sdfPtr = const_cast<sdf::Element *>(_sdf.get());
if (sdfPtr->HasElement("ros")) {
sdf::ElementPtr sdfRos = sdfPtr->GetElement("ros");
// Set namespace if tag is present
if (sdfRos->HasElement("namespace")) {
std::string ns = sdfRos->GetElement("namespace")->Get<std::string>();
// prevent exception: namespace must be absolute, it must lead with a '/'
if (ns.empty() || ns[0] != '/') {
ns = '/' + ns;
}
std::string ns_arg = std::string("__ns:=") + ns;
arguments.push_back(RCL_REMAP_FLAG);
arguments.push_back(ns_arg);
}
// Get list of remapping rules from SDF
if (sdfRos->HasElement("remapping")) {
sdf::ElementPtr argument_sdf = sdfRos->GetElement("remapping");
arguments.push_back(RCL_ROS_ARGS_FLAG);
while (argument_sdf) {
std::string argument = argument_sdf->Get<std::string>();
arguments.push_back(RCL_REMAP_FLAG);
arguments.push_back(argument);
argument_sdf = argument_sdf->GetNextElement("remapping");
}
}
}
std::vector<const char *> argv;
for (const auto & arg : arguments) {
argv.push_back(reinterpret_cast<const char *>(arg.data()));
}
if (!rclcpp::ok()) {
rclcpp::init(static_cast<int>(argv.size()), argv.data());
this->dataPtr->node = rclcpp::Node::make_shared("ignition_ros2_control");
}
this->dataPtr->executor_ = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();
this->dataPtr->executor_->add_node(this->dataPtr->node);
this->dataPtr->stop_ = false;
auto spin = [this]()
{
while (rclcpp::ok() && !this->dataPtr->stop_) {
this->dataPtr->executor_->spin_once();
}
};
this->dataPtr->thread_executor_spin_ = std::thread(spin);
RCLCPP_DEBUG_STREAM(
this->dataPtr->node->get_logger(), "[Ignition ROS 2 Control] Setting up controller for [" <<
model.Name(_ecm) << "] (Entity=" << _entity << ")].");
// Get list of enabled joints
auto enabledJoints = this->dataPtr->GetEnabledJoints(
_entity,
_ecm);
if (enabledJoints.size() == 0) {
RCLCPP_DEBUG_STREAM(
this->dataPtr->node->get_logger(), "[Ignition ROS 2 Control] There are no available Joints.");
return;
}
// Read urdf from ros parameter server then
// setup actuators and mechanism control node.
// This call will block if ROS is not properly initialized.
std::string urdf_string;
std::vector<hardware_interface::HardwareInfo> control_hardware;
try {
urdf_string = this->dataPtr->getURDF();
control_hardware = hardware_interface::parse_control_resources_from_urdf(urdf_string);
} catch (const std::runtime_error & ex) {
RCLCPP_ERROR_STREAM(
this->dataPtr->node->get_logger(),
"Error parsing URDF in ignition_ros2_control plugin, plugin not active : " << ex.what());
return;
}
std::unique_ptr<hardware_interface::ResourceManager> resource_manager_ =
std::make_unique<hardware_interface::ResourceManager>();
try {
this->dataPtr->robot_hw_sim_loader_.reset(
new pluginlib::ClassLoader<ignition_ros2_control::IgnitionSystemInterface>(
"ignition_ros2_control",
"ignition_ros2_control::IgnitionSystemInterface"));
} catch (pluginlib::LibraryLoadException & ex) {
RCLCPP_ERROR(
this->dataPtr->node->get_logger(), "Failed to create robot simulation interface loader: %s ",
ex.what());
return;
}
for (unsigned int i = 0; i < control_hardware.size(); ++i) {
std::string robot_hw_sim_type_str_ = control_hardware[i].hardware_class_type;
auto gazeboSystem = std::unique_ptr<ignition_ros2_control::IgnitionSystemInterface>(
this->dataPtr->robot_hw_sim_loader_->createUnmanagedInstance(robot_hw_sim_type_str_));
if (!gazeboSystem->initSim(
this->dataPtr->node,
enabledJoints,
control_hardware[i],
_ecm))
{
RCLCPP_FATAL(
this->dataPtr->node->get_logger(), "Could not initialize robot simulation interface");
return;
}
resource_manager_->import_component(std::move(gazeboSystem));
}
// Create the controller manager
RCLCPP_INFO(this->dataPtr->node->get_logger(), "Loading controller_manager");
this->dataPtr->controller_manager_.reset(
new controller_manager::ControllerManager(
std::move(resource_manager_),
this->dataPtr->executor_,
"controller_manager"));
this->dataPtr->executor_->add_node(this->dataPtr->controller_manager_);
if (!this->dataPtr->controller_manager_->has_parameter("update_rate")) {
RCLCPP_ERROR_STREAM(
this->dataPtr->node->get_logger(),
"controller manager doesn't have an update_rate parameter");
return;
}
auto cm_update_rate = this->dataPtr->controller_manager_->get_parameter("update_rate").as_int();
this->dataPtr->control_period_ = rclcpp::Duration(
std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<double>(1.0 / static_cast<double>(cm_update_rate))));
this->dataPtr->entity_ = _entity;
}
//////////////////////////////////////////////////
void IgnitionROS2ControlPlugin::PreUpdate(
const ignition::gazebo::UpdateInfo & _info,
ignition::gazebo::EntityComponentManager & /*_ecm*/)
{
static bool warned{false};
if (!warned) {
rclcpp::Duration gazebo_period(_info.dt);
// Check the period against the simulation period
if (this->dataPtr->control_period_ < _info.dt) {
RCLCPP_ERROR_STREAM(
this->dataPtr->node->get_logger(),
"Desired controller update period (" << this->dataPtr->control_period_.seconds() <<
" s) is faster than the gazebo simulation period (" <<
gazebo_period.seconds() << " s).");
} else if (this->dataPtr->control_period_ > gazebo_period) {
RCLCPP_WARN_STREAM(
this->dataPtr->node->get_logger(),
" Desired controller update period (" << this->dataPtr->control_period_.seconds() <<
" s) is slower than the gazebo simulation period (" <<
gazebo_period.seconds() << " s).");
}
warned = true;
}
// Always set commands on joints, otherwise at low control frequencies the joints tremble
// as they are updated at a fraction of gazebo sim time
this->dataPtr->controller_manager_->write();
}
//////////////////////////////////////////////////
void IgnitionROS2ControlPlugin::PostUpdate(
const ignition::gazebo::UpdateInfo & _info,
const ignition::gazebo::EntityComponentManager & /*_ecm*/)
{
// Get the simulation time and period
rclcpp::Time sim_time_ros(std::chrono::duration_cast<std::chrono::nanoseconds>(
_info.simTime).count());
rclcpp::Duration sim_period = sim_time_ros - this->dataPtr->last_update_sim_time_ros_;
if (sim_period >= this->dataPtr->control_period_) {
this->dataPtr->last_update_sim_time_ros_ = sim_time_ros;
auto ign_controller_manager =
std::dynamic_pointer_cast<ignition_ros2_control::IgnitionSystemInterface>(
this->dataPtr->controller_manager_);
this->dataPtr->controller_manager_->read();
this->dataPtr->controller_manager_->update();
}
}
} // namespace ignition_ros2_control
IGNITION_ADD_PLUGIN(
ignition_ros2_control::IgnitionROS2ControlPlugin,
ignition::gazebo::System,
ignition_ros2_control::IgnitionROS2ControlPlugin::ISystemConfigure,
ignition_ros2_control::IgnitionROS2ControlPlugin::ISystemPreUpdate,
ignition_ros2_control::IgnitionROS2ControlPlugin::ISystemPostUpdate)
IGNITION_ADD_PLUGIN_ALIAS(
ignition_ros2_control::IgnitionROS2ControlPlugin,
"ignition_ros2_control::IgnitionROS2ControlPlugin")