-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
Copy pathcontroller_server.cpp
863 lines (747 loc) · 30.8 KB
/
controller_server.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
// Copyright (c) 2019 Intel Corporation
//
// 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 <chrono>
#include <vector>
#include <memory>
#include <string>
#include <utility>
#include <limits>
#include "lifecycle_msgs/msg/state.hpp"
#include "nav2_core/controller_exceptions.hpp"
#include "nav_2d_utils/conversions.hpp"
#include "nav_2d_utils/tf_help.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_controller/controller_server.hpp"
using namespace std::chrono_literals;
using rcl_interfaces::msg::ParameterType;
using std::placeholders::_1;
namespace nav2_controller
{
ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("controller_server", "", options),
progress_checker_loader_("nav2_core", "nav2_core::ProgressChecker"),
default_progress_checker_ids_{"progress_checker"},
default_progress_checker_types_{"nav2_controller::SimpleProgressChecker"},
goal_checker_loader_("nav2_core", "nav2_core::GoalChecker"),
default_goal_checker_ids_{"goal_checker"},
default_goal_checker_types_{"nav2_controller::SimpleGoalChecker"},
lp_loader_("nav2_core", "nav2_core::Controller"),
default_ids_{"FollowPath"},
default_types_{"dwb_core::DWBLocalPlanner"},
costmap_update_timeout_(300ms)
{
RCLCPP_INFO(get_logger(), "Creating controller server");
declare_parameter("controller_frequency", 20.0);
declare_parameter("action_server_result_timeout", 10.0);
declare_parameter("progress_checker_plugins", default_progress_checker_ids_);
declare_parameter("goal_checker_plugins", default_goal_checker_ids_);
declare_parameter("controller_plugins", default_ids_);
declare_parameter("min_x_velocity_threshold", rclcpp::ParameterValue(0.0001));
declare_parameter("min_y_velocity_threshold", rclcpp::ParameterValue(0.0001));
declare_parameter("min_theta_velocity_threshold", rclcpp::ParameterValue(0.0001));
declare_parameter("speed_limit_topic", rclcpp::ParameterValue("speed_limit"));
declare_parameter("failure_tolerance", rclcpp::ParameterValue(0.0));
declare_parameter("use_realtime_priority", rclcpp::ParameterValue(false));
declare_parameter("publish_zero_velocity", rclcpp::ParameterValue(true));
declare_parameter("costmap_update_timeout", 0.30); // 300ms
// The costmap node is used in the implementation of the controller
costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
"local_costmap", std::string{get_namespace()},
get_parameter("use_sim_time").as_bool());
}
ControllerServer::~ControllerServer()
{
progress_checkers_.clear();
goal_checkers_.clear();
controllers_.clear();
costmap_thread_.reset();
}
nav2_util::CallbackReturn
ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
{
auto node = shared_from_this();
RCLCPP_INFO(get_logger(), "Configuring controller interface");
RCLCPP_INFO(get_logger(), "getting progress checker plugins..");
get_parameter("progress_checker_plugins", progress_checker_ids_);
if (progress_checker_ids_ == default_progress_checker_ids_) {
for (size_t i = 0; i < default_progress_checker_ids_.size(); ++i) {
nav2_util::declare_parameter_if_not_declared(
node, default_progress_checker_ids_[i] + ".plugin",
rclcpp::ParameterValue(default_progress_checker_types_[i]));
}
}
RCLCPP_INFO(get_logger(), "getting goal checker plugins..");
get_parameter("goal_checker_plugins", goal_checker_ids_);
if (goal_checker_ids_ == default_goal_checker_ids_) {
for (size_t i = 0; i < default_goal_checker_ids_.size(); ++i) {
nav2_util::declare_parameter_if_not_declared(
node, default_goal_checker_ids_[i] + ".plugin",
rclcpp::ParameterValue(default_goal_checker_types_[i]));
}
}
get_parameter("controller_plugins", controller_ids_);
if (controller_ids_ == default_ids_) {
for (size_t i = 0; i < default_ids_.size(); ++i) {
nav2_util::declare_parameter_if_not_declared(
node, default_ids_[i] + ".plugin",
rclcpp::ParameterValue(default_types_[i]));
}
}
controller_types_.resize(controller_ids_.size());
goal_checker_types_.resize(goal_checker_ids_.size());
progress_checker_types_.resize(progress_checker_ids_.size());
get_parameter("controller_frequency", controller_frequency_);
get_parameter("min_x_velocity_threshold", min_x_velocity_threshold_);
get_parameter("min_y_velocity_threshold", min_y_velocity_threshold_);
get_parameter("min_theta_velocity_threshold", min_theta_velocity_threshold_);
RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);
std::string speed_limit_topic;
get_parameter("speed_limit_topic", speed_limit_topic);
get_parameter("failure_tolerance", failure_tolerance_);
get_parameter("use_realtime_priority", use_realtime_priority_);
get_parameter("publish_zero_velocity", publish_zero_velocity_);
costmap_ros_->configure();
// Launch a thread to run the costmap node
costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
for (size_t i = 0; i != progress_checker_ids_.size(); i++) {
try {
progress_checker_types_[i] = nav2_util::get_plugin_type_param(
node, progress_checker_ids_[i]);
nav2_core::ProgressChecker::Ptr progress_checker =
progress_checker_loader_.createUniqueInstance(progress_checker_types_[i]);
RCLCPP_INFO(
get_logger(), "Created progress_checker : %s of type %s",
progress_checker_ids_[i].c_str(), progress_checker_types_[i].c_str());
progress_checker->initialize(node, progress_checker_ids_[i]);
progress_checkers_.insert({progress_checker_ids_[i], progress_checker});
} catch (const std::exception & ex) {
RCLCPP_FATAL(
get_logger(),
"Failed to create progress_checker. Exception: %s", ex.what());
on_cleanup(state);
return nav2_util::CallbackReturn::FAILURE;
}
}
for (size_t i = 0; i != progress_checker_ids_.size(); i++) {
progress_checker_ids_concat_ += progress_checker_ids_[i] + std::string(" ");
}
RCLCPP_INFO(
get_logger(),
"Controller Server has %s progress checkers available.", progress_checker_ids_concat_.c_str());
for (size_t i = 0; i != goal_checker_ids_.size(); i++) {
try {
goal_checker_types_[i] = nav2_util::get_plugin_type_param(node, goal_checker_ids_[i]);
nav2_core::GoalChecker::Ptr goal_checker =
goal_checker_loader_.createUniqueInstance(goal_checker_types_[i]);
RCLCPP_INFO(
get_logger(), "Created goal checker : %s of type %s",
goal_checker_ids_[i].c_str(), goal_checker_types_[i].c_str());
goal_checker->initialize(node, goal_checker_ids_[i], costmap_ros_);
goal_checkers_.insert({goal_checker_ids_[i], goal_checker});
} catch (const pluginlib::PluginlibException & ex) {
RCLCPP_FATAL(
get_logger(),
"Failed to create goal checker. Exception: %s", ex.what());
on_cleanup(state);
return nav2_util::CallbackReturn::FAILURE;
}
}
for (size_t i = 0; i != goal_checker_ids_.size(); i++) {
goal_checker_ids_concat_ += goal_checker_ids_[i] + std::string(" ");
}
RCLCPP_INFO(
get_logger(),
"Controller Server has %s goal checkers available.", goal_checker_ids_concat_.c_str());
for (size_t i = 0; i != controller_ids_.size(); i++) {
try {
controller_types_[i] = nav2_util::get_plugin_type_param(node, controller_ids_[i]);
nav2_core::Controller::Ptr controller =
lp_loader_.createUniqueInstance(controller_types_[i]);
RCLCPP_INFO(
get_logger(), "Created controller : %s of type %s",
controller_ids_[i].c_str(), controller_types_[i].c_str());
controller->configure(
node, controller_ids_[i],
costmap_ros_->getTfBuffer(), costmap_ros_);
controllers_.insert({controller_ids_[i], controller});
} catch (const pluginlib::PluginlibException & ex) {
RCLCPP_FATAL(
get_logger(),
"Failed to create controller. Exception: %s", ex.what());
on_cleanup(state);
return nav2_util::CallbackReturn::FAILURE;
}
}
for (size_t i = 0; i != controller_ids_.size(); i++) {
controller_ids_concat_ += controller_ids_[i] + std::string(" ");
}
RCLCPP_INFO(
get_logger(),
"Controller Server has %s controllers available.", controller_ids_concat_.c_str());
odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node);
vel_publisher_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel", 1);
double action_server_result_timeout;
get_parameter("action_server_result_timeout", action_server_result_timeout);
rcl_action_server_options_t server_options = rcl_action_server_get_default_options();
server_options.result_timeout.nanoseconds = RCL_S_TO_NS(action_server_result_timeout);
double costmap_update_timeout_dbl;
get_parameter("costmap_update_timeout", costmap_update_timeout_dbl);
costmap_update_timeout_ = rclcpp::Duration::from_seconds(costmap_update_timeout_dbl);
// Create the action server that we implement with our followPath method
// This may throw due to real-time prioritzation if user doesn't have real-time permissions
try {
action_server_ = std::make_unique<ActionServer>(
shared_from_this(),
"follow_path",
std::bind(&ControllerServer::computeControl, this),
nullptr,
std::chrono::milliseconds(500),
true /*spin thread*/, server_options, use_realtime_priority_ /*soft realtime*/);
} catch (const std::runtime_error & e) {
RCLCPP_ERROR(get_logger(), "Error creating action server! %s", e.what());
on_cleanup(state);
return nav2_util::CallbackReturn::FAILURE;
}
// Set subscription to the speed limiting topic
speed_limit_sub_ = create_subscription<nav2_msgs::msg::SpeedLimit>(
speed_limit_topic, rclcpp::QoS(10),
std::bind(&ControllerServer::speedLimitCallback, this, std::placeholders::_1));
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
ControllerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Activating");
const auto costmap_ros_state = costmap_ros_->activate();
if (costmap_ros_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) {
return nav2_util::CallbackReturn::FAILURE;
}
ControllerMap::iterator it;
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->activate();
}
vel_publisher_->on_activate();
action_server_->activate();
auto node = shared_from_this();
// Add callback for dynamic parameters
dyn_params_handler_ = node->add_on_set_parameters_callback(
std::bind(&ControllerServer::dynamicParametersCallback, this, _1));
// create bond connection
createBond();
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Deactivating");
action_server_->deactivate();
ControllerMap::iterator it;
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->deactivate();
}
/*
* The costmap is also a lifecycle node, so it may have already fired on_deactivate
* via rcl preshutdown cb. Despite the rclcpp docs saying on_shutdown callbacks fire
* in the order added, the preshutdown callbacks clearly don't per se, due to using an
* unordered_set iteration. Once this issue is resolved, we can maybe make a stronger
* ordering assumption: /~https://github.com/ros2/rclcpp/issues/2096
*/
costmap_ros_->deactivate();
publishZeroVelocity();
vel_publisher_->on_deactivate();
remove_on_set_parameters_callback(dyn_params_handler_.get());
dyn_params_handler_.reset();
// destroy bond connection
destroyBond();
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Cleaning up");
// Cleanup the helper classes
ControllerMap::iterator it;
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->cleanup();
}
controllers_.clear();
goal_checkers_.clear();
progress_checkers_.clear();
costmap_ros_->cleanup();
// Release any allocated resources
action_server_.reset();
odom_sub_.reset();
costmap_thread_.reset();
vel_publisher_.reset();
speed_limit_sub_.reset();
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
ControllerServer::on_shutdown(const rclcpp_lifecycle::State &)
{
RCLCPP_INFO(get_logger(), "Shutting down");
return nav2_util::CallbackReturn::SUCCESS;
}
bool ControllerServer::findControllerId(
const std::string & c_name,
std::string & current_controller)
{
if (controllers_.find(c_name) == controllers_.end()) {
if (controllers_.size() == 1 && c_name.empty()) {
RCLCPP_WARN_ONCE(
get_logger(), "No controller was specified in action call."
" Server will use only plugin loaded %s. "
"This warning will appear once.", controller_ids_concat_.c_str());
current_controller = controllers_.begin()->first;
} else {
RCLCPP_ERROR(
get_logger(), "FollowPath called with controller name %s, "
"which does not exist. Available controllers are: %s.",
c_name.c_str(), controller_ids_concat_.c_str());
return false;
}
} else {
RCLCPP_DEBUG(get_logger(), "Selected controller: %s.", c_name.c_str());
current_controller = c_name;
}
return true;
}
bool ControllerServer::findGoalCheckerId(
const std::string & c_name,
std::string & current_goal_checker)
{
if (goal_checkers_.find(c_name) == goal_checkers_.end()) {
if (goal_checkers_.size() == 1 && c_name.empty()) {
RCLCPP_WARN_ONCE(
get_logger(), "No goal checker was specified in parameter 'current_goal_checker'."
" Server will use only plugin loaded %s. "
"This warning will appear once.", goal_checker_ids_concat_.c_str());
current_goal_checker = goal_checkers_.begin()->first;
} else {
RCLCPP_ERROR(
get_logger(), "FollowPath called with goal_checker name %s in parameter"
" 'current_goal_checker', which does not exist. Available goal checkers are: %s.",
c_name.c_str(), goal_checker_ids_concat_.c_str());
return false;
}
} else {
RCLCPP_DEBUG(get_logger(), "Selected goal checker: %s.", c_name.c_str());
current_goal_checker = c_name;
}
return true;
}
bool ControllerServer::findProgressCheckerId(
const std::string & c_name,
std::string & current_progress_checker)
{
if (progress_checkers_.find(c_name) == progress_checkers_.end()) {
if (progress_checkers_.size() == 1 && c_name.empty()) {
RCLCPP_WARN_ONCE(
get_logger(), "No progress checker was specified in parameter 'current_progress_checker'."
" Server will use only plugin loaded %s. "
"This warning will appear once.", progress_checker_ids_concat_.c_str());
current_progress_checker = progress_checkers_.begin()->first;
} else {
RCLCPP_ERROR(
get_logger(), "FollowPath called with progress_checker name %s in parameter"
" 'current_progress_checker', which does not exist. Available progress checkers are: %s.",
c_name.c_str(), progress_checker_ids_concat_.c_str());
return false;
}
} else {
RCLCPP_DEBUG(get_logger(), "Selected progress checker: %s.", c_name.c_str());
current_progress_checker = c_name;
}
return true;
}
void ControllerServer::computeControl()
{
std::lock_guard<std::mutex> lock(dynamic_params_lock_);
RCLCPP_INFO(get_logger(), "Received a goal, begin computing control effort.");
try {
auto goal = action_server_->get_current_goal();
if (!goal) {
return; // goal would be nullptr if action_server_ is inactivate.
}
std::string c_name = goal->controller_id;
std::string current_controller;
if (findControllerId(c_name, current_controller)) {
current_controller_ = current_controller;
} else {
throw nav2_core::InvalidController("Failed to find controller name: " + c_name);
}
std::string gc_name = goal->goal_checker_id;
std::string current_goal_checker;
if (findGoalCheckerId(gc_name, current_goal_checker)) {
current_goal_checker_ = current_goal_checker;
} else {
throw nav2_core::ControllerException("Failed to find goal checker name: " + gc_name);
}
std::string pc_name = goal->progress_checker_id;
std::string current_progress_checker;
if (findProgressCheckerId(pc_name, current_progress_checker)) {
current_progress_checker_ = current_progress_checker;
} else {
throw nav2_core::ControllerException("Failed to find progress checker name: " + pc_name);
}
setPlannerPath(goal->path);
progress_checkers_[current_progress_checker_]->reset();
last_valid_cmd_time_ = now();
rclcpp::WallRate loop_rate(controller_frequency_);
while (rclcpp::ok()) {
auto start_time = this->now();
if (action_server_ == nullptr || !action_server_->is_server_active()) {
RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping.");
return;
}
if (action_server_->is_cancel_requested()) {
if (controllers_[current_controller_]->cancel()) {
RCLCPP_INFO(get_logger(), "Cancellation was successful. Stopping the robot.");
action_server_->terminate_all();
onGoalExit();
return;
} else {
RCLCPP_INFO_THROTTLE(
get_logger(), *get_clock(), 1000, "Waiting for the controller to finish cancellation");
}
}
// Don't compute a trajectory until costmap is valid (after clear costmap)
rclcpp::Rate r(100);
auto waiting_start = now();
while (!costmap_ros_->isCurrent()) {
if (now() - waiting_start > costmap_update_timeout_) {
throw nav2_core::ControllerTimedOut("Costmap timed out waiting for update");
}
r.sleep();
}
updateGlobalPath();
computeAndPublishVelocity();
if (isGoalReached()) {
RCLCPP_INFO(get_logger(), "Reached the goal!");
break;
}
auto cycle_duration = this->now() - start_time;
if (!loop_rate.sleep()) {
RCLCPP_WARN(
get_logger(),
"Control loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz.",
controller_frequency_, 1 / cycle_duration.seconds());
}
}
} catch (nav2_core::InvalidController & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
onGoalExit();
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::INVALID_CONTROLLER;
action_server_->terminate_current(result);
return;
} catch (nav2_core::ControllerTFError & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
onGoalExit();
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::TF_ERROR;
action_server_->terminate_current(result);
return;
} catch (nav2_core::NoValidControl & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
onGoalExit();
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::NO_VALID_CONTROL;
action_server_->terminate_current(result);
return;
} catch (nav2_core::FailedToMakeProgress & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
onGoalExit();
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::FAILED_TO_MAKE_PROGRESS;
action_server_->terminate_current(result);
return;
} catch (nav2_core::PatienceExceeded & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
onGoalExit();
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::PATIENCE_EXCEEDED;
action_server_->terminate_current(result);
return;
} catch (nav2_core::InvalidPath & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
onGoalExit();
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::INVALID_PATH;
action_server_->terminate_current(result);
return;
} catch (nav2_core::ControllerTimedOut & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
onGoalExit();
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::CONTROLLER_TIMED_OUT;
action_server_->terminate_current(result);
return;
} catch (nav2_core::ControllerException & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
onGoalExit();
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::UNKNOWN;
action_server_->terminate_current(result);
return;
} catch (std::exception & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
onGoalExit();
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::UNKNOWN;
action_server_->terminate_current(result);
return;
}
RCLCPP_DEBUG(get_logger(), "Controller succeeded, setting result");
onGoalExit();
// TODO(orduno) #861 Handle a pending preemption and set controller name
action_server_->succeeded_current();
}
void ControllerServer::setPlannerPath(const nav_msgs::msg::Path & path)
{
RCLCPP_DEBUG(
get_logger(),
"Providing path to the controller %s", current_controller_.c_str());
if (path.poses.empty()) {
throw nav2_core::InvalidPath("Path is empty.");
}
controllers_[current_controller_]->setPlan(path);
end_pose_ = path.poses.back();
end_pose_.header.frame_id = path.header.frame_id;
goal_checkers_[current_goal_checker_]->reset();
RCLCPP_DEBUG(
get_logger(), "Path end point is (%.2f, %.2f)",
end_pose_.pose.position.x, end_pose_.pose.position.y);
current_path_ = path;
}
void ControllerServer::computeAndPublishVelocity()
{
geometry_msgs::msg::PoseStamped pose;
if (!getRobotPose(pose)) {
throw nav2_core::ControllerTFError("Failed to obtain robot pose");
}
if (!progress_checkers_[current_progress_checker_]->check(pose)) {
throw nav2_core::FailedToMakeProgress("Failed to make progress");
}
nav_2d_msgs::msg::Twist2D twist = getThresholdedTwist(odom_sub_->getTwist());
geometry_msgs::msg::TwistStamped cmd_vel_2d;
try {
cmd_vel_2d =
controllers_[current_controller_]->computeVelocityCommands(
pose,
nav_2d_utils::twist2Dto3D(twist),
goal_checkers_[current_goal_checker_].get());
last_valid_cmd_time_ = now();
cmd_vel_2d.header.frame_id = costmap_ros_->getBaseFrameID();
cmd_vel_2d.header.stamp = last_valid_cmd_time_;
// Only no valid control exception types are valid to attempt to have control patience, as
// other types will not be resolved with more attempts
} catch (nav2_core::NoValidControl & e) {
if (failure_tolerance_ > 0 || failure_tolerance_ == -1.0) {
RCLCPP_WARN(this->get_logger(), "%s", e.what());
cmd_vel_2d.twist.angular.x = 0;
cmd_vel_2d.twist.angular.y = 0;
cmd_vel_2d.twist.angular.z = 0;
cmd_vel_2d.twist.linear.x = 0;
cmd_vel_2d.twist.linear.y = 0;
cmd_vel_2d.twist.linear.z = 0;
cmd_vel_2d.header.frame_id = costmap_ros_->getBaseFrameID();
cmd_vel_2d.header.stamp = now();
if ((now() - last_valid_cmd_time_).seconds() > failure_tolerance_ &&
failure_tolerance_ != -1.0)
{
throw nav2_core::PatienceExceeded("Controller patience exceeded");
}
} else {
throw nav2_core::NoValidControl(e.what());
}
}
std::shared_ptr<Action::Feedback> feedback = std::make_shared<Action::Feedback>();
feedback->speed = std::hypot(cmd_vel_2d.twist.linear.x, cmd_vel_2d.twist.linear.y);
// Find the closest pose to current pose on global path
nav_msgs::msg::Path & current_path = current_path_;
auto find_closest_pose_idx =
[&pose, ¤t_path]() {
size_t closest_pose_idx = 0;
double curr_min_dist = std::numeric_limits<double>::max();
for (size_t curr_idx = 0; curr_idx < current_path.poses.size(); ++curr_idx) {
double curr_dist = nav2_util::geometry_utils::euclidean_distance(
pose, current_path.poses[curr_idx]);
if (curr_dist < curr_min_dist) {
curr_min_dist = curr_dist;
closest_pose_idx = curr_idx;
}
}
return closest_pose_idx;
};
feedback->distance_to_goal =
nav2_util::geometry_utils::calculate_path_length(current_path_, find_closest_pose_idx());
action_server_->publish_feedback(feedback);
RCLCPP_DEBUG(get_logger(), "Publishing velocity at time %.2f", now().seconds());
publishVelocity(cmd_vel_2d);
}
void ControllerServer::updateGlobalPath()
{
if (action_server_->is_preempt_requested()) {
RCLCPP_INFO(get_logger(), "Passing new path to controller.");
auto goal = action_server_->accept_pending_goal();
std::string current_controller;
if (findControllerId(goal->controller_id, current_controller)) {
current_controller_ = current_controller;
} else {
RCLCPP_INFO(
get_logger(), "Terminating action, invalid controller %s requested.",
goal->controller_id.c_str());
action_server_->terminate_current();
return;
}
std::string current_goal_checker;
if (findGoalCheckerId(goal->goal_checker_id, current_goal_checker)) {
current_goal_checker_ = current_goal_checker;
} else {
RCLCPP_INFO(
get_logger(), "Terminating action, invalid goal checker %s requested.",
goal->goal_checker_id.c_str());
action_server_->terminate_current();
return;
}
std::string current_progress_checker;
if (findProgressCheckerId(goal->progress_checker_id, current_progress_checker)) {
if (current_progress_checker_ != current_progress_checker) {
RCLCPP_INFO(
get_logger(), "Change of progress checker %s requested, resetting it",
goal->progress_checker_id.c_str());
current_progress_checker_ = current_progress_checker;
progress_checkers_[current_progress_checker_]->reset();
}
} else {
RCLCPP_INFO(
get_logger(), "Terminating action, invalid progress checker %s requested.",
goal->progress_checker_id.c_str());
action_server_->terminate_current();
return;
}
setPlannerPath(goal->path);
}
}
void ControllerServer::publishVelocity(const geometry_msgs::msg::TwistStamped & velocity)
{
auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>(velocity);
if (vel_publisher_->is_activated() && vel_publisher_->get_subscription_count() > 0) {
vel_publisher_->publish(std::move(cmd_vel));
}
}
void ControllerServer::publishZeroVelocity()
{
geometry_msgs::msg::TwistStamped velocity;
velocity.twist.angular.x = 0;
velocity.twist.angular.y = 0;
velocity.twist.angular.z = 0;
velocity.twist.linear.x = 0;
velocity.twist.linear.y = 0;
velocity.twist.linear.z = 0;
velocity.header.frame_id = costmap_ros_->getBaseFrameID();
velocity.header.stamp = now();
publishVelocity(velocity);
}
void ControllerServer::onGoalExit()
{
if (publish_zero_velocity_) {
publishZeroVelocity();
}
// Reset the state of the controllers after the task has ended
ControllerMap::iterator it;
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->reset();
}
}
bool ControllerServer::isGoalReached()
{
geometry_msgs::msg::PoseStamped pose;
if (!getRobotPose(pose)) {
return false;
}
nav_2d_msgs::msg::Twist2D twist = getThresholdedTwist(odom_sub_->getTwist());
geometry_msgs::msg::Twist velocity = nav_2d_utils::twist2Dto3D(twist);
geometry_msgs::msg::PoseStamped transformed_end_pose;
rclcpp::Duration tolerance(rclcpp::Duration::from_seconds(costmap_ros_->getTransformTolerance()));
nav_2d_utils::transformPose(
costmap_ros_->getTfBuffer(), costmap_ros_->getGlobalFrameID(),
end_pose_, transformed_end_pose, tolerance);
return goal_checkers_[current_goal_checker_]->isGoalReached(
pose.pose, transformed_end_pose.pose,
velocity);
}
bool ControllerServer::getRobotPose(geometry_msgs::msg::PoseStamped & pose)
{
geometry_msgs::msg::PoseStamped current_pose;
if (!costmap_ros_->getRobotPose(current_pose)) {
return false;
}
pose = current_pose;
return true;
}
void ControllerServer::speedLimitCallback(const nav2_msgs::msg::SpeedLimit::SharedPtr msg)
{
ControllerMap::iterator it;
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->setSpeedLimit(msg->speed_limit, msg->percentage);
}
}
rcl_interfaces::msg::SetParametersResult
ControllerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
{
rcl_interfaces::msg::SetParametersResult result;
for (auto parameter : parameters) {
const auto & type = parameter.get_type();
const auto & name = parameter.get_name();
// If we are trying to change the parameter of a plugin we can just skip it at this point
// as they handle parameter changes themselves and don't need to lock the mutex
if (name.find('.') != std::string::npos) {
continue;
}
if (!dynamic_params_lock_.try_lock()) {
RCLCPP_WARN(
get_logger(),
"Unable to dynamically change Parameters while the controller is currently running");
result.successful = false;
result.reason =
"Unable to dynamically change Parameters while the controller is currently running";
return result;
}
if (type == ParameterType::PARAMETER_DOUBLE) {
if (name == "controller_frequency") {
controller_frequency_ = parameter.as_double();
} else if (name == "min_x_velocity_threshold") {
min_x_velocity_threshold_ = parameter.as_double();
} else if (name == "min_y_velocity_threshold") {
min_y_velocity_threshold_ = parameter.as_double();
} else if (name == "min_theta_velocity_threshold") {
min_theta_velocity_threshold_ = parameter.as_double();
} else if (name == "failure_tolerance") {
failure_tolerance_ = parameter.as_double();
}
}
dynamic_params_lock_.unlock();
}
result.successful = true;
return result;
}
} // namespace nav2_controller
#include "rclcpp_components/register_node_macro.hpp"
// Register the component with class_loader.
// This acts as a sort of entry point, allowing the component to be discoverable when its library
// is being loaded into a running process.
RCLCPP_COMPONENTS_REGISTER_NODE(nav2_controller::ControllerServer)