Skip to content

Commit

Permalink
feat(controller-server): publish_zero_velocity parameter (#4675)
Browse files Browse the repository at this point in the history
* feat(controller-server): `publish_zero_velocity` parameter

For optionally publishing a zero velocity command reference on goal
exit. Publishing a zero velocity is not desired when we are following
consecutive path segments that end with a velocity.

Signed-off-by: Rein Appeldoorn <[email protected]>

* processed comments

Signed-off-by: Rein Appeldoorn <[email protected]>

* comments Steve

Signed-off-by: Rein Appeldoorn <[email protected]>

---------

Signed-off-by: Rein Appeldoorn <[email protected]>
  • Loading branch information
reinzor committed Sep 20, 2024
1 parent d4c3faa commit 5dd7ad1
Show file tree
Hide file tree
Showing 2 changed files with 25 additions and 11 deletions.
5 changes: 5 additions & 0 deletions nav2_controller/include/nav2_controller/controller_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,6 +176,10 @@ class ControllerServer : public nav2_util::LifecycleNode
* @brief Calls velocity publisher to publish zero velocity
*/
void publishZeroVelocity();
/**
* @brief Called on goal exit
*/
void onGoalExit();
/**
* @brief Checks if goal is reached
* @return true or false
Expand Down Expand Up @@ -267,6 +271,7 @@ class ControllerServer : public nav2_util::LifecycleNode

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

// Whether we've published the single controller warning yet
Expand Down
31 changes: 20 additions & 11 deletions nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)

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
Expand Down Expand Up @@ -130,6 +131,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
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
Expand Down Expand Up @@ -476,7 +478,7 @@ void ControllerServer::computeControl()
if (controllers_[current_controller_]->cancel()) {
RCLCPP_INFO(get_logger(), "Cancellation was successful. Stopping the robot.");
action_server_->terminate_all();
publishZeroVelocity();
onGoalExit();
return;
} else {
RCLCPP_INFO_THROTTLE(
Expand Down Expand Up @@ -513,63 +515,63 @@ void ControllerServer::computeControl()
}
} catch (nav2_core::InvalidController & e) {
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
publishZeroVelocity();
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());
publishZeroVelocity();
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());
publishZeroVelocity();
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());
publishZeroVelocity();
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());
publishZeroVelocity();
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());
publishZeroVelocity();
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());
publishZeroVelocity();
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());
publishZeroVelocity();
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());
publishZeroVelocity();
onGoalExit();
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::UNKNOWN;
action_server_->terminate_current(result);
Expand All @@ -578,7 +580,7 @@ void ControllerServer::computeControl()

RCLCPP_DEBUG(get_logger(), "Controller succeeded, setting result");

publishZeroVelocity();
onGoalExit();

// TODO(orduno) #861 Handle a pending preemption and set controller name
action_server_->succeeded_current();
Expand Down Expand Up @@ -746,6 +748,13 @@ void ControllerServer::publishZeroVelocity()
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;
Expand Down

0 comments on commit 5dd7ad1

Please sign in to comment.