Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding planner server timeout for costmap waiting #4673

Merged
merged 2 commits into from
Sep 12, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ bt_navigator:
controller_server:
ros__parameters:
controller_frequency: 20.0
costmap_update_timeout: 0.30
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
Expand Down Expand Up @@ -198,6 +199,7 @@ map_server:
planner_server:
ros__parameters:
planner_plugins: ["GridBased"]
costmap_update_timeout: 1.0
GridBased:
plugin: "nav2_navfn_planner::NavfnPlanner"
tolerance: 0.5
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ bt_navigator:
controller_server:
ros__parameters:
controller_frequency: 20.0
costmap_update_timeout: 0.30
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
Expand Down Expand Up @@ -197,6 +198,7 @@ map_server:
planner_server:
ros__parameters:
planner_plugins: ["GridBased"]
costmap_update_timeout: 1.0
GridBased:
plugin: "nav2_navfn_planner::NavfnPlanner"
tolerance: 0.5
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_multirobot_params_all.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ bt_navigator:
controller_server:
ros__parameters:
controller_frequency: 20.0
costmap_update_timeout: 0.30
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
Expand Down Expand Up @@ -230,6 +231,7 @@ map_saver:
planner_server:
ros__parameters:
expected_planner_frequency: 20.0
costmap_update_timeout: 1.0
planner_plugins: ["GridBased"]
GridBased:
plugin: "nav2_navfn_planner::NavfnPlanner"
Expand Down
2 changes: 2 additions & 0 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ bt_navigator:
controller_server:
ros__parameters:
controller_frequency: 20.0
costmap_update_timeout: 0.30
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
Expand Down Expand Up @@ -276,6 +277,7 @@ planner_server:
ros__parameters:
expected_planner_frequency: 20.0
planner_plugins: ["GridBased"]
costmap_update_timeout: 1.0
GridBased:
plugin: "nav2_navfn_planner::NavfnPlanner"
tolerance: 0.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -267,6 +267,7 @@ class ControllerServer : public nav2_util::LifecycleNode

double failure_tolerance_;
bool use_realtime_priority_;
rclcpp::Duration costmap_update_timeout_;

// Whether we've published the single controller warning yet
geometry_msgs::msg::PoseStamped end_pose_;
Expand Down
19 changes: 18 additions & 1 deletion nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,8 @@
default_goal_checker_types_{"nav2_controller::SimpleGoalChecker"},
lp_loader_("nav2_core", "nav2_core::Controller"),
default_ids_{"FollowPath"},
default_types_{"dwb_core::DWBLocalPlanner"}
default_types_{"dwb_core::DWBLocalPlanner"},
costmap_update_timeout_(300ms)
{
RCLCPP_INFO(get_logger(), "Creating controller server");

Expand All @@ -63,6 +64,7 @@

declare_parameter("failure_tolerance", rclcpp::ParameterValue(0.0));
declare_parameter("use_realtime_priority", rclcpp::ParameterValue(false));
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>(
Expand Down Expand Up @@ -222,6 +224,10 @@
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 {
Expand Down Expand Up @@ -480,7 +486,11 @@

// 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");

Check warning on line 492 in nav2_controller/src/controller_server.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_controller/src/controller_server.cpp#L491-L492

Added lines #L491 - L492 were not covered by tests
}
r.sleep();
}

Expand Down Expand Up @@ -543,6 +553,13 @@
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());
publishZeroVelocity();

Check warning on line 558 in nav2_controller/src/controller_server.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_controller/src/controller_server.cpp#L557-L558

Added lines #L557 - L558 were not covered by tests
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::CONTROLLER_TIMED_OUT;
action_server_->terminate_current(result);

Check warning on line 561 in nav2_controller/src/controller_server.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_controller/src/controller_server.cpp#L560-L561

Added lines #L560 - L561 were not covered by tests
return;
} catch (nav2_core::ControllerException & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
publishZeroVelocity();
Expand Down
7 changes: 7 additions & 0 deletions nav2_core/include/nav2_core/controller_exceptions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,13 @@
: ControllerException(description) {}
};

class ControllerTimedOut : public ControllerException
{
public:
explicit ControllerTimedOut(const std::string & description)
: ControllerException(description) {}

Check warning on line 76 in nav2_core/include/nav2_core/controller_exceptions.hpp

View check run for this annotation

Codecov / codecov/patch

nav2_core/include/nav2_core/controller_exceptions.hpp#L76

Added line #L76 was not covered by tests
};

} // namespace nav2_core

#endif // NAV2_CORE__CONTROLLER_EXCEPTIONS_HPP_
1 change: 1 addition & 0 deletions nav2_msgs/action/FollowPath.action
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ uint16 INVALID_PATH=103
uint16 PATIENCE_EXCEEDED=104
uint16 FAILED_TO_MAKE_PROGRESS=105
uint16 NO_VALID_CONTROL=106
uint16 CONTROLLER_TIMED_OUT=107

std_msgs/Empty result
uint16 error_code
Expand Down
1 change: 1 addition & 0 deletions nav2_planner/include/nav2_planner/planner_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -242,6 +242,7 @@ class PlannerServer : public nav2_util::LifecycleNode
std::vector<std::string> planner_ids_;
std::vector<std::string> planner_types_;
double max_planner_duration_;
rclcpp::Duration costmap_update_timeout_;
std::string planner_ids_concat_;

// TF buffer
Expand Down
10 changes: 10 additions & 0 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
gp_loader_("nav2_core", "nav2_core::GlobalPlanner"),
default_ids_{"GridBased"},
default_types_{"nav2_navfn_planner::NavfnPlanner"},
costmap_update_timeout_(1s),
costmap_(nullptr)
{
RCLCPP_INFO(get_logger(), "Creating");
Expand All @@ -52,6 +53,7 @@
declare_parameter("planner_plugins", default_ids_);
declare_parameter("expected_planner_frequency", 1.0);
declare_parameter("action_server_result_timeout", 10.0);
declare_parameter("costmap_update_timeout", 1.0);

get_parameter("planner_plugins", planner_ids_);
if (planner_ids_ == default_ids_) {
Expand Down Expand Up @@ -150,6 +152,10 @@
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 servers for path planning to a pose and through poses
action_server_pose_ = std::make_unique<ActionServerToPose>(
shared_from_this(),
Expand Down Expand Up @@ -283,7 +289,11 @@
{
// Don't compute a plan 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::PlannerTimedOut("Costmap timed out waiting for update");

Check warning on line 295 in nav2_planner/src/planner_server.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_planner/src/planner_server.cpp#L294-L295

Added lines #L294 - L295 were not covered by tests
}
r.sleep();
}
}
Expand Down
Loading