-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
planner_server.cpp
696 lines (588 loc) · 22.5 KB
/
planner_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
// Copyright (c) 2018 Intel Corporation
// Copyright (c) 2019 Samsung Research America
//
// 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 <cmath>
#include <iomanip>
#include <iostream>
#include <limits>
#include <iterator>
#include <memory>
#include <string>
#include <vector>
#include <utility>
#include "builtin_interfaces/msg/duration.hpp"
#include "nav2_util/costmap.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "nav2_costmap_2d/cost_values.hpp"
#include "nav2_planner/planner_server.hpp"
using namespace std::chrono_literals;
using rcl_interfaces::msg::ParameterType;
using std::placeholders::_1;
namespace nav2_planner
{
PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("planner_server", "", options),
gp_loader_("nav2_core", "nav2_core::GlobalPlanner"),
default_ids_{"GridBased"},
default_types_{"nav2_navfn_planner/NavfnPlanner"},
costmap_(nullptr)
{
RCLCPP_INFO(get_logger(), "Creating");
// Declare this node's parameters
declare_parameter("planner_plugins", default_ids_);
declare_parameter("expected_planner_frequency", 1.0);
get_parameter("planner_plugins", planner_ids_);
if (planner_ids_ == default_ids_) {
for (size_t i = 0; i < default_ids_.size(); ++i) {
declare_parameter(default_ids_[i] + ".plugin", default_types_[i]);
}
}
// Setup the global costmap
costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
"global_costmap", std::string{get_namespace()}, "global_costmap",
get_parameter("use_sim_time").as_bool());
// Launch a thread to run the costmap node
costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
}
void
PlannerServer::prepDestruction()
{
planners_.clear();
costmap_thread_.reset();
}
PlannerServer::~PlannerServer()
{
prepDestruction();
}
void PlannerServer::on_rcl_preshutdown()
{
prepDestruction();
LifecycleNode::on_rcl_preshutdown();
}
nav2_util::CallbackReturn
PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Configuring");
costmap_ros_->configure();
costmap_ = costmap_ros_->getCostmap();
RCLCPP_DEBUG(
get_logger(), "Costmap size: %d,%d",
costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY());
tf_ = costmap_ros_->getTfBuffer();
planner_types_.resize(planner_ids_.size());
auto node = shared_from_this();
for (size_t i = 0; i != planner_ids_.size(); i++) {
try {
planner_types_[i] = nav2_util::get_plugin_type_param(
node, planner_ids_[i]);
nav2_core::GlobalPlanner::Ptr planner =
gp_loader_.createUniqueInstance(planner_types_[i]);
RCLCPP_INFO(
get_logger(), "Created global planner plugin %s of type %s",
planner_ids_[i].c_str(), planner_types_[i].c_str());
planner->configure(node, planner_ids_[i], tf_, costmap_ros_);
planners_.insert({planner_ids_[i], planner});
} catch (const pluginlib::PluginlibException & ex) {
RCLCPP_FATAL(
get_logger(), "Failed to create global planner. Exception: %s",
ex.what());
return nav2_util::CallbackReturn::FAILURE;
}
}
for (size_t i = 0; i != planner_ids_.size(); i++) {
planner_ids_concat_ += planner_ids_[i] + std::string(" ");
}
RCLCPP_INFO(
get_logger(),
"Planner Server has %s planners available.", planner_ids_concat_.c_str());
double expected_planner_frequency;
get_parameter("expected_planner_frequency", expected_planner_frequency);
if (expected_planner_frequency > 0) {
max_planner_duration_ = 1 / expected_planner_frequency;
} else {
RCLCPP_WARN(
get_logger(),
"The expected planner frequency parameter is %.4f Hz. The value should to be greater"
" than 0.0 to turn on duration overrrun warning messages", expected_planner_frequency);
max_planner_duration_ = 0.0;
}
// Initialize pubs & subs
plan_publisher_ = create_publisher<nav_msgs::msg::Path>("plan", 1);
// Create the action servers for path planning to a pose and through poses
action_server_pose_ = std::make_unique<ActionServerToPose>(
shared_from_this(),
"compute_path_to_pose",
std::bind(&PlannerServer::computePlan, this),
nullptr,
std::chrono::milliseconds(500),
true);
action_server_poses_ = std::make_unique<ActionServerThroughPoses>(
shared_from_this(),
"compute_path_through_poses",
std::bind(&PlannerServer::computePlanThroughPoses, this),
nullptr,
std::chrono::milliseconds(500),
true);
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
PlannerServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Activating");
plan_publisher_->on_activate();
action_server_pose_->activate();
action_server_poses_->activate();
costmap_ros_->activate();
PlannerMap::iterator it;
for (it = planners_.begin(); it != planners_.end(); ++it) {
it->second->activate();
}
auto node = shared_from_this();
is_path_valid_service_ = node->create_service<nav2_msgs::srv::IsPathValid>(
"is_path_valid",
std::bind(
&PlannerServer::isPathValid, this,
std::placeholders::_1, std::placeholders::_2));
// Add callback for dynamic parameters
dyn_params_handler_ = node->add_on_set_parameters_callback(
std::bind(&PlannerServer::dynamicParametersCallback, this, _1));
// create bond connection
createBond();
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Deactivating");
action_server_pose_->deactivate();
action_server_poses_->deactivate();
plan_publisher_->on_deactivate();
costmap_ros_->deactivate();
PlannerMap::iterator it;
for (it = planners_.begin(); it != planners_.end(); ++it) {
it->second->deactivate();
}
dyn_params_handler_.reset();
// destroy bond connection
destroyBond();
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Cleaning up");
action_server_pose_.reset();
action_server_poses_.reset();
plan_publisher_.reset();
tf_.reset();
costmap_ros_->cleanup();
PlannerMap::iterator it;
for (it = planners_.begin(); it != planners_.end(); ++it) {
it->second->cleanup();
}
planners_.clear();
costmap_ = nullptr;
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
PlannerServer::on_shutdown(const rclcpp_lifecycle::State &)
{
RCLCPP_INFO(get_logger(), "Shutting down");
return nav2_util::CallbackReturn::SUCCESS;
}
template<typename T>
bool PlannerServer::isServerInactive(
std::unique_ptr<nav2_util::SimpleActionServer<T>> & action_server)
{
if (action_server == nullptr || !action_server->is_server_active()) {
RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping.");
return true;
}
return false;
}
void PlannerServer::waitForCostmap()
{
// Don't compute a plan until costmap is valid (after clear costmap)
rclcpp::Rate r(100);
while (!costmap_ros_->isCurrent()) {
r.sleep();
}
}
template<typename T>
bool PlannerServer::isCancelRequested(
std::unique_ptr<nav2_util::SimpleActionServer<T>> & action_server)
{
if (action_server->is_cancel_requested()) {
RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling planning action.");
action_server->terminate_all();
return true;
}
return false;
}
template<typename T>
void PlannerServer::getPreemptedGoalIfRequested(
std::unique_ptr<nav2_util::SimpleActionServer<T>> & action_server,
typename std::shared_ptr<const typename T::Goal> goal)
{
if (action_server->is_preempt_requested()) {
goal = action_server->accept_pending_goal();
}
}
template<typename T>
bool PlannerServer::getStartPose(
typename std::shared_ptr<const typename T::Goal> goal,
geometry_msgs::msg::PoseStamped & start)
{
if (goal->use_start) {
start = goal->start;
} else if (!costmap_ros_->getRobotPose(start)) {
return false;
}
return true;
}
bool PlannerServer::transformPosesToGlobalFrame(
geometry_msgs::msg::PoseStamped & curr_start,
geometry_msgs::msg::PoseStamped & curr_goal)
{
if (!costmap_ros_->transformPoseToGlobalFrame(curr_start, curr_start) ||
!costmap_ros_->transformPoseToGlobalFrame(curr_goal, curr_goal))
{
return false;
}
return true;
}
template<typename T>
bool PlannerServer::validatePath(
const geometry_msgs::msg::PoseStamped & goal,
const nav_msgs::msg::Path & path,
const std::string & planner_id)
{
if (path.poses.empty()) {
RCLCPP_WARN(
get_logger(), "Planning algorithm %s failed to generate a valid"
" path to (%.2f, %.2f)", planner_id.c_str(),
goal.pose.position.x, goal.pose.position.y);
return false;
}
RCLCPP_DEBUG(
get_logger(),
"Found valid path of size %zu to (%.2f, %.2f)",
path.poses.size(), goal.pose.position.x,
goal.pose.position.y);
return true;
}
void PlannerServer::computePlanThroughPoses()
{
std::lock_guard<std::mutex> lock(dynamic_params_lock_);
auto start_time = steady_clock_.now();
// Initialize the ComputePathThroughPoses goal and result
auto goal = action_server_poses_->get_current_goal();
auto result = std::make_shared<ActionThroughPoses::Result>();
nav_msgs::msg::Path concat_path;
geometry_msgs::msg::PoseStamped curr_start, curr_goal;
try {
if (isServerInactive(action_server_poses_) || isCancelRequested(action_server_poses_)) {
return;
}
waitForCostmap();
getPreemptedGoalIfRequested(action_server_poses_, goal);
if (goal->goals.empty()) {
throw nav2_core::NoViapointsGiven("No viapoints given");
}
// Use start pose if provided otherwise use current robot pose
geometry_msgs::msg::PoseStamped start;
if (!getStartPose<ActionThroughPoses>(goal, start)) {
throw nav2_core::PlannerTFError("Unable to get start pose");
}
// Get consecutive paths through these points
for (unsigned int i = 0; i != goal->goals.size(); i++) {
// Get starting point
if (i == 0) {
curr_start = start;
} else {
curr_start = goal->goals[i - 1];
}
curr_goal = goal->goals[i];
// Transform them into the global frame
if (!transformPosesToGlobalFrame(curr_start, curr_goal)) {
throw nav2_core::PlannerTFError("Unable to transform poses to global frame");
}
// Get plan from start -> goal
nav_msgs::msg::Path curr_path = getPlan(curr_start, curr_goal, goal->planner_id);
if (!validatePath<ActionThroughPoses>(curr_goal, curr_path, goal->planner_id)) {
throw nav2_core::NoValidPathCouldBeFound(goal->planner_id + " generated a empty path");
}
// Concatenate paths together
concat_path.poses.insert(
concat_path.poses.end(), curr_path.poses.begin(), curr_path.poses.end());
concat_path.header = curr_path.header;
}
// Publish the plan for visualization purposes
result->path = concat_path;
publishPlan(result->path);
auto cycle_duration = steady_clock_.now() - start_time;
result->planning_time = cycle_duration;
if (max_planner_duration_ && cycle_duration.seconds() > max_planner_duration_) {
RCLCPP_WARN(
get_logger(),
"Planner loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz",
1 / max_planner_duration_, 1 / cycle_duration.seconds());
}
action_server_poses_->succeeded_current(result);
} catch (nav2_core::InvalidPlanner & ex) {
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
result->error_code = ActionToPoseGoal::INVALID_PLANNER;
action_server_poses_->terminate_current(result);
} catch (nav2_core::StartOccupied & ex) {
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
result->error_code = ActionThroughPosesGoal::START_OCCUPIED;
action_server_poses_->terminate_current(result);
} catch (nav2_core::GoalOccupied & ex) {
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
result->error_code = ActionThroughPosesGoal::GOAL_OCCUPIED;
action_server_poses_->terminate_current(result);
} catch (nav2_core::NoValidPathCouldBeFound & ex) {
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
result->error_code = ActionThroughPosesGoal::NO_VALID_PATH;
action_server_poses_->terminate_current(result);
} catch (nav2_core::PlannerTimedOut & ex) {
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
result->error_code = ActionThroughPosesGoal::TIMEOUT;
action_server_poses_->terminate_current(result);
} catch (nav2_core::StartOutsideMapBounds & ex) {
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
result->error_code = ActionThroughPosesGoal::START_OUTSIDE_MAP;
action_server_poses_->terminate_current(result);
} catch (nav2_core::GoalOutsideMapBounds & ex) {
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
result->error_code = ActionThroughPosesGoal::GOAL_OUTSIDE_MAP;
action_server_poses_->terminate_current(result);
} catch (nav2_core::PlannerTFError & ex) {
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
result->error_code = ActionThroughPosesGoal::TF_ERROR;
action_server_poses_->terminate_current(result);
} catch (nav2_core::NoViapointsGiven & ex) {
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
result->error_code = ActionThroughPosesGoal::NO_VIAPOINTS_GIVEN;
action_server_poses_->terminate_current(result);
} catch (std::exception & ex) {
exceptionWarning(curr_start, curr_goal, goal->planner_id, ex);
result->error_code = ActionThroughPosesGoal::UNKNOWN;
action_server_poses_->terminate_current(result);
}
}
void
PlannerServer::computePlan()
{
std::lock_guard<std::mutex> lock(dynamic_params_lock_);
auto start_time = steady_clock_.now();
// Initialize the ComputePathToPose goal and result
auto goal = action_server_pose_->get_current_goal();
auto result = std::make_shared<ActionToPose::Result>();
geometry_msgs::msg::PoseStamped start;
try {
if (isServerInactive(action_server_pose_) || isCancelRequested(action_server_pose_)) {
return;
}
waitForCostmap();
getPreemptedGoalIfRequested(action_server_pose_, goal);
// Use start pose if provided otherwise use current robot pose
if (!getStartPose<ActionToPose>(goal, start)) {
throw nav2_core::PlannerTFError("Unable to get start pose");
}
// Transform them into the global frame
geometry_msgs::msg::PoseStamped goal_pose = goal->goal;
if (!transformPosesToGlobalFrame(start, goal_pose)) {
throw nav2_core::PlannerTFError("Unable to transform poses to global frame");
}
result->path = getPlan(start, goal_pose, goal->planner_id);
if (!validatePath<ActionThroughPoses>(goal_pose, result->path, goal->planner_id)) {
throw nav2_core::NoValidPathCouldBeFound(goal->planner_id + " generated a empty path");
}
// Publish the plan for visualization purposes
publishPlan(result->path);
auto cycle_duration = steady_clock_.now() - start_time;
result->planning_time = cycle_duration;
if (max_planner_duration_ && cycle_duration.seconds() > max_planner_duration_) {
RCLCPP_WARN(
get_logger(),
"Planner loop missed its desired rate of %.4f Hz. Current loop rate is %.4f Hz",
1 / max_planner_duration_, 1 / cycle_duration.seconds());
}
action_server_pose_->succeeded_current(result);
} catch (nav2_core::InvalidPlanner & ex) {
exceptionWarning(start, goal->goal, goal->planner_id, ex);
result->error_code = ActionToPoseGoal::INVALID_PLANNER;
action_server_pose_->terminate_current(result);
} catch (nav2_core::StartOccupied & ex) {
exceptionWarning(start, goal->goal, goal->planner_id, ex);
result->error_code = ActionToPoseGoal::START_OCCUPIED;
action_server_pose_->terminate_current(result);
} catch (nav2_core::GoalOccupied & ex) {
exceptionWarning(start, goal->goal, goal->planner_id, ex);
result->error_code = ActionToPoseGoal::GOAL_OCCUPIED;
action_server_pose_->terminate_current(result);
} catch (nav2_core::NoValidPathCouldBeFound & ex) {
exceptionWarning(start, goal->goal, goal->planner_id, ex);
result->error_code = ActionToPoseGoal::NO_VALID_PATH;
action_server_pose_->terminate_current(result);
} catch (nav2_core::PlannerTimedOut & ex) {
exceptionWarning(start, goal->goal, goal->planner_id, ex);
result->error_code = ActionToPoseGoal::TIMEOUT;
action_server_pose_->terminate_current(result);
} catch (nav2_core::StartOutsideMapBounds & ex) {
exceptionWarning(start, goal->goal, goal->planner_id, ex);
result->error_code = ActionToPoseGoal::START_OUTSIDE_MAP;
action_server_pose_->terminate_current(result);
} catch (nav2_core::GoalOutsideMapBounds & ex) {
exceptionWarning(start, goal->goal, goal->planner_id, ex);
result->error_code = ActionToPoseGoal::GOAL_OUTSIDE_MAP;
action_server_pose_->terminate_current(result);
} catch (nav2_core::PlannerTFError & ex) {
exceptionWarning(start, goal->goal, goal->planner_id, ex);
result->error_code = ActionToPoseGoal::TF_ERROR;
action_server_pose_->terminate_current(result);
} catch (std::exception & ex) {
exceptionWarning(start, goal->goal, goal->planner_id, ex);
result->error_code = ActionToPoseGoal::UNKNOWN;
action_server_pose_->terminate_current(result);
}
}
nav_msgs::msg::Path
PlannerServer::getPlan(
const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal,
const std::string & planner_id)
{
RCLCPP_DEBUG(
get_logger(), "Attempting to a find path from (%.2f, %.2f) to "
"(%.2f, %.2f).", start.pose.position.x, start.pose.position.y,
goal.pose.position.x, goal.pose.position.y);
if (planners_.find(planner_id) != planners_.end()) {
return planners_[planner_id]->createPlan(start, goal);
} else {
if (planners_.size() == 1 && planner_id.empty()) {
RCLCPP_WARN_ONCE(
get_logger(), "No planners specified in action call. "
"Server will use only plugin %s in server."
" This warning will appear once.", planner_ids_concat_.c_str());
return planners_[planners_.begin()->first]->createPlan(start, goal);
} else {
RCLCPP_ERROR(
get_logger(), "planner %s is not a valid planner. "
"Planner names are: %s", planner_id.c_str(),
planner_ids_concat_.c_str());
throw nav2_core::InvalidPlanner("Planner id " + planner_id + " is invalid");
}
}
return nav_msgs::msg::Path();
}
void
PlannerServer::publishPlan(const nav_msgs::msg::Path & path)
{
auto msg = std::make_unique<nav_msgs::msg::Path>(path);
if (plan_publisher_->is_activated() && plan_publisher_->get_subscription_count() > 0) {
plan_publisher_->publish(std::move(msg));
}
}
void PlannerServer::isPathValid(
const std::shared_ptr<nav2_msgs::srv::IsPathValid::Request> request,
std::shared_ptr<nav2_msgs::srv::IsPathValid::Response> response)
{
response->is_valid = true;
if (request->path.poses.empty()) {
response->is_valid = false;
return;
}
geometry_msgs::msg::PoseStamped current_pose;
unsigned int closest_point_index = 0;
if (costmap_ros_->getRobotPose(current_pose)) {
float current_distance = std::numeric_limits<float>::max();
float closest_distance = current_distance;
geometry_msgs::msg::Point current_point = current_pose.pose.position;
for (unsigned int i = 0; i < request->path.poses.size(); ++i) {
geometry_msgs::msg::Point path_point = request->path.poses[i].pose.position;
current_distance = nav2_util::geometry_utils::euclidean_distance(
current_point,
path_point);
if (current_distance < closest_distance) {
closest_point_index = i;
closest_distance = current_distance;
}
}
/**
* The lethal check starts at the closest point to avoid points that have already been passed
* and may have become occupied
*/
unsigned int mx = 0;
unsigned int my = 0;
for (unsigned int i = closest_point_index; i < request->path.poses.size(); ++i) {
costmap_->worldToMap(
request->path.poses[i].pose.position.x,
request->path.poses[i].pose.position.y, mx, my);
unsigned int cost = costmap_->getCost(mx, my);
if (cost == nav2_costmap_2d::LETHAL_OBSTACLE ||
cost == nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
{
response->is_valid = false;
}
}
}
}
rcl_interfaces::msg::SetParametersResult
PlannerServer::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
{
std::lock_guard<std::mutex> lock(dynamic_params_lock_);
rcl_interfaces::msg::SetParametersResult result;
for (auto parameter : parameters) {
const auto & type = parameter.get_type();
const auto & name = parameter.get_name();
if (type == ParameterType::PARAMETER_DOUBLE) {
if (name == "expected_planner_frequency") {
if (parameter.as_double() > 0) {
max_planner_duration_ = 1 / parameter.as_double();
} else {
RCLCPP_WARN(
get_logger(),
"The expected planner frequency parameter is %.4f Hz. The value should to be greater"
" than 0.0 to turn on duration overrrun warning messages", parameter.as_double());
max_planner_duration_ = 0.0;
}
}
}
}
result.successful = true;
return result;
}
void PlannerServer::exceptionWarning(
const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal,
const std::string & planner_id,
const std::exception & ex)
{
RCLCPP_WARN(
get_logger(), "%s plugin failed to plan from (%.2f, %.2f) to (%0.2f, %.2f): \"%s\"",
planner_id.c_str(),
start.pose.position.x, start.pose.position.y,
goal.pose.position.x, goal.pose.position.y,
ex.what());
}
} // namespace nav2_planner
#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_planner::PlannerServer)