Skip to content

Commit 3e0fd9e

Browse files
[JTC] Set allow_nonzero_velocity_at_trajectory_end default false and rename class variables (backport #834) (#843)
1 parent 383d049 commit 3e0fd9e

File tree

7 files changed

+38
-34
lines changed

7 files changed

+38
-34
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: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -65,12 +65,12 @@ controller_interface::CallbackReturn JointTrajectoryController::on_init()
6565
}
6666

6767
// TODO(christophfroehlich): remove deprecation warning
68-
if (params_.allow_nonzero_velocity_at_trajectory_end)
68+
if (params_.allow_nonzero_velocity_at_trajectory_end == false)
6969
{
7070
RCLCPP_WARN(
7171
get_node()->get_logger(),
72-
"[Deprecated]: \"allow_nonzero_velocity_at_trajectory_end\" is set to "
73-
"true. The default behavior will change to false.");
72+
"\"allow_nonzero_velocity_at_trajectory_end\" is set to false. (The default behavior changed "
73+
"to false, and trajectories might get discarded.)");
7474
}
7575

7676
return CallbackReturn::SUCCESS;
@@ -142,7 +142,7 @@ controller_interface::return_type JointTrajectoryController::update(
142142
const JointTrajectoryPoint & desired)
143143
{
144144
// error defined as the difference between current and desired
145-
if (normalize_joint_error_[index])
145+
if (joints_angle_wraparound_[index])
146146
{
147147
// if desired, the shortest_angular_distance is calculated, i.e., the error is
148148
// normalized between -pi<error<pi
@@ -728,19 +728,19 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
728728
}
729729

730730
// Configure joint position error normalization from ROS parameters (angle_wraparound)
731-
normalize_joint_error_.resize(dof_);
731+
joints_angle_wraparound_.resize(dof_);
732732
for (size_t i = 0; i < dof_; ++i)
733733
{
734734
const auto & gains = params_.gains.joints_map.at(params_.joints[i]);
735735
if (gains.normalize_error)
736736
{
737737
// TODO(anyone): Remove deprecation warning in the end of 2023
738738
RCLCPP_INFO(logger, "`normalize_error` is deprecated, use `angle_wraparound` instead!");
739-
normalize_joint_error_[i] = gains.normalize_error;
739+
joints_angle_wraparound_[i] = gains.normalize_error;
740740
}
741741
else
742742
{
743-
normalize_joint_error_[i] = gains.angle_wraparound;
743+
joints_angle_wraparound_[i] = gains.angle_wraparound;
744744
}
745745
}
746746

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 1 addition & 1 deletion
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: {

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
@@ -492,14 +491,13 @@ TEST_P(TrajectoryControllerTestParameterized, hold_on_startup)
492491
// Floating-point value comparison threshold
493492
const double EPS = 1e-6;
494493
/**
495-
* @brief check if position error of revolute joints are normalized if not configured so
494+
* @brief check if position error of revolute joints are angle_wraparound if not configured so
496495
*/
497-
TEST_P(TrajectoryControllerTestParameterized, position_error_not_normalized)
496+
TEST_P(TrajectoryControllerTestParameterized, position_error_not_angle_wraparound)
498497
{
499498
rclcpp::executors::MultiThreadedExecutor executor;
500499
constexpr double k_p = 10.0;
501-
std::vector<rclcpp::Parameter> params = {
502-
rclcpp::Parameter("allow_nonzero_velocity_at_trajectory_end", true)};
500+
std::vector<rclcpp::Parameter> params = {};
503501
SetUpAndActivateTrajectoryController(executor, params, true, k_p, 0.0, false);
504502
subscribeToState();
505503

@@ -742,14 +740,13 @@ TEST_P(TrajectoryControllerTestParameterized, timeout)
742740
}
743741

744742
/**
745-
* @brief check if position error of revolute joints are normalized if configured so
743+
* @brief check if position error of revolute joints are angle_wraparound if configured so
746744
*/
747-
TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
745+
TEST_P(TrajectoryControllerTestParameterized, position_error_angle_wraparound)
748746
{
749747
rclcpp::executors::MultiThreadedExecutor executor;
750748
constexpr double k_p = 10.0;
751-
std::vector<rclcpp::Parameter> params = {
752-
rclcpp::Parameter("allow_nonzero_velocity_at_trajectory_end", true)};
749+
std::vector<rclcpp::Parameter> params = {};
753750
SetUpAndActivateTrajectoryController(executor, params, true, k_p, 0.0, true);
754751
subscribeToState();
755752

@@ -790,7 +787,7 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
790787
EXPECT_NEAR(points[0][1], state_msg->reference.positions[1], allowed_delta);
791788
EXPECT_NEAR(points[0][2], state_msg->reference.positions[2], 3 * allowed_delta);
792789

793-
// is error.positions[2] normalized?
790+
// is error.positions[2] angle_wraparound?
794791
EXPECT_NEAR(
795792
state_msg->error.positions[0], state_msg->reference.positions[0] - INITIAL_POS_JOINTS[0], EPS);
796793
EXPECT_NEAR(
@@ -819,7 +816,7 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
819816
EXPECT_NEAR(
820817
k_p * (state_msg->reference.positions[1] - INITIAL_POS_JOINTS[1]), joint_vel_[1],
821818
k_p * allowed_delta);
822-
// is error of positions[2] normalized?
819+
// is error of positions[2] angle_wraparound?
823820
EXPECT_GT(0.0, joint_vel_[2]);
824821
EXPECT_NEAR(
825822
k_p * (state_msg->reference.positions[2] - INITIAL_POS_JOINTS[2] - 2 * M_PI), joint_vel_[2],
@@ -847,7 +844,7 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
847844
EXPECT_NEAR(
848845
k_p * (state_msg->reference.positions[1] - INITIAL_POS_JOINTS[1]), joint_eff_[1],
849846
k_p * allowed_delta);
850-
// is error of positions[2] normalized?
847+
// is error of positions[2] angle_wraparound?
851848
EXPECT_GT(0.0, joint_eff_[2]);
852849
EXPECT_NEAR(
853850
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
@@ -200,7 +200,7 @@ class TrajectoryControllerTest : public ::testing::Test
200200
}
201201

202202
void SetPidParameters(
203-
double p_default = 0.0, double ff_default = 1.0, bool normalize_error_default = false)
203+
double p_default = 0.0, double ff_default = 1.0, bool angle_wraparound_default = false)
204204
{
205205
traj_controller_->trigger_declare_parameters();
206206
auto node = traj_controller_->get_node();
@@ -213,27 +213,31 @@ class TrajectoryControllerTest : public ::testing::Test
213213
const rclcpp::Parameter k_d(prefix + ".d", 0.0);
214214
const rclcpp::Parameter i_clamp(prefix + ".i_clamp", 0.0);
215215
const rclcpp::Parameter ff_velocity_scale(prefix + ".ff_velocity_scale", ff_default);
216-
const rclcpp::Parameter normalize_error(prefix + ".normalize_error", normalize_error_default);
217-
node->set_parameters({k_p, k_i, k_d, i_clamp, ff_velocity_scale, normalize_error});
216+
const rclcpp::Parameter angle_wraparound(
217+
prefix + ".angle_wraparound", angle_wraparound_default);
218+
node->set_parameters({k_p, k_i, k_d, i_clamp, ff_velocity_scale, angle_wraparound});
218219
}
219220
}
220221

221222
void SetUpAndActivateTrajectoryController(
222223
rclcpp::Executor & executor, const std::vector<rclcpp::Parameter> & parameters = {},
223224
bool separate_cmd_and_state_values = false, double k_p = 0.0, double ff = 1.0,
224-
bool normalize_error = false)
225+
bool angle_wraparound = false)
225226
{
226227
SetUpTrajectoryController(executor);
227228

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

238242
traj_controller_->get_node()->configure();
239243

0 commit comments

Comments
 (0)