Skip to content

Commit e40c825

Browse files
jwallace42MartiBoletAlexeyMerzlyakovstevedanomodolor
authored andcommitted
Smoother error codes (ros-navigation#3296)
* minimum error code set * test for invalid smoother * undo * added rest of error tests * Solve bug when CostmapInfoServer is reactivated (ros-navigation#3292) * Solve bug when CostmapInfoServer is reactivated * Smoothness metrics update (ros-navigation#3294) * Update metrics for path smoothness * Support Savitzky-Golay smoother * preempt/cancel test for time behavior, spin pluguin (ros-navigation#3301) * include preempt/cancel test for time behavior, spin pluguin * linting * fix bug in code * removed changes to simple_smoother * reverted simple_smoother * revert * revert * updated constrained smoother * revert * added smoother error for invalid path * linting * invalid path test * added error codes * Timeout exception thrown by smoothers * code review Co-authored-by: Joshua Wallace <josho.wallace.com> Co-authored-by: MartiBolet <[email protected]> Co-authored-by: Alexey Merzlyakov <[email protected]> Co-authored-by: Stevedan Ogochukwu Omodolor <[email protected]>
1 parent bb21242 commit e40c825

File tree

21 files changed

+429
-42
lines changed

21 files changed

+429
-42
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/smooth_path_action.hpp

Lines changed: 22 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,10 @@ namespace nav2_behavior_tree
3030
*/
3131
class SmoothPathAction : public nav2_behavior_tree::BtActionNode<nav2_msgs::action::SmoothPath>
3232
{
33+
using Action = nav2_msgs::action::SmoothPath;
34+
using ActionResult = Action::Result;
35+
using ActionGoal = Action::Goal;
36+
3337
public:
3438
/**
3539
* @brief A constructor for nav2_behavior_tree::SmoothPathAction
@@ -52,6 +56,16 @@ class SmoothPathAction : public nav2_behavior_tree::BtActionNode<nav2_msgs::acti
5256
*/
5357
BT::NodeStatus on_success() override;
5458

59+
/**
60+
* @brief Function to perform some user-defined operation upon abortion of the action
61+
*/
62+
BT::NodeStatus on_aborted() override;
63+
64+
/**
65+
* @brief Function to perform some user-defined operation upon cancellation of the action
66+
*/
67+
BT::NodeStatus on_cancelled() override;
68+
5569
/**
5670
* @brief Creates list of BT ports
5771
* @return BT::PortsList Containing basic ports along with node-specific ports
@@ -60,18 +74,20 @@ class SmoothPathAction : public nav2_behavior_tree::BtActionNode<nav2_msgs::acti
6074
{
6175
return providedBasicPorts(
6276
{
63-
BT::OutputPort<nav_msgs::msg::Path>(
64-
"smoothed_path",
65-
"Path smoothed by SmootherServer node"),
66-
BT::OutputPort<double>("smoothing_duration", "Time taken to smooth path"),
67-
BT::OutputPort<bool>(
68-
"was_completed", "True if smoothing was not interrupted by time limit"),
6977
BT::InputPort<nav_msgs::msg::Path>("unsmoothed_path", "Path to be smoothed"),
7078
BT::InputPort<double>("max_smoothing_duration", 3.0, "Maximum smoothing duration"),
7179
BT::InputPort<bool>(
7280
"check_for_collisions", false,
7381
"If true collision check will be performed after smoothing"),
7482
BT::InputPort<std::string>("smoother_id", ""),
83+
BT::OutputPort<nav_msgs::msg::Path>(
84+
"smoothed_path",
85+
"Path smoothed by SmootherServer node"),
86+
BT::OutputPort<double>("smoothing_duration", "Time taken to smooth path"),
87+
BT::OutputPort<bool>(
88+
"was_completed", "True if smoothing was not interrupted by time limit"),
89+
BT::OutputPort<ActionResult::_error_code_type>(
90+
"error_code_id", "The smooth path error code"),
7591
});
7692
}
7793
};

nav2_behavior_tree/plugins/action/smooth_path_action.cpp

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,21 @@ BT::NodeStatus SmoothPathAction::on_success()
4444
setOutput("smoothed_path", result_.result->path);
4545
setOutput("smoothing_duration", rclcpp::Duration(result_.result->smoothing_duration).seconds());
4646
setOutput("was_completed", result_.result->was_completed);
47+
// Set empty error code, action was successful
48+
setOutput("error_code_id", ActionGoal::NONE);
49+
return BT::NodeStatus::SUCCESS;
50+
}
51+
52+
BT::NodeStatus SmoothPathAction::on_aborted()
53+
{
54+
setOutput("error_code_id", result_.result->error_code);
55+
return BT::NodeStatus::FAILURE;
56+
}
57+
58+
BT::NodeStatus SmoothPathAction::on_cancelled()
59+
{
60+
// Set empty error code, action was cancelled
61+
setOutput("error_code_id", ActionGoal::NONE);
4762
return BT::NodeStatus::SUCCESS;
4863
}
4964

nav2_constrained_smoother/include/nav2_constrained_smoother/smoother.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828

2929
#include "nav2_constrained_smoother/smoother_cost_function.hpp"
3030
#include "nav2_constrained_smoother/utils.hpp"
31+
#include "nav2_core/smoother_exceptions.hpp"
3132

3233
#include "ceres/ceres.h"
3334
#include "Eigen/Core"
@@ -94,7 +95,7 @@ class Smoother
9495
{
9596
// Path has always at least 2 points
9697
if (path.size() < 2) {
97-
throw std::runtime_error("Constrained smoother: Path must have at least 2 points");
98+
throw nav2_core::InvalidPath("Constrained smoother: Path must have at least 2 points");
9899
}
99100

100101
options_.max_solver_time_in_seconds = params.max_time;
@@ -110,7 +111,7 @@ class Smoother
110111
RCLCPP_INFO(rclcpp::get_logger("smoother_server"), "%s", summary.FullReport().c_str());
111112
}
112113
if (!summary.IsSolutionUsable() || summary.initial_cost - summary.final_cost < 0.0) {
113-
return false;
114+
throw nav2_core::FailedToSmoothPath("Solution is not usable");
114115
}
115116
} else {
116117
RCLCPP_INFO(rclcpp::get_logger("smoother_server"), "Path too short to optimize");

nav2_constrained_smoother/src/constrained_smoother.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
#include "nav2_constrained_smoother/constrained_smoother.hpp"
2424
#include "nav2_util/node_utils.hpp"
2525
#include "nav2_util/geometry_utils.hpp"
26-
#include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
26+
#include "nav2_core/smoother_exceptions.hpp"
2727

2828
#include "pluginlib/class_loader.hpp"
2929
#include "pluginlib/class_list_macros.hpp"
@@ -137,8 +137,8 @@ bool ConstrainedSmoother::smooth(nav_msgs::msg::Path & path, const rclcpp::Durat
137137
logger_,
138138
"%s: failed to smooth plan, Ceres could not find a usable solution to optimize.",
139139
plugin_name_.c_str());
140-
throw std::runtime_error(
141-
"Failed to smooth plan, Ceres could not find a usable solution.");
140+
throw nav2_core::FailedToSmoothPath(
141+
"Failed to smooth plan, Ceres could not find a usable solution");
142142
}
143143

144144
// populate final path
Lines changed: 67 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,67 @@
1+
// Copyright (c) 2022 Joshua Wallace
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_CORE__SMOOTHER_EXCEPTIONS_HPP_
16+
#define NAV2_CORE__SMOOTHER_EXCEPTIONS_HPP_
17+
18+
#include <stdexcept>
19+
#include <string>
20+
21+
namespace nav2_core
22+
{
23+
24+
class SmootherException : public std::runtime_error
25+
{
26+
public:
27+
explicit SmootherException(const std::string & description)
28+
: std::runtime_error(description) {}
29+
};
30+
31+
class InvalidSmoother : public SmootherException
32+
{
33+
public:
34+
explicit InvalidSmoother(const std::string & description)
35+
: SmootherException(description) {}
36+
};
37+
38+
class InvalidPath : public SmootherException
39+
{
40+
public:
41+
explicit InvalidPath(const std::string & description)
42+
: SmootherException(description) {}
43+
};
44+
45+
class SmootherTimedOut : public SmootherException
46+
{
47+
public:
48+
explicit SmootherTimedOut(const std::string & description)
49+
: SmootherException(description) {}
50+
};
51+
52+
class SmoothedPathInCollision : public SmootherException
53+
{
54+
public:
55+
explicit SmoothedPathInCollision(const std::string & description)
56+
: SmootherException(description) {}
57+
};
58+
59+
class FailedToSmoothPath : public SmootherException
60+
{
61+
public:
62+
explicit FailedToSmoothPath(const std::string & description)
63+
: SmootherException(description) {}
64+
};
65+
66+
} // namespace nav2_core
67+
#endif // NAV2_CORE__SMOOTHER_EXCEPTIONS_HPP_

nav2_msgs/action/SmoothPath.action

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,13 @@
1+
# Error codes
2+
# Note: The expected priority order of the errors should match the message order
3+
uint16 NONE=0
4+
uint16 UNKNOWN=500
5+
uint16 INVALID_SMOOTHER=501
6+
uint16 TIMEOUT=502
7+
uint16 SMOOTHED_PATH_IN_COLLISION=503
8+
uint16 FAILED_TO_SMOOTH_PATH=504
9+
uint16 INVALID_PATH=505
10+
111
#goal definition
212
nav_msgs/Path path
313
string smoother_id
@@ -8,5 +18,6 @@ bool check_for_collisions
818
nav_msgs/Path path
919
builtin_interfaces/Duration smoothing_duration
1020
bool was_completed
21+
uint16 error_code
1122
---
1223
#feedback definition

nav2_simple_commander/nav2_simple_commander/robot_navigator.py

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -433,16 +433,18 @@ def _smoothPathImpl(self, path, smoother_id='', max_duration=2.0, check_for_coll
433433
self.result_future = self.goal_handle.get_result_async()
434434
rclpy.spin_until_future_complete(self, self.result_future)
435435
self.status = self.result_future.result().status
436-
if self.status != GoalStatus.STATUS_SUCCEEDED:
437-
self.warn(f'Getting path failed with status code: {self.status}')
438-
return None
439436

440437
return self.result_future.result().result
441438

442439
def smoothPath(self, path, smoother_id='', max_duration=2.0, check_for_collision=False):
443440
"""Send a `SmoothPath` action request."""
444441
rtn = self._smoothPathImpl(
445-
self, path, smoother_id='', max_duration=2.0, check_for_collision=False)
442+
path, smoother_id='', max_duration=2.0, check_for_collision=False)
443+
444+
if self.status != GoalStatus.STATUS_SUCCEEDED:
445+
self.warn(f'Getting path failed with status code: {self.status}')
446+
return None
447+
446448
if not rtn:
447449
return None
448450
else:

nav2_smoother/include/nav2_smoother/nav2_smoother.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -114,6 +114,7 @@ class SmootherServer : public nav2_util::LifecycleNode
114114
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
115115

116116
using Action = nav2_msgs::action::SmoothPath;
117+
using ActionGoal = Action::Goal;
117118
using ActionServer = nav2_util::SimpleActionServer<Action>;
118119

119120
/**
@@ -135,6 +136,13 @@ class SmootherServer : public nav2_util::LifecycleNode
135136
*/
136137
bool findSmootherId(const std::string & c_name, std::string & name);
137138

139+
/**
140+
* @brief Validate that the path contains a meaningful path for smoothing
141+
* @param path current path
142+
* return bool if the path is valid
143+
*/
144+
bool validate(const nav_msgs::msg::Path & path);
145+
138146
// Our action server implements the SmoothPath action
139147
std::unique_ptr<ActionServer> action_server_;
140148

nav2_smoother/src/nav2_smoother.cpp

Lines changed: 53 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
#include <utility>
2121
#include <vector>
2222

23-
#include "nav2_core/planner_exceptions.hpp"
23+
#include "nav2_core/smoother_exceptions.hpp"
2424
#include "nav2_smoother/nav2_smoother.hpp"
2525
#include "nav2_util/node_utils.hpp"
2626
#include "nav_2d_utils/conversions.hpp"
@@ -263,13 +263,17 @@ void SmootherServer::smoothPlan()
263263
if (findSmootherId(c_name, current_smoother)) {
264264
current_smoother_ = current_smoother;
265265
} else {
266-
action_server_->terminate_current();
267-
return;
266+
throw nav2_core::InvalidSmoother("Invalid Smoother: " + c_name);
268267
}
269268

270269
// Perform smoothing
271270
auto goal = action_server_->get_current_goal();
272271
result->path = goal->path;
272+
273+
if (!validate(result->path)) {
274+
throw nav2_core::InvalidPath("Requested path to smooth is invalid");
275+
}
276+
273277
result->was_completed = smoothers_[current_smoother_]->smooth(
274278
result->path, goal->max_smoothing_duration);
275279
result->smoothing_duration = steady_clock_.now() - start_time;
@@ -283,6 +287,7 @@ void SmootherServer::smoothPlan()
283287
rclcpp::Duration(goal->max_smoothing_duration).seconds(),
284288
rclcpp::Duration(result->smoothing_duration).seconds());
285289
}
290+
286291
plan_publisher_->publish(result->path);
287292

288293
// Check for collisions
@@ -299,8 +304,11 @@ void SmootherServer::smoothPlan()
299304
get_logger(),
300305
"Smoothed path leads to a collision at x: %lf, y: %lf, theta: %lf",
301306
pose2d.x, pose2d.y, pose2d.theta);
302-
action_server_->terminate_current(result);
303-
return;
307+
throw nav2_core::SmoothedPathInCollision(
308+
"Smoothed Path collided at"
309+
"X: " + std::to_string(pose2d.x) +
310+
"Y: " + std::to_string(pose2d.y) +
311+
"Theta: " + std::to_string(pose2d.theta));
304312
}
305313
fetch_data = false;
306314
}
@@ -311,13 +319,50 @@ void SmootherServer::smoothPlan()
311319
rclcpp::Duration(result->smoothing_duration).seconds());
312320

313321
action_server_->succeeded_current(result);
314-
} catch (nav2_core::PlannerException & e) {
315-
RCLCPP_ERROR(this->get_logger(), e.what());
316-
action_server_->terminate_current();
322+
} catch (nav2_core::InvalidSmoother & ex) {
323+
RCLCPP_ERROR(this->get_logger(), "%s", ex.what());
324+
result->error_code = ActionGoal::INVALID_SMOOTHER;
325+
action_server_->terminate_current(result);
326+
return;
327+
} catch (nav2_core::SmootherTimedOut & ex) {
328+
RCLCPP_ERROR(this->get_logger(), "%s", ex.what());
329+
result->error_code = ActionGoal::TIMEOUT;
330+
action_server_->terminate_current(result);
331+
return;
332+
} catch (nav2_core::SmoothedPathInCollision & ex) {
333+
RCLCPP_ERROR(this->get_logger(), "%s", ex.what());
334+
result->error_code = ActionGoal::SMOOTHED_PATH_IN_COLLISION;
335+
action_server_->terminate_current(result);
336+
return;
337+
} catch (nav2_core::FailedToSmoothPath & ex) {
338+
RCLCPP_ERROR(this->get_logger(), "%s", ex.what());
339+
result->error_code = ActionGoal::FAILED_TO_SMOOTH_PATH;
340+
action_server_->terminate_current(result);
341+
return;
342+
} catch (nav2_core::InvalidPath & ex) {
343+
RCLCPP_ERROR(this->get_logger(), "%s", ex.what());
344+
result->error_code = ActionGoal::INVALID_PATH;
345+
action_server_->terminate_current(result);
346+
return;
347+
} catch (nav2_core::SmootherException & ex) {
348+
RCLCPP_ERROR(this->get_logger(), "%s", ex.what());
349+
result->error_code = ActionGoal::UNKNOWN;
350+
action_server_->terminate_current(result);
317351
return;
318352
}
319353
}
320354

355+
bool SmootherServer::validate(const nav_msgs::msg::Path & path)
356+
{
357+
if (path.poses.empty()) {
358+
RCLCPP_WARN(get_logger(), "Requested path to smooth is empty");
359+
return false;
360+
}
361+
362+
RCLCPP_DEBUG(get_logger(), "Requested path to smooth is valid");
363+
return true;
364+
}
365+
321366
} // namespace nav2_smoother
322367

323368
#include "rclcpp_components/register_node_macro.hpp"

nav2_smoother/src/savitzky_golay_smoother.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include <vector>
1616
#include <memory>
1717
#include "nav2_smoother/savitzky_golay_smoother.hpp"
18+
#include "nav2_core/smoother_exceptions.hpp"
1819

1920
namespace nav2_smoother
2021
{
@@ -71,7 +72,7 @@ bool SavitzkyGolaySmoother::smooth(
7172
RCLCPP_WARN(
7273
logger_,
7374
"Smoothing time exceeded allowed duration of %0.2f.", max_time.seconds());
74-
return false;
75+
throw nav2_core::SmootherTimedOut("Smoothing time exceed allowed duration");
7576
}
7677

7778
// Smooth path segment

0 commit comments

Comments
 (0)