-
Notifications
You must be signed in to change notification settings - Fork 324
/
joint_trajectory_controller.cpp
1447 lines (1301 loc) · 48.6 KB
/
joint_trajectory_controller.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
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// Copyright (c) 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_trajectory_controller/joint_trajectory_controller.hpp"
#include <stddef.h>
#include <chrono>
#include <functional>
#include <memory>
#include <ostream>
#include <ratio>
#include <string>
#include <vector>
#include "angles/angles.h"
#include "builtin_interfaces/msg/duration.hpp"
#include "builtin_interfaces/msg/time.hpp"
#include "controller_interface/helpers.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "joint_trajectory_controller/trajectory.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/event_handler.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp_action/create_server.hpp"
#include "rclcpp_action/server_goal_handle.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp_lifecycle/state.hpp"
#include "std_msgs/msg/header.hpp"
namespace joint_trajectory_controller
{
JointTrajectoryController::JointTrajectoryController()
: controller_interface::ControllerInterface(), dof_(0)
{
}
controller_interface::CallbackReturn JointTrajectoryController::on_init()
{
try
{
// Create the parameter listener and get the parameters
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
JointTrajectoryController::command_interface_configuration() const
{
controller_interface::InterfaceConfiguration conf;
conf.type = controller_interface::interface_configuration_type::INDIVIDUAL;
if (dof_ == 0)
{
fprintf(
stderr,
"During ros2_control interface configuration, degrees of freedom is not valid;"
" it should be positive. Actual DOF is %zu\n",
dof_);
std::exit(EXIT_FAILURE);
}
conf.names.reserve(dof_ * params_.command_interfaces.size());
for (const auto & joint_name : command_joint_names_)
{
for (const auto & interface_type : params_.command_interfaces)
{
conf.names.push_back(joint_name + "/" + interface_type);
}
}
return conf;
}
controller_interface::InterfaceConfiguration
JointTrajectoryController::state_interface_configuration() const
{
controller_interface::InterfaceConfiguration conf;
conf.type = controller_interface::interface_configuration_type::INDIVIDUAL;
conf.names.reserve(dof_ * params_.state_interfaces.size());
for (const auto & joint_name : params_.joints)
{
for (const auto & interface_type : params_.state_interfaces)
{
conf.names.push_back(joint_name + "/" + interface_type);
}
}
return conf;
}
controller_interface::return_type JointTrajectoryController::update(
const rclcpp::Time & time, const rclcpp::Duration & period)
{
if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
{
return controller_interface::return_type::OK;
}
auto compute_error_for_joint = [&](
JointTrajectoryPoint & error, size_t index,
const JointTrajectoryPoint & current,
const JointTrajectoryPoint & desired)
{
// error defined as the difference between current and desired
if (normalize_joint_error_[index])
{
// if desired, the shortest_angular_distance is calculated, i.e., the error is
// normalized between -pi<error<pi
error.positions[index] =
angles::shortest_angular_distance(current.positions[index], desired.positions[index]);
}
else
{
error.positions[index] = desired.positions[index] - current.positions[index];
}
if (has_velocity_state_interface_ && has_velocity_command_interface_)
{
error.velocities[index] = desired.velocities[index] - current.velocities[index];
}
if (has_acceleration_state_interface_ && has_acceleration_command_interface_)
{
error.accelerations[index] = desired.accelerations[index] - current.accelerations[index];
}
};
// Check if a new external message has been received from nonRT threads
auto current_external_msg = traj_external_point_ptr_->get_trajectory_msg();
auto new_external_msg = traj_msg_external_point_ptr_.readFromRT();
if (current_external_msg != *new_external_msg)
{
fill_partial_goal(*new_external_msg);
sort_to_local_joint_order(*new_external_msg);
// TODO(denis): Add here integration of position and velocity
traj_external_point_ptr_->update(*new_external_msg);
// set the active trajectory pointer to the new goal
traj_point_active_ptr_ = &traj_external_point_ptr_;
}
// TODO(anyone): can I here also use const on joint_interface since the reference_wrapper is not
// changed, but its value only?
auto assign_interface_from_point =
[&](auto & joint_interface, const std::vector<double> & trajectory_point_interface)
{
for (size_t index = 0; index < dof_; ++index)
{
joint_interface[index].get().set_value(trajectory_point_interface[index]);
}
};
// current state update
state_current_.time_from_start.set__sec(0);
read_state_from_hardware(state_current_);
// currently carrying out a trajectory
if (traj_point_active_ptr_ && (*traj_point_active_ptr_)->has_trajectory_msg())
{
bool first_sample = false;
// if sampling the first time, set the point before you sample
if (!(*traj_point_active_ptr_)->is_sampled_already())
{
first_sample = true;
if (params_.open_loop_control)
{
(*traj_point_active_ptr_)->set_point_before_trajectory_msg(time, last_commanded_state_);
}
else
{
(*traj_point_active_ptr_)->set_point_before_trajectory_msg(time, state_current_);
}
}
// find segment for current timestamp
TrajectoryPointConstIter start_segment_itr, end_segment_itr;
const bool valid_point =
(*traj_point_active_ptr_)
->sample(time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
if (valid_point)
{
bool tolerance_violated_while_moving = false;
bool outside_goal_tolerance = false;
bool within_goal_time = true;
double time_difference = 0.0;
const bool before_last_point = end_segment_itr != (*traj_point_active_ptr_)->end();
// Check state/goal tolerance
for (size_t index = 0; index < dof_; ++index)
{
compute_error_for_joint(state_error_, index, state_current_, state_desired_);
// Always check the state tolerance on the first sample in case the first sample
// is the last point
if (
(before_last_point || first_sample) &&
!check_state_tolerance_per_joint(
state_error_, index, default_tolerances_.state_tolerance[index], false))
{
tolerance_violated_while_moving = true;
}
// past the final point, check that we end up inside goal tolerance
if (
!before_last_point &&
!check_state_tolerance_per_joint(
state_error_, index, default_tolerances_.goal_state_tolerance[index], false))
{
outside_goal_tolerance = true;
if (default_tolerances_.goal_time_tolerance != 0.0)
{
// if we exceed goal_time_tolerance set it to aborted
const rclcpp::Time traj_start = (*traj_point_active_ptr_)->get_trajectory_start_time();
const rclcpp::Time traj_end = traj_start + start_segment_itr->time_from_start;
time_difference = get_node()->now().seconds() - traj_end.seconds();
if (time_difference > default_tolerances_.goal_time_tolerance)
{
within_goal_time = false;
}
}
}
}
// set values for next hardware write() if tolerance is met
if (!tolerance_violated_while_moving && within_goal_time)
{
if (use_closed_loop_pid_adapter_)
{
// Update PIDs
for (auto i = 0ul; i < dof_; ++i)
{
tmp_command_[i] = (state_desired_.velocities[i] * ff_velocity_scale_[i]) +
pids_[i]->computeCommand(
state_error_.positions[i], state_error_.velocities[i],
(uint64_t)period.nanoseconds());
}
}
// set values for next hardware write()
if (has_position_command_interface_)
{
assign_interface_from_point(joint_command_interface_[0], state_desired_.positions);
}
if (has_velocity_command_interface_)
{
if (use_closed_loop_pid_adapter_)
{
assign_interface_from_point(joint_command_interface_[1], tmp_command_);
}
else
{
assign_interface_from_point(joint_command_interface_[1], state_desired_.velocities);
}
}
if (has_acceleration_command_interface_)
{
assign_interface_from_point(joint_command_interface_[2], state_desired_.accelerations);
}
if (has_effort_command_interface_)
{
if (use_closed_loop_pid_adapter_)
{
assign_interface_from_point(joint_command_interface_[3], tmp_command_);
}
else
{
assign_interface_from_point(joint_command_interface_[3], state_desired_.effort);
}
}
// store the previous command. Used in open-loop control mode
last_commanded_state_ = state_desired_;
}
const auto active_goal = *rt_active_goal_.readFromRT();
if (active_goal)
{
// send feedback
auto feedback = std::make_shared<FollowJTrajAction::Feedback>();
feedback->header.stamp = time;
feedback->joint_names = params_.joints;
feedback->actual = state_current_;
feedback->desired = state_desired_;
feedback->error = state_error_;
active_goal->setFeedback(feedback);
// check abort
if (tolerance_violated_while_moving)
{
set_hold_position();
auto result = std::make_shared<FollowJTrajAction::Result>();
RCLCPP_WARN(get_node()->get_logger(), "Aborted due to state tolerance violation");
result->set__error_code(FollowJTrajAction::Result::PATH_TOLERANCE_VIOLATED);
active_goal->setAborted(result);
// TODO(matthew-reynolds): Need a lock-free write here
// See https://github.com/ros-controls/ros2_controllers/issues/168
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
// remove the active trajectory pointer so that we stop commanding the hardware
traj_point_active_ptr_ = nullptr;
// check goal tolerance
}
else if (!before_last_point)
{
if (!outside_goal_tolerance)
{
auto res = std::make_shared<FollowJTrajAction::Result>();
res->set__error_code(FollowJTrajAction::Result::SUCCESSFUL);
active_goal->setSucceeded(res);
// TODO(matthew-reynolds): Need a lock-free write here
// See https://github.com/ros-controls/ros2_controllers/issues/168
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
// remove the active trajectory pointer so that we stop commanding the hardware
traj_point_active_ptr_ = nullptr;
RCLCPP_INFO(get_node()->get_logger(), "Goal reached, success!");
}
else if (!within_goal_time)
{
set_hold_position();
auto result = std::make_shared<FollowJTrajAction::Result>();
result->set__error_code(FollowJTrajAction::Result::GOAL_TOLERANCE_VIOLATED);
active_goal->setAborted(result);
// TODO(matthew-reynolds): Need a lock-free write here
// See https://github.com/ros-controls/ros2_controllers/issues/168
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
RCLCPP_WARN(
get_node()->get_logger(), "Aborted due goal_time_tolerance exceeding by %f seconds",
time_difference);
}
// else, run another cycle while waiting for outside_goal_tolerance
// to be satisfied or violated within the goal_time_tolerance
}
}
else if (tolerance_violated_while_moving)
{
set_hold_position();
RCLCPP_ERROR(get_node()->get_logger(), "Holding position due to state tolerance violation");
}
}
}
publish_state(time, state_desired_, state_current_, state_error_);
return controller_interface::return_type::OK;
}
void JointTrajectoryController::read_state_from_hardware(JointTrajectoryPoint & state)
{
auto assign_point_from_interface =
[&](std::vector<double> & trajectory_point_interface, const auto & joint_interface)
{
for (size_t index = 0; index < dof_; ++index)
{
trajectory_point_interface[index] = joint_interface[index].get().get_value();
}
};
// Assign values from the hardware
// Position states always exist
assign_point_from_interface(state.positions, joint_state_interface_[0]);
// velocity and acceleration states are optional
if (has_velocity_state_interface_)
{
assign_point_from_interface(state.velocities, joint_state_interface_[1]);
// Acceleration is used only in combination with velocity
if (has_acceleration_state_interface_)
{
assign_point_from_interface(state.accelerations, joint_state_interface_[2]);
}
else
{
// Make empty so the property is ignored during interpolation
state.accelerations.clear();
}
}
else
{
// Make empty so the property is ignored during interpolation
state.velocities.clear();
state.accelerations.clear();
}
}
bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajectoryPoint & state)
{
bool has_values = true;
auto assign_point_from_interface =
[&](std::vector<double> & trajectory_point_interface, const auto & joint_interface)
{
for (size_t index = 0; index < dof_; ++index)
{
trajectory_point_interface[index] = joint_interface[index].get().get_value();
}
};
auto interface_has_values = [](const auto & joint_interface)
{
return std::find_if(
joint_interface.begin(), joint_interface.end(),
[](const auto & interface)
{ return std::isnan(interface.get().get_value()); }) == joint_interface.end();
};
// Assign values from the command interfaces as state. Therefore needs check for both.
// Position state interface has to exist always
if (has_position_command_interface_ && interface_has_values(joint_command_interface_[0]))
{
assign_point_from_interface(state.positions, joint_command_interface_[0]);
}
else
{
state.positions.clear();
has_values = false;
}
// velocity and acceleration states are optional
if (has_velocity_state_interface_)
{
if (has_velocity_command_interface_ && interface_has_values(joint_command_interface_[1]))
{
assign_point_from_interface(state.velocities, joint_command_interface_[1]);
}
else
{
state.velocities.clear();
has_values = false;
}
}
else
{
state.velocities.clear();
}
// Acceleration is used only in combination with velocity
if (has_acceleration_state_interface_)
{
if (has_acceleration_command_interface_ && interface_has_values(joint_command_interface_[2]))
{
assign_point_from_interface(state.accelerations, joint_command_interface_[2]);
}
else
{
state.accelerations.clear();
has_values = false;
}
}
else
{
state.accelerations.clear();
}
return has_values;
}
bool JointTrajectoryController::read_commands_from_command_interfaces(
JointTrajectoryPoint & commands)
{
bool has_values = true;
auto assign_point_from_interface =
[&](std::vector<double> & trajectory_point_interface, const auto & joint_interface)
{
for (size_t index = 0; index < dof_; ++index)
{
trajectory_point_interface[index] = joint_interface[index].get().get_value();
}
};
auto interface_has_values = [](const auto & joint_interface)
{
return std::find_if(
joint_interface.begin(), joint_interface.end(),
[](const auto & interface)
{ return std::isnan(interface.get().get_value()); }) == joint_interface.end();
};
// Assign values from the command interfaces as command.
if (has_position_command_interface_)
{
if (interface_has_values(joint_command_interface_[0]))
{
assign_point_from_interface(commands.positions, joint_command_interface_[0]);
}
else
{
commands.positions.clear();
has_values = false;
}
}
if (has_velocity_command_interface_)
{
if (interface_has_values(joint_command_interface_[1]))
{
assign_point_from_interface(commands.velocities, joint_command_interface_[1]);
}
else
{
commands.velocities.clear();
has_values = false;
}
}
if (has_acceleration_command_interface_)
{
if (interface_has_values(joint_command_interface_[2]))
{
assign_point_from_interface(commands.accelerations, joint_command_interface_[2]);
}
else
{
commands.accelerations.clear();
has_values = false;
}
}
if (has_effort_command_interface_)
{
if (interface_has_values(joint_command_interface_[3]))
{
assign_point_from_interface(commands.effort, joint_command_interface_[3]);
}
else
{
commands.effort.clear();
has_values = false;
}
}
return has_values;
}
void JointTrajectoryController::query_state_service(
const std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Request> request,
std::shared_ptr<control_msgs::srv::QueryTrajectoryState::Response> response)
{
const auto logger = get_node()->get_logger();
// Preconditions
if (get_state().id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
RCLCPP_ERROR(logger, "Can't sample trajectory. Controller is not active.");
response->success = false;
return;
}
const auto active_goal = *rt_active_goal_.readFromRT();
response->name = params_.joints;
trajectory_msgs::msg::JointTrajectoryPoint state_requested = state_current_;
if ((traj_point_active_ptr_ && (*traj_point_active_ptr_)->has_trajectory_msg()))
{
TrajectoryPointConstIter start_segment_itr, end_segment_itr;
response->success = (*traj_point_active_ptr_)
->sample(
static_cast<rclcpp::Time>(request->time), interpolation_method_,
state_requested, start_segment_itr, end_segment_itr);
// If the requested sample time precedes the trajectory finish time respond as failure
if (response->success)
{
if (end_segment_itr == (*traj_point_active_ptr_)->end())
{
RCLCPP_ERROR(logger, "Requested sample time precedes the current trajectory end time.");
response->success = false;
}
}
else
{
RCLCPP_ERROR(
logger, "Requested sample time is earlier than the current trajectory start time.");
}
}
else
{
RCLCPP_ERROR(logger, "Currently there is no valid trajectory instance.");
response->success = false;
}
response->position = state_requested.positions;
response->velocity = state_requested.velocities;
response->acceleration = state_requested.accelerations;
}
controller_interface::CallbackReturn JointTrajectoryController::on_configure(
const rclcpp_lifecycle::State &)
{
const auto logger = get_node()->get_logger();
if (!param_listener_)
{
RCLCPP_ERROR(get_node()->get_logger(), "Error encountered during init");
return controller_interface::CallbackReturn::ERROR;
}
// update the dynamic map parameters
param_listener_->refresh_dynamic_parameters();
// get parameters from the listener in case they were updated
params_ = param_listener_->get_params();
// Check if the DoF has changed
if ((dof_ > 0) && (params_.joints.size() != dof_))
{
RCLCPP_ERROR(
logger,
"The JointTrajectoryController does not support restarting with a different number of DOF");
// TODO(andyz): update vector lengths if num. joints did change and re-initialize them so we
// can continue
return CallbackReturn::FAILURE;
}
dof_ = params_.joints.size();
// TODO(destogl): why is this here? Add comment or move
if (!reset())
{
return CallbackReturn::FAILURE;
}
if (params_.joints.empty())
{
// TODO(destogl): is this correct? Can we really move-on if no joint names are not provided?
RCLCPP_WARN(logger, "'joints' parameter is empty.");
}
command_joint_names_ = params_.command_joints;
if (command_joint_names_.empty())
{
command_joint_names_ = params_.joints;
RCLCPP_INFO(
logger, "No specific joint names are used for command interfaces. Using 'joints' parameter.");
}
else if (command_joint_names_.size() != params_.joints.size())
{
RCLCPP_ERROR(
logger, "'command_joints' parameter has to have the same size as 'joints' parameter.");
return CallbackReturn::FAILURE;
}
// // Specialized, child controllers set interfaces before calling configure function.
// if (command_interface_types_.empty())
// {
// command_interface_types_ = get_node()->get_parameter("command_interfaces").as_string_array();
// }
if (params_.command_interfaces.empty())
{
RCLCPP_ERROR(logger, "'command_interfaces' parameter is empty.");
return CallbackReturn::FAILURE;
}
// Check if only allowed interface types are used and initialize storage to avoid memory
// allocation during activation
joint_command_interface_.resize(allowed_interface_types_.size());
has_position_command_interface_ =
contains_interface_type(params_.command_interfaces, hardware_interface::HW_IF_POSITION);
has_velocity_command_interface_ =
contains_interface_type(params_.command_interfaces, hardware_interface::HW_IF_VELOCITY);
has_acceleration_command_interface_ =
contains_interface_type(params_.command_interfaces, hardware_interface::HW_IF_ACCELERATION);
has_effort_command_interface_ =
contains_interface_type(params_.command_interfaces, hardware_interface::HW_IF_EFFORT);
// if there is only velocity or if there is effort command interface
// then use also PID adapter
use_closed_loop_pid_adapter_ =
(has_velocity_command_interface_ && params_.command_interfaces.size() == 1 &&
!params_.open_loop_control) ||
has_effort_command_interface_;
if (use_closed_loop_pid_adapter_)
{
pids_.resize(dof_);
ff_velocity_scale_.resize(dof_);
tmp_command_.resize(dof_, 0.0);
// Init PID gains from ROS parameters
for (size_t i = 0; i < dof_; ++i)
{
const auto & gains = params_.gains.joints_map.at(params_.joints[i]);
pids_[i] = std::make_shared<control_toolbox::Pid>(
gains.p, gains.i, gains.d, gains.i_clamp, -gains.i_clamp);
ff_velocity_scale_[i] = gains.ff_velocity_scale;
}
}
// Configure joint position error normalization from ROS parameters
normalize_joint_error_.resize(dof_);
for (size_t i = 0; i < dof_; ++i)
{
const auto & gains = params_.gains.joints_map.at(params_.joints[i]);
normalize_joint_error_[i] = gains.normalize_error;
}
if (params_.state_interfaces.empty())
{
RCLCPP_ERROR(logger, "'state_interfaces' parameter is empty.");
return CallbackReturn::FAILURE;
}
// Check if only allowed interface types are used and initialize storage to avoid memory
// allocation during activation
// Note: 'effort' storage is also here, but never used. Still, for this is OK.
joint_state_interface_.resize(allowed_interface_types_.size());
has_position_state_interface_ =
contains_interface_type(params_.state_interfaces, hardware_interface::HW_IF_POSITION);
has_velocity_state_interface_ =
contains_interface_type(params_.state_interfaces, hardware_interface::HW_IF_VELOCITY);
has_acceleration_state_interface_ =
contains_interface_type(params_.state_interfaces, hardware_interface::HW_IF_ACCELERATION);
// Validation of combinations of state and velocity together have to be done
// here because the parameter validators only deal with each parameter
// separately.
if (
has_velocity_command_interface_ && params_.command_interfaces.size() == 1 &&
(!has_velocity_state_interface_ || !has_position_state_interface_))
{
RCLCPP_ERROR(
logger,
"'velocity' command interface can only be used alone if 'velocity' and "
"'position' state interfaces are present");
return CallbackReturn::FAILURE;
}
// effort is always used alone so no need for size check
if (
has_effort_command_interface_ &&
(!has_velocity_state_interface_ || !has_position_state_interface_))
{
RCLCPP_ERROR(
logger,
"'effort' command interface can only be used alone if 'velocity' and "
"'position' state interfaces are present");
return CallbackReturn::FAILURE;
}
auto get_interface_list = [](const std::vector<std::string> & interface_types)
{
std::stringstream ss_interfaces;
for (size_t index = 0; index < interface_types.size(); ++index)
{
if (index != 0)
{
ss_interfaces << " ";
}
ss_interfaces << interface_types[index];
}
return ss_interfaces.str();
};
// Print output so users can be sure the interface setup is correct
RCLCPP_INFO(
logger, "Command interfaces are [%s] and state interfaces are [%s].",
get_interface_list(params_.command_interfaces).c_str(),
get_interface_list(params_.state_interfaces).c_str());
default_tolerances_ = get_segment_tolerances(params_);
const std::string interpolation_string =
get_node()->get_parameter("interpolation_method").as_string();
interpolation_method_ = interpolation_methods::from_string(interpolation_string);
RCLCPP_INFO(
logger, "Using '%s' interpolation method.",
interpolation_methods::InterpolationMethodMap.at(interpolation_method_).c_str());
joint_command_subscriber_ =
get_node()->create_subscription<trajectory_msgs::msg::JointTrajectory>(
"~/joint_trajectory", rclcpp::SystemDefaultsQoS(),
std::bind(&JointTrajectoryController::topic_callback, this, std::placeholders::_1));
publisher_ = get_node()->create_publisher<ControllerStateMsg>(
"~/controller_state", rclcpp::SystemDefaultsQoS());
state_publisher_ = std::make_unique<StatePublisher>(publisher_);
state_publisher_->lock();
state_publisher_->msg_.joint_names = params_.joints;
state_publisher_->msg_.reference.positions.resize(dof_);
state_publisher_->msg_.reference.velocities.resize(dof_);
state_publisher_->msg_.reference.accelerations.resize(dof_);
state_publisher_->msg_.feedback.positions.resize(dof_);
state_publisher_->msg_.error.positions.resize(dof_);
if (has_velocity_state_interface_)
{
state_publisher_->msg_.feedback.velocities.resize(dof_);
state_publisher_->msg_.error.velocities.resize(dof_);
}
if (has_acceleration_state_interface_)
{
state_publisher_->msg_.feedback.accelerations.resize(dof_);
state_publisher_->msg_.error.accelerations.resize(dof_);
}
if (has_position_command_interface_)
{
state_publisher_->msg_.output.positions.resize(dof_);
}
if (has_velocity_command_interface_)
{
state_publisher_->msg_.output.velocities.resize(dof_);
}
if (has_acceleration_command_interface_)
{
state_publisher_->msg_.output.accelerations.resize(dof_);
}
if (has_effort_command_interface_)
{
state_publisher_->msg_.output.effort.resize(dof_);
}
state_publisher_->unlock();
// action server configuration
if (params_.allow_partial_joints_goal)
{
RCLCPP_INFO(logger, "Goals with partial set of joints are allowed");
}
RCLCPP_INFO(
logger, "Action status changes will be monitored at %.2f Hz.", params_.action_monitor_rate);
action_monitor_period_ = rclcpp::Duration::from_seconds(1.0 / params_.action_monitor_rate);
using namespace std::placeholders;
action_server_ = rclcpp_action::create_server<FollowJTrajAction>(
get_node()->get_node_base_interface(), get_node()->get_node_clock_interface(),
get_node()->get_node_logging_interface(), get_node()->get_node_waitables_interface(),
std::string(get_node()->get_name()) + "/follow_joint_trajectory",
std::bind(&JointTrajectoryController::goal_received_callback, this, _1, _2),
std::bind(&JointTrajectoryController::goal_cancelled_callback, this, _1),
std::bind(&JointTrajectoryController::goal_accepted_callback, this, _1));
resize_joint_trajectory_point(state_current_, dof_);
resize_joint_trajectory_point_command(command_current_, dof_);
resize_joint_trajectory_point(state_desired_, dof_);
resize_joint_trajectory_point(state_error_, dof_);
resize_joint_trajectory_point(last_commanded_state_, dof_);
query_state_srv_ = get_node()->create_service<control_msgs::srv::QueryTrajectoryState>(
std::string(get_node()->get_name()) + "/query_state",
std::bind(&JointTrajectoryController::query_state_service, this, _1, _2));
return CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn JointTrajectoryController::on_activate(
const rclcpp_lifecycle::State &)
{
// order all joints in the storage
for (const auto & interface : params_.command_interfaces)
{
auto it =
std::find(allowed_interface_types_.begin(), allowed_interface_types_.end(), interface);
auto index = std::distance(allowed_interface_types_.begin(), it);
if (!controller_interface::get_ordered_interfaces(
command_interfaces_, command_joint_names_, interface, joint_command_interface_[index]))
{
RCLCPP_ERROR(
get_node()->get_logger(), "Expected %zu '%s' command interfaces, got %zu.", dof_,
interface.c_str(), joint_command_interface_[index].size());
return CallbackReturn::ERROR;
}
}
for (const auto & interface : params_.state_interfaces)
{
auto it =
std::find(allowed_interface_types_.begin(), allowed_interface_types_.end(), interface);
auto index = std::distance(allowed_interface_types_.begin(), it);
if (!controller_interface::get_ordered_interfaces(
state_interfaces_, params_.joints, interface, joint_state_interface_[index]))
{
RCLCPP_ERROR(
get_node()->get_logger(), "Expected %zu '%s' state interfaces, got %zu.", dof_,
interface.c_str(), joint_state_interface_[index].size());
return CallbackReturn::ERROR;
}
}
// Store 'home' pose
traj_msg_home_ptr_ = std::make_shared<trajectory_msgs::msg::JointTrajectory>();
traj_msg_home_ptr_->header.stamp.sec = 0;
traj_msg_home_ptr_->header.stamp.nanosec = 0;
traj_msg_home_ptr_->points.resize(1);
traj_msg_home_ptr_->points[0].time_from_start.sec = 0;
traj_msg_home_ptr_->points[0].time_from_start.nanosec = 50000000;
traj_msg_home_ptr_->points[0].positions.resize(joint_state_interface_[0].size());
for (size_t index = 0; index < joint_state_interface_[0].size(); ++index)
{
traj_msg_home_ptr_->points[0].positions[index] =
joint_state_interface_[0][index].get().get_value();
}
traj_external_point_ptr_ = std::make_shared<Trajectory>();
traj_home_point_ptr_ = std::make_shared<Trajectory>();
traj_msg_external_point_ptr_.writeFromNonRT(
std::shared_ptr<trajectory_msgs::msg::JointTrajectory>());
subscriber_is_active_ = true;
traj_point_active_ptr_ = &traj_external_point_ptr_;
// Initialize current state storage if hardware state has tracking offset
read_state_from_hardware(state_current_);
read_state_from_hardware(state_desired_);
read_state_from_hardware(last_commanded_state_);
// Handle restart of controller by reading from commands if
// those are not nan
trajectory_msgs::msg::JointTrajectoryPoint state;
resize_joint_trajectory_point(state, dof_);
if (read_state_from_command_interfaces(state))
{
state_current_ = state;
state_desired_ = state;
last_commanded_state_ = state;
}
return CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn JointTrajectoryController::on_deactivate(
const rclcpp_lifecycle::State &)
{
// TODO(anyone): How to halt when using effort commands?
for (size_t index = 0; index < dof_; ++index)
{
if (has_position_command_interface_)
{
joint_command_interface_[0][index].get().set_value(
joint_command_interface_[0][index].get().get_value());
}
if (has_velocity_command_interface_)
{
joint_command_interface_[1][index].get().set_value(0.0);
}
if (has_effort_command_interface_)
{
joint_command_interface_[3][index].get().set_value(0.0);
}
}
for (size_t index = 0; index < allowed_interface_types_.size(); ++index)
{
joint_command_interface_[index].clear();
joint_state_interface_[index].clear();
}
release_interfaces();
subscriber_is_active_ = false;
return CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn JointTrajectoryController::on_cleanup(
const rclcpp_lifecycle::State &)
{
// go home
if (traj_home_point_ptr_ != nullptr)
{
traj_home_point_ptr_->update(traj_msg_home_ptr_);
traj_point_active_ptr_ = &traj_home_point_ptr_;
}
return CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn JointTrajectoryController::on_error(
const rclcpp_lifecycle::State &)
{
if (!reset())
{
return CallbackReturn::ERROR;
}
return CallbackReturn::SUCCESS;
}
bool JointTrajectoryController::reset()
{
subscriber_is_active_ = false;
joint_command_subscriber_.reset();
for (const auto & pid : pids_)
{
if (pid)