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

feat(controller-server): publish_zero_velocity parameter #4675

Merged
Merged
Show file tree
Hide file tree
Changes from 3 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
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();
/**
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
* @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
32 changes: 22 additions & 10 deletions nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@

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 @@
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 @@ -299,6 +301,9 @@
costmap_ros_->deactivate();

publishZeroVelocity();
for (auto & controller : controllers_) {
reinzor marked this conversation as resolved.
Show resolved Hide resolved
controller.second->reset();
}
vel_publisher_->on_deactivate();

remove_on_set_parameters_callback(dyn_params_handler_.get());
Expand Down Expand Up @@ -476,7 +481,7 @@
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,42 +518,42 @@
}
} 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();
reinzor marked this conversation as resolved.
Show resolved Hide resolved
std::shared_ptr<Action::Result> result = std::make_shared<Action::Result>();
result->error_code = Action::Result::INVALID_PATH;
action_server_->terminate_current(result);
Expand All @@ -562,14 +567,14 @@
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();

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

View check run for this annotation

Codecov / codecov/patch

nav2_controller/src/controller_server.cpp#L577

Added line #L577 was not covered by tests
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 +583,7 @@

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 +751,13 @@
velocity.header.frame_id = costmap_ros_->getBaseFrameID();
velocity.header.stamp = now();
publishVelocity(velocity);
}

void ControllerServer::onGoalExit()
{
if (publish_zero_velocity_) {
publishZeroVelocity();
}
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved

// Reset the state of the controllers after the task has ended
ControllerMap::iterator it;
Expand Down
Loading