-
Notifications
You must be signed in to change notification settings - Fork 72
/
ign_system.cpp
777 lines (671 loc) · 29.7 KB
/
ign_system.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
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
// 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 "ign_ros2_control/ign_system.hpp"
#include <ignition/msgs/imu.pb.h>
#include <limits>
#include <map>
#include <memory>
#include <string>
#include <utility>
#include <vector>
#include <ignition/gazebo/components/AngularVelocity.hh>
#include <ignition/gazebo/components/Imu.hh>
#include <ignition/gazebo/components/JointForce.hh>
#include <ignition/gazebo/components/JointForceCmd.hh>
#include <ignition/gazebo/components/JointPosition.hh>
#include <ignition/gazebo/components/JointPositionReset.hh>
#include <ignition/gazebo/components/JointVelocity.hh>
#include <ignition/gazebo/components/JointVelocityCmd.hh>
#include <ignition/gazebo/components/JointVelocityReset.hh>
#include <ignition/gazebo/components/LinearAcceleration.hh>
#include <ignition/gazebo/components/Name.hh>
#include <ignition/gazebo/components/ParentEntity.hh>
#include <ignition/gazebo/components/Pose.hh>
#include <ignition/gazebo/components/Sensor.hh>
#include <ignition/transport/Node.hh>
#include <hardware_interface/hardware_info.hpp>
struct jointData
{
/// \brief Joint's names.
std::string name;
/// \brief Current joint position
double joint_position;
/// \brief Current joint velocity
double joint_velocity;
/// \brief Current joint effort
double joint_effort;
/// \brief Current cmd joint position
double joint_position_cmd;
/// \brief Current cmd joint velocity
double joint_velocity_cmd;
/// \brief Current cmd joint effort
double joint_effort_cmd;
/// \brief flag if joint is actuated (has command interfaces) or passive
bool is_actuated;
/// \brief handles to the joints from within Gazebo
ignition::gazebo::Entity sim_joint;
/// \brief Control method defined in the URDF for each joint.
ign_ros2_control::IgnitionSystemInterface::ControlMethod joint_control_method;
};
struct MimicJoint
{
std::size_t joint_index;
std::size_t mimicked_joint_index;
double multiplier = 1.0;
std::vector<std::string> interfaces_to_mimic;
};
class ImuData
{
public:
/// \brief imu's name.
std::string name{};
/// \brief imu's topic name.
std::string topicName{};
/// \brief handles to the imu from within Gazebo
ignition::gazebo::Entity sim_imu_sensors_ = ignition::gazebo::kNullEntity;
/// \brief An array per IMU with 4 orientation, 3 angular velocity and 3 linear acceleration
std::array<double, 10> imu_sensor_data_;
/// \brief callback to get the IMU topic values
void OnIMU(const ignition::msgs::IMU & _msg);
};
void ImuData::OnIMU(const ignition::msgs::IMU & _msg)
{
this->imu_sensor_data_[0] = _msg.orientation().x();
this->imu_sensor_data_[1] = _msg.orientation().y();
this->imu_sensor_data_[2] = _msg.orientation().z();
this->imu_sensor_data_[3] = _msg.orientation().w();
this->imu_sensor_data_[4] = _msg.angular_velocity().x();
this->imu_sensor_data_[5] = _msg.angular_velocity().y();
this->imu_sensor_data_[6] = _msg.angular_velocity().z();
this->imu_sensor_data_[7] = _msg.linear_acceleration().x();
this->imu_sensor_data_[8] = _msg.linear_acceleration().y();
this->imu_sensor_data_[9] = _msg.linear_acceleration().z();
}
class ign_ros2_control::IgnitionSystemPrivate
{
public:
IgnitionSystemPrivate() = default;
~IgnitionSystemPrivate() = default;
/// \brief Degrees od freedom.
size_t n_dof_;
/// \brief last time the write method was called.
rclcpp::Time last_update_sim_time_ros_;
/// \brief vector with the joint's names.
std::vector<struct jointData> joints_;
/// \brief vector with the imus .
std::vector<std::shared_ptr<ImuData>> imus_;
/// \brief state interfaces that will be exported to the Resource Manager
std::vector<hardware_interface::StateInterface> state_interfaces_;
/// \brief command interfaces that will be exported to the Resource Manager
std::vector<hardware_interface::CommandInterface> command_interfaces_;
/// \brief Entity component manager, ECM shouldn't be accessed outside those
/// methods, otherwise the app will crash
ignition::gazebo::EntityComponentManager * ecm;
/// \brief controller update rate
int * update_rate;
/// \brief Ignition communication node.
ignition::transport::Node node;
/// \brief mapping of mimicked joints to index of joint they mimic
std::vector<MimicJoint> mimic_joints_;
/// \brief Gain which converts position error to a velocity command
double position_proportional_gain_;
};
namespace ign_ros2_control
{
bool IgnitionSystem::initSim(
rclcpp::Node::SharedPtr & model_nh,
std::map<std::string, ignition::gazebo::Entity> & enableJoints,
const hardware_interface::HardwareInfo & hardware_info,
ignition::gazebo::EntityComponentManager & _ecm,
int & update_rate)
{
this->dataPtr = std::make_unique<IgnitionSystemPrivate>();
this->dataPtr->last_update_sim_time_ros_ = rclcpp::Time();
this->nh_ = model_nh;
this->dataPtr->ecm = &_ecm;
this->dataPtr->n_dof_ = hardware_info.joints.size();
this->dataPtr->update_rate = &update_rate;
RCLCPP_DEBUG(this->nh_->get_logger(), "n_dof_ %lu", this->dataPtr->n_dof_);
this->dataPtr->joints_.resize(this->dataPtr->n_dof_);
constexpr double default_gain = 0.1;
try {
this->dataPtr->position_proportional_gain_ = this->nh_->declare_parameter<double>(
"position_proportional_gain", default_gain);
} catch (rclcpp::exceptions::ParameterAlreadyDeclaredException & ex) {
this->nh_->get_parameter(
"position_proportional_gain", this->dataPtr->position_proportional_gain_);
}
RCLCPP_INFO_STREAM(
this->nh_->get_logger(),
"The position_proportional_gain has been set to: " <<
this->dataPtr->position_proportional_gain_);
if (this->dataPtr->n_dof_ == 0) {
RCLCPP_ERROR_STREAM(this->nh_->get_logger(), "There is no joint available");
return false;
}
for (unsigned int j = 0; j < this->dataPtr->n_dof_; j++) {
auto & joint_info = hardware_info.joints[j];
std::string joint_name = this->dataPtr->joints_[j].name = joint_info.name;
auto it = enableJoints.find(joint_name);
if (it == enableJoints.end()) {
RCLCPP_WARN_STREAM(
this->nh_->get_logger(), "Skipping joint in the URDF named '" << joint_name <<
"' which is not in the gazebo model.");
continue;
}
ignition::gazebo::Entity simjoint = enableJoints[joint_name];
this->dataPtr->joints_[j].sim_joint = simjoint;
// Create joint position component if one doesn't exist
if (!_ecm.EntityHasComponentType(
simjoint,
ignition::gazebo::components::JointPosition().TypeId()))
{
_ecm.CreateComponent(simjoint, ignition::gazebo::components::JointPosition());
}
// Create joint velocity component if one doesn't exist
if (!_ecm.EntityHasComponentType(
simjoint,
ignition::gazebo::components::JointVelocity().TypeId()))
{
_ecm.CreateComponent(simjoint, ignition::gazebo::components::JointVelocity());
}
// Create joint force component if one doesn't exist
if (!_ecm.EntityHasComponentType(
simjoint,
ignition::gazebo::components::JointForce().TypeId()))
{
_ecm.CreateComponent(simjoint, ignition::gazebo::components::JointForce());
}
// Accept this joint and continue configuration
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "Loading joint: " << joint_name);
std::string suffix = "";
// check if joint is mimicked
if (joint_info.parameters.find("mimic") != joint_info.parameters.end()) {
const auto mimicked_joint = joint_info.parameters.at("mimic");
const auto mimicked_joint_it = std::find_if(
hardware_info.joints.begin(), hardware_info.joints.end(),
[&mimicked_joint](const hardware_interface::ComponentInfo & info) {
return info.name == mimicked_joint;
});
if (mimicked_joint_it == hardware_info.joints.end()) {
throw std::runtime_error(
std::string("Mimicked joint '") + mimicked_joint + "' not found");
}
MimicJoint mimic_joint;
mimic_joint.joint_index = j;
mimic_joint.mimicked_joint_index = std::distance(
hardware_info.joints.begin(), mimicked_joint_it);
auto param_it = joint_info.parameters.find("multiplier");
if (param_it != joint_info.parameters.end()) {
mimic_joint.multiplier = std::stod(joint_info.parameters.at("multiplier"));
} else {
mimic_joint.multiplier = 1.0;
}
// check joint info of mimicked joint
auto & joint_info_mimicked = hardware_info.joints[mimic_joint.mimicked_joint_index];
const auto state_mimicked_interface = std::find_if(
joint_info_mimicked.state_interfaces.begin(), joint_info_mimicked.state_interfaces.end(),
[&mimic_joint](const hardware_interface::InterfaceInfo & interface_info) {
bool pos = interface_info.name == "position";
if (pos) {mimic_joint.interfaces_to_mimic.push_back(hardware_interface::HW_IF_POSITION);}
bool vel = interface_info.name == "velocity";
if (vel) {mimic_joint.interfaces_to_mimic.push_back(hardware_interface::HW_IF_VELOCITY);}
bool eff = interface_info.name == "effort";
if (vel) {mimic_joint.interfaces_to_mimic.push_back(hardware_interface::HW_IF_EFFORT);}
return pos || vel || eff;
});
if (state_mimicked_interface == joint_info_mimicked.state_interfaces.end()) {
throw std::runtime_error(
std::string(
"For mimic joint '") + joint_info.name +
"' no state interface was found in mimicked joint '" + mimicked_joint +
" ' to mimic");
}
RCLCPP_INFO_STREAM(
this->nh_->get_logger(),
"Joint '" << joint_name << "'is mimicking joint '"
<< mimicked_joint << "' with multiplier: "
<< mimic_joint.multiplier);
this->dataPtr->mimic_joints_.push_back(mimic_joint);
suffix = "_mimic";
}
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\tState:");
auto get_initial_value =
[this, joint_name](const hardware_interface::InterfaceInfo & interface_info) {
double initial_value{0.0};
if (!interface_info.initial_value.empty()) {
try {
initial_value = std::stod(interface_info.initial_value);
RCLCPP_INFO(this->nh_->get_logger(), "\t\t\t found initial value: %f", initial_value);
} catch (std::invalid_argument &) {
RCLCPP_ERROR_STREAM(
this->nh_->get_logger(),
"Failed converting initial_value string to real number for the joint "
<< joint_name
<< " and state interface " << interface_info.name
<< ". Actual value of parameter: " << interface_info.initial_value
<< ". Initial value will be set to 0.0");
throw std::invalid_argument("Failed converting initial_value string");
}
}
return initial_value;
};
double initial_position = std::numeric_limits<double>::quiet_NaN();
double initial_velocity = std::numeric_limits<double>::quiet_NaN();
double initial_effort = std::numeric_limits<double>::quiet_NaN();
// register the state handles
for (unsigned int i = 0; i < joint_info.state_interfaces.size(); ++i) {
if (joint_info.state_interfaces[i].name == "position") {
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t position");
this->dataPtr->state_interfaces_.emplace_back(
joint_name + suffix,
hardware_interface::HW_IF_POSITION,
&this->dataPtr->joints_[j].joint_position);
initial_position = get_initial_value(joint_info.state_interfaces[i]);
this->dataPtr->joints_[j].joint_position = initial_position;
}
if (joint_info.state_interfaces[i].name == "velocity") {
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t velocity");
this->dataPtr->state_interfaces_.emplace_back(
joint_name + suffix,
hardware_interface::HW_IF_VELOCITY,
&this->dataPtr->joints_[j].joint_velocity);
initial_velocity = get_initial_value(joint_info.state_interfaces[i]);
this->dataPtr->joints_[j].joint_velocity = initial_velocity;
}
if (joint_info.state_interfaces[i].name == "effort") {
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t effort");
this->dataPtr->state_interfaces_.emplace_back(
joint_name + suffix,
hardware_interface::HW_IF_EFFORT,
&this->dataPtr->joints_[j].joint_effort);
initial_effort = get_initial_value(joint_info.state_interfaces[i]);
this->dataPtr->joints_[j].joint_effort = initial_effort;
}
}
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\tCommand:");
// register the command handles
for (unsigned int i = 0; i < joint_info.command_interfaces.size(); ++i) {
if (joint_info.command_interfaces[i].name == "position") {
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t position");
this->dataPtr->command_interfaces_.emplace_back(
joint_name + suffix,
hardware_interface::HW_IF_POSITION,
&this->dataPtr->joints_[j].joint_position_cmd);
if (!std::isnan(initial_position)) {
this->dataPtr->joints_[j].joint_position_cmd = initial_position;
}
} else if (joint_info.command_interfaces[i].name == "velocity") {
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t velocity");
this->dataPtr->command_interfaces_.emplace_back(
joint_name + suffix,
hardware_interface::HW_IF_VELOCITY,
&this->dataPtr->joints_[j].joint_velocity_cmd);
if (!std::isnan(initial_velocity)) {
this->dataPtr->joints_[j].joint_velocity_cmd = initial_velocity;
}
} else if (joint_info.command_interfaces[i].name == "effort") {
this->dataPtr->joints_[j].joint_control_method |= EFFORT;
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t effort");
this->dataPtr->command_interfaces_.emplace_back(
joint_name + suffix,
hardware_interface::HW_IF_EFFORT,
&this->dataPtr->joints_[j].joint_effort_cmd);
if (!std::isnan(initial_effort)) {
this->dataPtr->joints_[j].joint_effort_cmd = initial_effort;
}
}
// independently of existence of command interface set initial value if defined
if (!std::isnan(initial_position)) {
this->dataPtr->joints_[j].joint_position = initial_position;
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[j].sim_joint,
ignition::gazebo::components::JointPositionReset({initial_position}));
}
if (!std::isnan(initial_velocity)) {
this->dataPtr->joints_[j].joint_velocity = initial_velocity;
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[j].sim_joint,
ignition::gazebo::components::JointVelocityReset({initial_velocity}));
}
}
// check if joint is actuated (has command interfaces) or passive
this->dataPtr->joints_[j].is_actuated = (joint_info.command_interfaces.size() > 0);
}
registerSensors(hardware_info);
return true;
}
void IgnitionSystem::registerSensors(
const hardware_interface::HardwareInfo & hardware_info)
{
// Collect gazebo sensor handles
size_t n_sensors = hardware_info.sensors.size();
std::vector<hardware_interface::ComponentInfo> sensor_components_;
for (unsigned int j = 0; j < n_sensors; j++) {
hardware_interface::ComponentInfo component = hardware_info.sensors[j];
sensor_components_.push_back(component);
}
// This is split in two steps: Count the number and type of sensor and associate the interfaces
// So we have resize only once the structures where the data will be stored, and we can safely
// use pointers to the structures
this->dataPtr->ecm->Each<ignition::gazebo::components::Imu,
ignition::gazebo::components::Name>(
[&](const ignition::gazebo::Entity & _entity,
const ignition::gazebo::components::Imu *,
const ignition::gazebo::components::Name * _name) -> bool
{
auto imuData = std::make_shared<ImuData>();
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "Loading sensor: " << _name->Data());
auto sensorTopicComp = this->dataPtr->ecm->Component<
ignition::gazebo::components::SensorTopic>(_entity);
if (sensorTopicComp) {
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "Topic name: " << sensorTopicComp->Data());
}
RCLCPP_INFO_STREAM(
this->nh_->get_logger(), "\tState:");
imuData->name = _name->Data();
imuData->sim_imu_sensors_ = _entity;
hardware_interface::ComponentInfo component;
for (auto & comp : sensor_components_) {
if (comp.name == _name->Data()) {
component = comp;
}
}
static const std::map<std::string, size_t> interface_name_map = {
{"orientation.x", 0},
{"orientation.y", 1},
{"orientation.z", 2},
{"orientation.w", 3},
{"angular_velocity.x", 4},
{"angular_velocity.y", 5},
{"angular_velocity.z", 6},
{"linear_acceleration.x", 7},
{"linear_acceleration.y", 8},
{"linear_acceleration.z", 9},
};
for (const auto & state_interface : component.state_interfaces) {
RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t " << state_interface.name);
size_t data_index = interface_name_map.at(state_interface.name);
this->dataPtr->state_interfaces_.emplace_back(
imuData->name,
state_interface.name,
&imuData->imu_sensor_data_[data_index]);
}
this->dataPtr->imus_.push_back(imuData);
return true;
});
}
CallbackReturn
IgnitionSystem::on_init(const hardware_interface::HardwareInfo & system_info)
{
RCLCPP_WARN(this->nh_->get_logger(), "On init...");
if (hardware_interface::SystemInterface::on_init(system_info) != CallbackReturn::SUCCESS) {
return CallbackReturn::ERROR;
}
return CallbackReturn::SUCCESS;
}
CallbackReturn IgnitionSystem::on_configure(
const rclcpp_lifecycle::State & /*previous_state*/)
{
RCLCPP_INFO(
this->nh_->get_logger(), "System Successfully configured!");
return CallbackReturn::SUCCESS;
}
std::vector<hardware_interface::StateInterface>
IgnitionSystem::export_state_interfaces()
{
return std::move(this->dataPtr->state_interfaces_);
}
std::vector<hardware_interface::CommandInterface>
IgnitionSystem::export_command_interfaces()
{
return std::move(this->dataPtr->command_interfaces_);
}
CallbackReturn IgnitionSystem::on_activate(const rclcpp_lifecycle::State & previous_state)
{
return CallbackReturn::SUCCESS;
return hardware_interface::SystemInterface::on_activate(previous_state);
}
CallbackReturn IgnitionSystem::on_deactivate(const rclcpp_lifecycle::State & previous_state)
{
return CallbackReturn::SUCCESS;
return hardware_interface::SystemInterface::on_deactivate(previous_state);
}
hardware_interface::return_type IgnitionSystem::read(
const rclcpp::Time & /*time*/,
const rclcpp::Duration & /*period*/)
{
for (unsigned int i = 0; i < this->dataPtr->joints_.size(); ++i) {
if (this->dataPtr->joints_[i].sim_joint == ignition::gazebo::v6::kNullEntity) {
continue;
}
// Get the joint velocity
const auto * jointVelocity =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocity>(
this->dataPtr->joints_[i].sim_joint);
// TODO(ahcorde): Revisit this part ignitionrobotics/ign-physics#124
// Get the joint force
// const auto * jointForce =
// _ecm.Component<ignition::gazebo::components::JointForce>(
// this->dataPtr->sim_joints_[j]);
// Get the joint position
const auto * jointPositions =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointPosition>(
this->dataPtr->joints_[i].sim_joint);
this->dataPtr->joints_[i].joint_position = jointPositions->Data()[0];
this->dataPtr->joints_[i].joint_velocity = jointVelocity->Data()[0];
// this->dataPtr->joint_effort_[j] = jointForce->Data()[0];
}
for (unsigned int i = 0; i < this->dataPtr->imus_.size(); ++i) {
if (this->dataPtr->imus_[i]->topicName.empty()) {
auto sensorTopicComp = this->dataPtr->ecm->Component<
ignition::gazebo::components::SensorTopic>(this->dataPtr->imus_[i]->sim_imu_sensors_);
if (sensorTopicComp) {
this->dataPtr->imus_[i]->topicName = sensorTopicComp->Data();
RCLCPP_INFO_STREAM(
this->nh_->get_logger(), "IMU " << this->dataPtr->imus_[i]->name <<
" has a topic name: " << sensorTopicComp->Data());
this->dataPtr->node.Subscribe(
this->dataPtr->imus_[i]->topicName, &ImuData::OnIMU,
this->dataPtr->imus_[i].get());
}
}
}
return hardware_interface::return_type::OK;
}
hardware_interface::return_type
IgnitionSystem::perform_command_mode_switch(
const std::vector<std::string> & start_interfaces,
const std::vector<std::string> & stop_interfaces)
{
for (unsigned int j = 0; j < this->dataPtr->joints_.size(); j++) {
for (const std::string & interface_name : stop_interfaces) {
// Clear joint control method bits corresponding to stop interfaces
if (interface_name == (this->dataPtr->joints_[j].name + "/" +
hardware_interface::HW_IF_POSITION))
{
this->dataPtr->joints_[j].joint_control_method &=
static_cast<ControlMethod_>(VELOCITY & EFFORT);
} else if (interface_name == (this->dataPtr->joints_[j].name + "/" + // NOLINT
hardware_interface::HW_IF_VELOCITY))
{
this->dataPtr->joints_[j].joint_control_method &=
static_cast<ControlMethod_>(POSITION & EFFORT);
} else if (interface_name == (this->dataPtr->joints_[j].name + "/" + // NOLINT
hardware_interface::HW_IF_EFFORT))
{
this->dataPtr->joints_[j].joint_control_method &=
static_cast<ControlMethod_>(POSITION & VELOCITY);
}
}
// Set joint control method bits corresponding to start interfaces
for (const std::string & interface_name : start_interfaces) {
if (interface_name == (this->dataPtr->joints_[j].name + "/" +
hardware_interface::HW_IF_POSITION))
{
this->dataPtr->joints_[j].joint_control_method |= POSITION;
} else if (interface_name == (this->dataPtr->joints_[j].name + "/" + // NOLINT
hardware_interface::HW_IF_VELOCITY))
{
this->dataPtr->joints_[j].joint_control_method |= VELOCITY;
} else if (interface_name == (this->dataPtr->joints_[j].name + "/" + // NOLINT
hardware_interface::HW_IF_EFFORT))
{
this->dataPtr->joints_[j].joint_control_method |= EFFORT;
}
}
}
return hardware_interface::return_type::OK;
}
hardware_interface::return_type IgnitionSystem::write(
const rclcpp::Time & /*time*/,
const rclcpp::Duration & /*period*/)
{
for (unsigned int i = 0; i < this->dataPtr->joints_.size(); ++i) {
if (this->dataPtr->joints_[i].sim_joint == ignition::gazebo::v6::kNullEntity) {
continue;
}
if (this->dataPtr->joints_[i].joint_control_method & VELOCITY) {
if (!this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocityCmd>(
this->dataPtr->joints_[i].sim_joint))
{
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[i].sim_joint,
ignition::gazebo::components::JointVelocityCmd({0}));
} else {
const auto jointVelCmd =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocityCmd>(
this->dataPtr->joints_[i].sim_joint);
*jointVelCmd = ignition::gazebo::components::JointVelocityCmd(
{this->dataPtr->joints_[i].joint_velocity_cmd});
}
} else if (this->dataPtr->joints_[i].joint_control_method & POSITION) {
// Get error in position
double error;
error = (this->dataPtr->joints_[i].joint_position -
this->dataPtr->joints_[i].joint_position_cmd) * *this->dataPtr->update_rate;
// Calculate target velcity
double target_vel = -this->dataPtr->position_proportional_gain_ * error;
auto vel =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocityCmd>(
this->dataPtr->joints_[i].sim_joint);
if (vel == nullptr) {
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[i].sim_joint,
ignition::gazebo::components::JointVelocityCmd({target_vel}));
} else if (!vel->Data().empty()) {
vel->Data()[0] = target_vel;
}
} else if (this->dataPtr->joints_[i].joint_control_method & EFFORT) {
if (!this->dataPtr->ecm->Component<ignition::gazebo::components::JointForceCmd>(
this->dataPtr->joints_[i].sim_joint))
{
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[i].sim_joint,
ignition::gazebo::components::JointForceCmd({0}));
} else {
const auto jointEffortCmd =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointForceCmd>(
this->dataPtr->joints_[i].sim_joint);
*jointEffortCmd = ignition::gazebo::components::JointForceCmd(
{this->dataPtr->joints_[i].joint_effort_cmd});
}
} else if (this->dataPtr->joints_[i].is_actuated) {
// Fallback case is a velocity command of zero (only for actuated joints)
double target_vel = 0.0;
auto vel =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocityCmd>(
this->dataPtr->joints_[i].sim_joint);
if (vel == nullptr) {
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[i].sim_joint,
ignition::gazebo::components::JointVelocityCmd({target_vel}));
} else if (!vel->Data().empty()) {
vel->Data()[0] = target_vel;
}
}
}
// set values of all mimic joints with respect to mimicked joint
for (const auto & mimic_joint : this->dataPtr->mimic_joints_) {
for (const auto & mimic_interface : mimic_joint.interfaces_to_mimic) {
if (mimic_interface == "position") {
// Get the joint position
double position_mimicked_joint =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointPosition>(
this->dataPtr->joints_[mimic_joint.mimicked_joint_index].sim_joint)->Data()[0];
double position_mimic_joint =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointPosition>(
this->dataPtr->joints_[mimic_joint.joint_index].sim_joint)->Data()[0];
double position_error =
position_mimic_joint - position_mimicked_joint * mimic_joint.multiplier;
double velocity_sp = (-1.0) * position_error * (*this->dataPtr->update_rate);
auto vel =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocityCmd>(
this->dataPtr->joints_[mimic_joint.joint_index].sim_joint);
if (vel == nullptr) {
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[mimic_joint.joint_index].sim_joint,
ignition::gazebo::components::JointVelocityCmd({velocity_sp}));
} else if (!vel->Data().empty()) {
vel->Data()[0] = velocity_sp;
}
}
if (mimic_interface == "velocity") {
// get the velocity of mimicked joint
double velocity_mimicked_joint =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocity>(
this->dataPtr->joints_[mimic_joint.mimicked_joint_index].sim_joint)->Data()[0];
if (!this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocityCmd>(
this->dataPtr->joints_[mimic_joint.joint_index].sim_joint))
{
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[mimic_joint.joint_index].sim_joint,
ignition::gazebo::components::JointVelocityCmd({0}));
} else {
const auto jointVelCmd =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointVelocityCmd>(
this->dataPtr->joints_[mimic_joint.joint_index].sim_joint);
*jointVelCmd = ignition::gazebo::components::JointVelocityCmd(
{mimic_joint.multiplier * velocity_mimicked_joint});
}
}
if (mimic_interface == "effort") {
// TODO(ahcorde): Revisit this part ignitionrobotics/ign-physics#124
// Get the joint force
// const auto * jointForce =
// _ecm.Component<ignition::gazebo::components::JointForce>(
// this->dataPtr->sim_joints_[j]);
if (!this->dataPtr->ecm->Component<ignition::gazebo::components::JointForceCmd>(
this->dataPtr->joints_[mimic_joint.joint_index].sim_joint))
{
this->dataPtr->ecm->CreateComponent(
this->dataPtr->joints_[mimic_joint.joint_index].sim_joint,
ignition::gazebo::components::JointForceCmd({0}));
} else {
const auto jointEffortCmd =
this->dataPtr->ecm->Component<ignition::gazebo::components::JointForceCmd>(
this->dataPtr->joints_[mimic_joint.joint_index].sim_joint);
*jointEffortCmd = ignition::gazebo::components::JointForceCmd(
{mimic_joint.multiplier *
this->dataPtr->joints_[mimic_joint.mimicked_joint_index].joint_effort});
}
}
}
}
return hardware_interface::return_type::OK;
}
} // namespace ign_ros2_control
#include "pluginlib/class_list_macros.hpp" // NOLINT
PLUGINLIB_EXPORT_CLASS(
ign_ros2_control::IgnitionSystem, ign_ros2_control::IgnitionSystemInterface)