From 1d6a3553a103afa59e381ac79a084b79512ee8ec Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Thu, 21 Mar 2024 07:25:50 +0100 Subject: [PATCH] Deprecate start with holding (#1076) (cherry picked from commit ea667556f73478c62f6b46337e007dc28ad25184) # Conflicts: # joint_trajectory_controller/src/joint_trajectory_controller.cpp # joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml --- .../src/joint_trajectory_controller.cpp | 16 ++++++++++++++++ .../joint_trajectory_controller_parameters.yaml | 8 ++++++++ 2 files changed, 24 insertions(+) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 9e450d0750..47febcb045 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -1002,8 +1002,24 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( read_state_from_state_interfaces(last_commanded_state_); } +<<<<<<< HEAD // The controller should start by holding position at the beginning of active state add_new_trajectory_msg(set_hold_position()); +======= + // Should the controller start by holding position at the beginning of active state? + if (params_.start_with_holding) + { + 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."); + } +>>>>>>> ea66755 (Deprecate start with holding (#1076)) 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 6fea36752c..048fda8f93 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -90,6 +90,14 @@ joint_trajectory_controller: one_of<>: [["splines", "none"]], } } +<<<<<<< HEAD +======= + start_with_holding: { + type: bool, + default_value: true, + description: "(Deprecated) If true, start with holding position after activation. Otherwise, no command will be sent until the first trajectory is received.", + } +>>>>>>> ea66755 (Deprecate start with holding (#1076)) allow_nonzero_velocity_at_trajectory_end: { type: bool, default_value: true,