Skip to content
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
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();
/**
Comment thread
SteveMacenski marked this conversation as 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
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();
Comment thread
reinzor marked this conversation as resolved.
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();
}
Comment thread
SteveMacenski marked this conversation as resolved.

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