Skip to content

Commit f1a5397

Browse files
[JTC] Remove deprecation warnings, set allow_nonzero_velocity_at_trajectory_end default false (#834)
1 parent 232154d commit f1a5397

7 files changed

+34
-53
lines changed

joint_trajectory_controller/doc/parameters.rst

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ start_with_holding (bool)
6666
allow_nonzero_velocity_at_trajectory_end (boolean)
6767
If false, the last velocity point has to be zero or the goal will be rejected.
6868

69-
Default: true
69+
Default: false
7070

7171
cmd_timeout (double)
7272
Timeout after which the input command is considered stale.
@@ -147,5 +147,4 @@ gains.<joint_name>.angle_wraparound (bool)
147147
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
148148
position :math:`s` from the state interface.
149149

150-
151150
Default: false

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -167,8 +167,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
167167
std::vector<PidPtr> pids_;
168168
// Feed-forward velocity weight factor when calculating closed loop pid adapter's command
169169
std::vector<double> ff_velocity_scale_;
170-
// Configuration for every joint, if position error is normalized
171-
std::vector<bool> normalize_joint_error_;
170+
// Configuration for every joint, if position error is wrapped around
171+
std::vector<bool> joints_angle_wraparound_;
172172
// reserved storage for result of the command when closed loop pid adapter is used
173173
std::vector<double> tmp_command_;
174174

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 3 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -64,15 +64,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_init()
6464
return CallbackReturn::ERROR;
6565
}
6666

67-
// TODO(christophfroehlich): remove deprecation warning
68-
if (params_.allow_nonzero_velocity_at_trajectory_end)
69-
{
70-
RCLCPP_WARN(
71-
get_node()->get_logger(),
72-
"[Deprecated]: \"allow_nonzero_velocity_at_trajectory_end\" is set to "
73-
"true. The default behavior will change to false.");
74-
}
75-
7667
return CallbackReturn::SUCCESS;
7768
}
7869

@@ -131,7 +122,7 @@ controller_interface::return_type JointTrajectoryController::update(
131122
const JointTrajectoryPoint & desired)
132123
{
133124
// error defined as the difference between current and desired
134-
if (normalize_joint_error_[index])
125+
if (joints_angle_wraparound_[index])
135126
{
136127
// if desired, the shortest_angular_distance is calculated, i.e., the error is
137128
// normalized between -pi<error<pi
@@ -725,20 +716,11 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
725716
}
726717

727718
// Configure joint position error normalization from ROS parameters (angle_wraparound)
728-
normalize_joint_error_.resize(dof_);
719+
joints_angle_wraparound_.resize(dof_);
729720
for (size_t i = 0; i < dof_; ++i)
730721
{
731722
const auto & gains = params_.gains.joints_map.at(params_.joints[i]);
732-
if (gains.normalize_error)
733-
{
734-
// TODO(anyone): Remove deprecation warning in the end of 2023
735-
RCLCPP_INFO(logger, "`normalize_error` is deprecated, use `angle_wraparound` instead!");
736-
normalize_joint_error_[i] = gains.normalize_error;
737-
}
738-
else
739-
{
740-
normalize_joint_error_[i] = gains.angle_wraparound;
741-
}
723+
joints_angle_wraparound_[i] = gains.angle_wraparound;
742724
}
743725

744726
if (params_.state_interfaces.empty())

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 1 addition & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ joint_trajectory_controller:
8080
}
8181
allow_nonzero_velocity_at_trajectory_end: {
8282
type: bool,
83-
default_value: true,
83+
default_value: false,
8484
description: "If false, the last velocity point has to be zero or the goal will be rejected",
8585
}
8686
cmd_timeout: {
@@ -118,11 +118,6 @@ joint_trajectory_controller:
118118
default_value: 0.0,
119119
description: "Feed-forward scaling of velocity."
120120
}
121-
normalize_error: {
122-
type: bool,
123-
default_value: false,
124-
description: "(Deprecated) Use position error normalization to -pi to pi."
125-
}
126121
angle_wraparound: {
127122
type: bool,
128123
default_value: false,

joint_trajectory_controller/test/test_trajectory_actions.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -653,7 +653,11 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_allow_nonzero_velocity_at_tr
653653

654654
// will be accepted despite nonzero last point
655655
EXPECT_TRUE(gh_future.get());
656-
EXPECT_EQ(rclcpp_action::ResultCode::SUCCEEDED, common_resultcode_);
656+
if ((traj_controller_->has_effort_command_interface()) == false)
657+
{
658+
// can't succeed with effort cmd if
659+
EXPECT_EQ(rclcpp_action::ResultCode::SUCCEEDED, common_resultcode_);
660+
}
657661
}
658662

659663
TEST_P(TestTrajectoryActionsTestParameterized, test_allow_nonzero_velocity_at_trajectory_end_false)

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 10 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -201,8 +201,7 @@ TEST_P(TrajectoryControllerTestParameterized, activate)
201201
TEST_P(TrajectoryControllerTestParameterized, cleanup)
202202
{
203203
rclcpp::executors::MultiThreadedExecutor executor;
204-
std::vector<rclcpp::Parameter> params = {
205-
rclcpp::Parameter("allow_nonzero_velocity_at_trajectory_end", true)};
204+
std::vector<rclcpp::Parameter> params = {};
206205
SetUpAndActivateTrajectoryController(executor, params);
207206

208207
// send msg
@@ -456,14 +455,13 @@ TEST_P(TrajectoryControllerTestParameterized, hold_on_startup)
456455
// Floating-point value comparison threshold
457456
const double EPS = 1e-6;
458457
/**
459-
* @brief check if position error of revolute joints are normalized if not configured so
458+
* @brief check if position error of revolute joints are angle_wraparound if not configured so
460459
*/
461-
TEST_P(TrajectoryControllerTestParameterized, position_error_not_normalized)
460+
TEST_P(TrajectoryControllerTestParameterized, position_error_not_angle_wraparound)
462461
{
463462
rclcpp::executors::MultiThreadedExecutor executor;
464463
constexpr double k_p = 10.0;
465-
std::vector<rclcpp::Parameter> params = {
466-
rclcpp::Parameter("allow_nonzero_velocity_at_trajectory_end", true)};
464+
std::vector<rclcpp::Parameter> params = {};
467465
SetUpAndActivateTrajectoryController(executor, params, true, k_p, 0.0, false);
468466
subscribeToState();
469467

@@ -706,14 +704,13 @@ TEST_P(TrajectoryControllerTestParameterized, timeout)
706704
}
707705

708706
/**
709-
* @brief check if position error of revolute joints are normalized if configured so
707+
* @brief check if position error of revolute joints are angle_wraparound if configured so
710708
*/
711-
TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
709+
TEST_P(TrajectoryControllerTestParameterized, position_error_angle_wraparound)
712710
{
713711
rclcpp::executors::MultiThreadedExecutor executor;
714712
constexpr double k_p = 10.0;
715-
std::vector<rclcpp::Parameter> params = {
716-
rclcpp::Parameter("allow_nonzero_velocity_at_trajectory_end", true)};
713+
std::vector<rclcpp::Parameter> params = {};
717714
SetUpAndActivateTrajectoryController(executor, params, true, k_p, 0.0, true);
718715
subscribeToState();
719716

@@ -754,7 +751,7 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
754751
EXPECT_NEAR(points[0][1], state_msg->reference.positions[1], allowed_delta);
755752
EXPECT_NEAR(points[0][2], state_msg->reference.positions[2], 3 * allowed_delta);
756753

757-
// is error.positions[2] normalized?
754+
// is error.positions[2] angle_wraparound?
758755
EXPECT_NEAR(
759756
state_msg->error.positions[0], state_msg->reference.positions[0] - INITIAL_POS_JOINTS[0], EPS);
760757
EXPECT_NEAR(
@@ -783,7 +780,7 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
783780
EXPECT_NEAR(
784781
k_p * (state_msg->reference.positions[1] - INITIAL_POS_JOINTS[1]), joint_vel_[1],
785782
k_p * allowed_delta);
786-
// is error of positions[2] normalized?
783+
// is error of positions[2] angle_wraparound?
787784
EXPECT_GT(0.0, joint_vel_[2]);
788785
EXPECT_NEAR(
789786
k_p * (state_msg->reference.positions[2] - INITIAL_POS_JOINTS[2] - 2 * M_PI), joint_vel_[2],
@@ -811,7 +808,7 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
811808
EXPECT_NEAR(
812809
k_p * (state_msg->reference.positions[1] - INITIAL_POS_JOINTS[1]), joint_eff_[1],
813810
k_p * allowed_delta);
814-
// is error of positions[2] normalized?
811+
// is error of positions[2] angle_wraparound?
815812
EXPECT_GT(0.0, joint_eff_[2]);
816813
EXPECT_NEAR(
817814
k_p * (state_msg->reference.positions[2] - INITIAL_POS_JOINTS[2] - 2 * M_PI), joint_eff_[2],

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -198,7 +198,7 @@ class TrajectoryControllerTest : public ::testing::Test
198198
}
199199

200200
void SetPidParameters(
201-
double p_default = 0.0, double ff_default = 1.0, bool normalize_error_default = false)
201+
double p_default = 0.0, double ff_default = 1.0, bool angle_wraparound_default = false)
202202
{
203203
traj_controller_->trigger_declare_parameters();
204204
auto node = traj_controller_->get_node();
@@ -211,27 +211,31 @@ class TrajectoryControllerTest : public ::testing::Test
211211
const rclcpp::Parameter k_d(prefix + ".d", 0.0);
212212
const rclcpp::Parameter i_clamp(prefix + ".i_clamp", 0.0);
213213
const rclcpp::Parameter ff_velocity_scale(prefix + ".ff_velocity_scale", ff_default);
214-
const rclcpp::Parameter normalize_error(prefix + ".normalize_error", normalize_error_default);
215-
node->set_parameters({k_p, k_i, k_d, i_clamp, ff_velocity_scale, normalize_error});
214+
const rclcpp::Parameter angle_wraparound(
215+
prefix + ".angle_wraparound", angle_wraparound_default);
216+
node->set_parameters({k_p, k_i, k_d, i_clamp, ff_velocity_scale, angle_wraparound});
216217
}
217218
}
218219

219220
void SetUpAndActivateTrajectoryController(
220221
rclcpp::Executor & executor, const std::vector<rclcpp::Parameter> & parameters = {},
221222
bool separate_cmd_and_state_values = false, double k_p = 0.0, double ff = 1.0,
222-
bool normalize_error = false)
223+
bool angle_wraparound = false)
223224
{
224225
SetUpTrajectoryController(executor);
225226

227+
// add this to simplify tests, can be overwritten by parameters
228+
rclcpp::Parameter nonzero_vel_parameter("allow_nonzero_velocity_at_trajectory_end", true);
229+
traj_controller_->get_node()->set_parameter(nonzero_vel_parameter);
230+
226231
// set pid parameters before configure
227-
SetPidParameters(k_p, ff, normalize_error);
232+
SetPidParameters(k_p, ff, angle_wraparound);
233+
234+
// set optional parameters
228235
for (const auto & param : parameters)
229236
{
230237
traj_controller_->get_node()->set_parameter(param);
231238
}
232-
// ignore velocity tolerances for this test since they aren't committed in test_robot->write()
233-
rclcpp::Parameter stopped_velocity_parameters("constraints.stopped_velocity_tolerance", 0.0);
234-
traj_controller_->get_node()->set_parameter(stopped_velocity_parameters);
235239

236240
traj_controller_->get_node()->configure();
237241

0 commit comments

Comments
 (0)