From 061a8e17bc6b835633ac272621063be76c147137 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Fri, 17 Nov 2023 09:52:35 +0000 Subject: [PATCH] Set `allow_nonzero_velocity_at_trajectory_end` default false --- joint_trajectory_controller/doc/parameters.rst | 3 +-- .../src/joint_trajectory_controller.cpp | 9 --------- .../src/joint_trajectory_controller_parameters.yaml | 2 +- 3 files changed, 2 insertions(+), 12 deletions(-) diff --git a/joint_trajectory_controller/doc/parameters.rst b/joint_trajectory_controller/doc/parameters.rst index 95a6599191..8ad2b406d6 100644 --- a/joint_trajectory_controller/doc/parameters.rst +++ b/joint_trajectory_controller/doc/parameters.rst @@ -66,7 +66,7 @@ start_with_holding (bool) allow_nonzero_velocity_at_trajectory_end (boolean) If false, the last velocity point has to be zero or the goal will be rejected. - Default: true + Default: false cmd_timeout (double) Timeout after which the input command is considered stale. @@ -147,5 +147,4 @@ gains..angle_wraparound (bool) Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured position :math:`s` from the state interface. - Default: false diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index e527a76307..c01e4ac587 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -64,15 +64,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_init() return CallbackReturn::ERROR; } - // TODO(christophfroehlich): remove deprecation warning - if (params_.allow_nonzero_velocity_at_trajectory_end) - { - RCLCPP_WARN( - get_node()->get_logger(), - "[Deprecated]: \"allow_nonzero_velocity_at_trajectory_end\" is set to " - "true. The default behavior will change to false."); - } - return CallbackReturn::SUCCESS; } diff --git a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml index ce17ba8bf9..ca6900acb5 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -80,7 +80,7 @@ joint_trajectory_controller: } allow_nonzero_velocity_at_trajectory_end: { type: bool, - default_value: true, + default_value: false, description: "If false, the last velocity point has to be zero or the goal will be rejected", } cmd_timeout: {