Skip to content

Commit ef1330f

Browse files
feat(controller-server): publish_zero_velocity parameter jazzy backport (#4687)
* feat(controller-server): `publish_zero_velocity` parameter (#4675) Backport of #4675 Signed-off-by: Rein Appeldoorn <rein.appeldoorn@nobleo.nl> * Update nav2_controller/src/controller_server.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: Rein Appeldoorn <reinzor@gmail.com> --------- Signed-off-by: Rein Appeldoorn <rein.appeldoorn@nobleo.nl> Signed-off-by: Rein Appeldoorn <reinzor@gmail.com> Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>
1 parent 9f64098 commit ef1330f

File tree

1 file changed

+25
-11
lines changed

1 file changed

+25
-11
lines changed

‎nav2_controller/src/controller_server.cpp‎

Lines changed: 25 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
6363

6464
declare_parameter("failure_tolerance", rclcpp::ParameterValue(0.0));
6565
declare_parameter("use_realtime_priority", rclcpp::ParameterValue(false));
66+
declare_parameter("publish_zero_velocity", rclcpp::ParameterValue(true));
6667

6768
// The costmap node is used in the implementation of the controller
6869
costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
@@ -292,7 +293,18 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
292293
*/
293294
costmap_ros_->deactivate();
294295

295-
publishZeroVelocity();
296+
// Always publish a zero velocity when deactivating the controller server
297+
geometry_msgs::msg::TwistStamped velocity;
298+
velocity.twist.angular.x = 0;
299+
velocity.twist.angular.y = 0;
300+
velocity.twist.angular.z = 0;
301+
velocity.twist.linear.x = 0;
302+
velocity.twist.linear.y = 0;
303+
velocity.twist.linear.z = 0;
304+
velocity.header.frame_id = costmap_ros_->getBaseFrameID();
305+
velocity.header.stamp = now();
306+
publishVelocity(velocity);
307+
296308
vel_publisher_->on_deactivate();
297309

298310
remove_on_set_parameters_callback(dyn_params_handler_.get());
@@ -719,16 +731,18 @@ void ControllerServer::publishVelocity(const geometry_msgs::msg::TwistStamped &
719731

720732
void ControllerServer::publishZeroVelocity()
721733
{
722-
geometry_msgs::msg::TwistStamped velocity;
723-
velocity.twist.angular.x = 0;
724-
velocity.twist.angular.y = 0;
725-
velocity.twist.angular.z = 0;
726-
velocity.twist.linear.x = 0;
727-
velocity.twist.linear.y = 0;
728-
velocity.twist.linear.z = 0;
729-
velocity.header.frame_id = costmap_ros_->getBaseFrameID();
730-
velocity.header.stamp = now();
731-
publishVelocity(velocity);
734+
if (get_parameter("publish_zero_velocity").as_bool()) {
735+
geometry_msgs::msg::TwistStamped velocity;
736+
velocity.twist.angular.x = 0;
737+
velocity.twist.angular.y = 0;
738+
velocity.twist.angular.z = 0;
739+
velocity.twist.linear.x = 0;
740+
velocity.twist.linear.y = 0;
741+
velocity.twist.linear.z = 0;
742+
velocity.header.frame_id = costmap_ros_->getBaseFrameID();
743+
velocity.header.stamp = now();
744+
publishVelocity(velocity);
745+
}
732746

733747
// Reset the state of the controllers after the task has ended
734748
ControllerMap::iterator it;

0 commit comments

Comments
 (0)