From c696df066fdaabd93ade134f71dd02bb6ca9cc1e Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 13 Mar 2024 22:08:13 +0000 Subject: [PATCH] Deprecate start with holding --- .../src/joint_trajectory_controller.cpp | 8 ++++++++ .../src/joint_trajectory_controller_parameters.yaml | 2 +- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index c50180ee01..561fd903ac 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -930,6 +930,14 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( { add_new_trajectory_msg(set_hold_position()); } + else + { + RCLCPP_WARN( + get_node()->get_logger(), + "Parameter \"start_with_holding\" is deprecated. " + "It will be removed in a future release and start with holding position will be the default " + "behavior."); + } rt_is_holding_.writeFromNonRT(true); // parse timeout parameter diff --git a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml index 083b362ab7..44330557c4 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -85,7 +85,7 @@ joint_trajectory_controller: start_with_holding: { type: bool, default_value: true, - description: "If true, start with holding position after activation. Otherwise, no command will be sent until the first trajectory is received.", + description: "(Deprecated) If true, start with holding position after activation. Otherwise, no command will be sent until the first trajectory is received.", } allow_nonzero_velocity_at_trajectory_end: { type: bool,