Skip to content

Commit 8e6697b

Browse files
[JTC] Configurable joint positon error normalization behavior (ros-controls#491) (ros-controls#579)
* Use the same variables for state feedback and PID loop * Make joint_error normalization configurable * Activate test for only velocity controller * Allow ff_velocity_scale=0 without deprecated warning * Add test for setpoint due to normalized position error * Update comments in test Co-authored-by: Bence Magyar <[email protected]> (cherry picked from commit 67e5d4d) Co-authored-by: Christoph Fröhlich <[email protected]>
1 parent ce0aeb2 commit 8e6697b

File tree

5 files changed

+242
-10
lines changed

5 files changed

+242
-10
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -166,6 +166,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
166166
std::vector<PidPtr> pids_;
167167
// Feed-forward velocity weight factor when calculating closed loop pid adapter's command
168168
std::vector<double> ff_velocity_scale_;
169+
// Configuration for every joint, if position error is normalized
170+
std::vector<bool> normalize_joint_error_;
169171
// reserved storage for result of the command when closed loop pid adapter is used
170172
std::vector<double> tmp_command_;
171173

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 20 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -125,8 +125,17 @@ controller_interface::return_type JointTrajectoryController::update(
125125
const JointTrajectoryPoint & desired)
126126
{
127127
// error defined as the difference between current and desired
128-
error.positions[index] =
129-
angles::shortest_angular_distance(current.positions[index], desired.positions[index]);
128+
if (normalize_joint_error_[index])
129+
{
130+
// if desired, the shortest_angular_distance is calculated, i.e., the error is
131+
// normalized between -pi<error<pi
132+
error.positions[index] =
133+
angles::shortest_angular_distance(current.positions[index], desired.positions[index]);
134+
}
135+
else
136+
{
137+
error.positions[index] = desired.positions[index] - current.positions[index];
138+
}
130139
if (has_velocity_state_interface_ && has_velocity_command_interface_)
131140
{
132141
error.velocities[index] = desired.velocities[index] - current.velocities[index];
@@ -243,8 +252,7 @@ controller_interface::return_type JointTrajectoryController::update(
243252
{
244253
tmp_command_[i] = (state_desired_.velocities[i] * ff_velocity_scale_[i]) +
245254
pids_[i]->computeCommand(
246-
state_desired_.positions[i] - state_current_.positions[i],
247-
state_desired_.velocities[i] - state_current_.velocities[i],
255+
state_error_.positions[i], state_error_.velocities[i],
248256
(uint64_t)period.nanoseconds());
249257
}
250258
}
@@ -581,6 +589,14 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
581589
}
582590
}
583591

592+
// Configure joint position error normalization from ROS parameters
593+
normalize_joint_error_.resize(dof_);
594+
for (size_t i = 0; i < dof_; ++i)
595+
{
596+
const auto & gains = params_.gains.joints_map.at(params_.joints[i]);
597+
normalize_joint_error_[i] = gains.normalize_error;
598+
}
599+
584600
if (params_.state_interfaces.empty())
585601
{
586602
RCLCPP_ERROR(logger, "'state_interfaces' parameter is empty.");

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -101,6 +101,11 @@ joint_trajectory_controller:
101101
default_value: 0.0,
102102
description: "Feed-forward scaling of velocity."
103103
}
104+
normalize_error: {
105+
type: bool,
106+
default_value: false,
107+
description: "Use position error normalization to -pi to pi."
108+
}
104109
constraints:
105110
stopped_velocity_tolerance: {
106111
type: double,

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 204 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -499,6 +499,210 @@ TEST_P(TrajectoryControllerTestParameterized, state_topic_consistency)
499499
EXPECT_TRUE(state->error.accelerations.empty() || state->error.accelerations == zeros);
500500
}
501501

502+
// Floating-point value comparison threshold
503+
const double EPS = 1e-6;
504+
/**
505+
* @brief check if position error of revolute joints are normalized if not configured so
506+
*/
507+
TEST_P(TrajectoryControllerTestParameterized, position_error_not_normalized)
508+
{
509+
rclcpp::executors::MultiThreadedExecutor executor;
510+
constexpr double k_p = 10.0;
511+
SetUpAndActivateTrajectoryController(executor, true, {}, true, k_p, 0.0, false);
512+
subscribeToState();
513+
514+
size_t n_joints = joint_names_.size();
515+
516+
// send msg
517+
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
518+
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)};
519+
// *INDENT-OFF*
520+
std::vector<std::vector<double>> points{
521+
{{3.3, 4.4, 6.6}}, {{7.7, 8.8, 9.9}}, {{10.10, 11.11, 12.12}}};
522+
std::vector<std::vector<double>> points_velocities{
523+
{{0.01, 0.01, 0.01}}, {{0.05, 0.05, 0.05}}, {{0.06, 0.06, 0.06}}};
524+
// *INDENT-ON*
525+
publish(time_from_start, points, rclcpp::Time(), {}, points_velocities);
526+
traj_controller_->wait_for_trajectory(executor);
527+
528+
// first update
529+
updateController(rclcpp::Duration(FIRST_POINT_TIME));
530+
531+
// Spin to receive latest state
532+
executor.spin_some();
533+
auto state_msg = getState();
534+
ASSERT_TRUE(state_msg);
535+
536+
const auto allowed_delta = 0.1;
537+
538+
// no update of state_interface
539+
EXPECT_EQ(state_msg->actual.positions, INITIAL_POS_JOINTS);
540+
541+
// has the msg the correct vector sizes?
542+
EXPECT_EQ(n_joints, state_msg->desired.positions.size());
543+
EXPECT_EQ(n_joints, state_msg->actual.positions.size());
544+
EXPECT_EQ(n_joints, state_msg->error.positions.size());
545+
546+
// are the correct desired positions used?
547+
EXPECT_NEAR(points[0][0], state_msg->desired.positions[0], allowed_delta);
548+
EXPECT_NEAR(points[0][1], state_msg->desired.positions[1], allowed_delta);
549+
EXPECT_NEAR(points[0][2], state_msg->desired.positions[2], 3 * allowed_delta);
550+
551+
// no normalization of position error
552+
EXPECT_NEAR(
553+
state_msg->error.positions[0], state_msg->desired.positions[0] - INITIAL_POS_JOINTS[0], EPS);
554+
EXPECT_NEAR(
555+
state_msg->error.positions[1], state_msg->desired.positions[1] - INITIAL_POS_JOINTS[1], EPS);
556+
EXPECT_NEAR(
557+
state_msg->error.positions[2], state_msg->desired.positions[2] - INITIAL_POS_JOINTS[2], EPS);
558+
559+
if (traj_controller_->has_position_command_interface())
560+
{
561+
// check command interface
562+
EXPECT_NEAR(points[0][0], joint_pos_[0], allowed_delta);
563+
EXPECT_NEAR(points[0][1], joint_pos_[1], allowed_delta);
564+
EXPECT_NEAR(points[0][2], joint_pos_[2], allowed_delta);
565+
}
566+
567+
if (traj_controller_->has_velocity_command_interface())
568+
{
569+
// check command interface
570+
EXPECT_LE(0.0, joint_vel_[0]);
571+
EXPECT_LE(0.0, joint_vel_[1]);
572+
EXPECT_LE(0.0, joint_vel_[2]);
573+
574+
// use_closed_loop_pid_adapter_
575+
if (traj_controller_->use_closed_loop_pid_adapter())
576+
{
577+
// we expect u = k_p * (s_d-s)
578+
EXPECT_NEAR(
579+
k_p * (state_msg->desired.positions[0] - INITIAL_POS_JOINTS[0]), joint_vel_[0],
580+
k_p * allowed_delta);
581+
EXPECT_NEAR(
582+
k_p * (state_msg->desired.positions[1] - INITIAL_POS_JOINTS[1]), joint_vel_[1],
583+
k_p * allowed_delta);
584+
// no normalization of position error
585+
EXPECT_NEAR(
586+
k_p * (state_msg->desired.positions[2] - INITIAL_POS_JOINTS[2]), joint_vel_[2],
587+
k_p * allowed_delta);
588+
}
589+
}
590+
591+
if (traj_controller_->has_effort_command_interface())
592+
{
593+
// check command interface
594+
EXPECT_LE(0.0, joint_eff_[0]);
595+
EXPECT_LE(0.0, joint_eff_[1]);
596+
EXPECT_LE(0.0, joint_eff_[2]);
597+
}
598+
599+
executor.cancel();
600+
}
601+
602+
/**
603+
* @brief check if position error of revolute joints are normalized if configured so
604+
*/
605+
TEST_P(TrajectoryControllerTestParameterized, position_error_normalized)
606+
{
607+
rclcpp::executors::MultiThreadedExecutor executor;
608+
constexpr double k_p = 10.0;
609+
SetUpAndActivateTrajectoryController(executor, true, {}, true, k_p, 0.0, true);
610+
subscribeToState();
611+
612+
size_t n_joints = joint_names_.size();
613+
614+
// send msg
615+
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
616+
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)};
617+
// *INDENT-OFF*
618+
std::vector<std::vector<double>> points{
619+
{{3.3, 4.4, 6.6}}, {{7.7, 8.8, 9.9}}, {{10.10, 11.11, 12.12}}};
620+
std::vector<std::vector<double>> points_velocities{
621+
{{0.01, 0.01, 0.01}}, {{0.05, 0.05, 0.05}}, {{0.06, 0.06, 0.06}}};
622+
// *INDENT-ON*
623+
publish(time_from_start, points, rclcpp::Time(), {}, points_velocities);
624+
traj_controller_->wait_for_trajectory(executor);
625+
626+
// first update
627+
updateController(rclcpp::Duration(FIRST_POINT_TIME));
628+
629+
// Spin to receive latest state
630+
executor.spin_some();
631+
auto state_msg = getState();
632+
ASSERT_TRUE(state_msg);
633+
634+
const auto allowed_delta = 0.1;
635+
636+
// no update of state_interface
637+
EXPECT_EQ(state_msg->actual.positions, INITIAL_POS_JOINTS);
638+
639+
// has the msg the correct vector sizes?
640+
EXPECT_EQ(n_joints, state_msg->desired.positions.size());
641+
EXPECT_EQ(n_joints, state_msg->actual.positions.size());
642+
EXPECT_EQ(n_joints, state_msg->error.positions.size());
643+
644+
// are the correct desired positions used?
645+
EXPECT_NEAR(points[0][0], state_msg->desired.positions[0], allowed_delta);
646+
EXPECT_NEAR(points[0][1], state_msg->desired.positions[1], allowed_delta);
647+
EXPECT_NEAR(points[0][2], state_msg->desired.positions[2], 3 * allowed_delta);
648+
649+
// is error.positions[2] normalized?
650+
EXPECT_NEAR(
651+
state_msg->error.positions[0], state_msg->desired.positions[0] - INITIAL_POS_JOINTS[0], EPS);
652+
EXPECT_NEAR(
653+
state_msg->error.positions[1], state_msg->desired.positions[1] - INITIAL_POS_JOINTS[1], EPS);
654+
EXPECT_NEAR(
655+
state_msg->error.positions[2],
656+
state_msg->desired.positions[2] - INITIAL_POS_JOINTS[2] - 2 * M_PI, EPS);
657+
658+
if (traj_controller_->has_position_command_interface())
659+
{
660+
// check command interface
661+
EXPECT_NEAR(points[0][0], joint_pos_[0], allowed_delta);
662+
EXPECT_NEAR(points[0][1], joint_pos_[1], allowed_delta);
663+
EXPECT_NEAR(points[0][2], joint_pos_[2], allowed_delta);
664+
}
665+
666+
if (traj_controller_->has_velocity_command_interface())
667+
{
668+
// check command interface
669+
EXPECT_LE(0.0, joint_vel_[0]);
670+
EXPECT_LE(0.0, joint_vel_[1]);
671+
672+
// use_closed_loop_pid_adapter_
673+
if (traj_controller_->use_closed_loop_pid_adapter())
674+
{
675+
EXPECT_GE(0.0, joint_vel_[2]);
676+
// we expect u = k_p * (s_d-s) for positions[0] and positions[1]
677+
EXPECT_NEAR(
678+
k_p * (state_msg->desired.positions[0] - INITIAL_POS_JOINTS[0]), joint_vel_[0],
679+
k_p * allowed_delta);
680+
EXPECT_NEAR(
681+
k_p * (state_msg->desired.positions[1] - INITIAL_POS_JOINTS[1]), joint_vel_[1],
682+
k_p * allowed_delta);
683+
// is error of positions[2] normalized?
684+
EXPECT_NEAR(
685+
k_p * (state_msg->desired.positions[2] - INITIAL_POS_JOINTS[2] - 2 * M_PI), joint_vel_[2],
686+
k_p * allowed_delta);
687+
}
688+
else
689+
{
690+
// interpolated points_velocities only
691+
EXPECT_LE(0.0, joint_vel_[2]);
692+
}
693+
}
694+
695+
if (traj_controller_->has_effort_command_interface())
696+
{
697+
// check command interface
698+
EXPECT_LE(0.0, joint_eff_[0]);
699+
EXPECT_LE(0.0, joint_eff_[1]);
700+
EXPECT_LE(0.0, joint_eff_[2]);
701+
}
702+
703+
executor.cancel();
704+
}
705+
502706
void TrajectoryControllerTest::test_state_publish_rate_target(int target_msg_count)
503707
{
504708
rclcpp::Parameter state_publish_rate_param(

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -112,6 +112,8 @@ class TestableJointTrajectoryController
112112

113113
bool has_effort_command_interface() { return has_effort_command_interface_; }
114114

115+
bool use_closed_loop_pid_adapter() { return use_closed_loop_pid_adapter_; }
116+
115117
rclcpp::WaitSet joint_cmd_sub_wait_set_;
116118
};
117119

@@ -171,32 +173,35 @@ class TrajectoryControllerTest : public ::testing::Test
171173
node->set_parameters({joint_names_param, cmd_interfaces_params, state_interfaces_params});
172174
}
173175

174-
void SetPidParameters()
176+
void SetPidParameters(
177+
double p_default = 0.0, double ff_default = 1.0, bool normalize_error_default = false)
175178
{
176179
traj_controller_->trigger_declare_parameters();
177180
auto node = traj_controller_->get_node();
178181

179182
for (size_t i = 0; i < joint_names_.size(); ++i)
180183
{
181184
const std::string prefix = "gains." + joint_names_[i];
182-
const rclcpp::Parameter k_p(prefix + ".p", 0.0);
185+
const rclcpp::Parameter k_p(prefix + ".p", p_default);
183186
const rclcpp::Parameter k_i(prefix + ".i", 0.0);
184187
const rclcpp::Parameter k_d(prefix + ".d", 0.0);
185188
const rclcpp::Parameter i_clamp(prefix + ".i_clamp", 0.0);
186-
const rclcpp::Parameter ff_velocity_scale(prefix + ".ff_velocity_scale", 1.0);
187-
node->set_parameters({k_p, k_i, k_d, i_clamp, ff_velocity_scale});
189+
const rclcpp::Parameter ff_velocity_scale(prefix + ".ff_velocity_scale", ff_default);
190+
const rclcpp::Parameter normalize_error(prefix + ".normalize_error", normalize_error_default);
191+
node->set_parameters({k_p, k_i, k_d, i_clamp, ff_velocity_scale, normalize_error});
188192
}
189193
}
190194

191195
void SetUpAndActivateTrajectoryController(
192196
rclcpp::Executor & executor, bool use_local_parameters = true,
193197
const std::vector<rclcpp::Parameter> & parameters = {},
194-
bool separate_cmd_and_state_values = false)
198+
bool separate_cmd_and_state_values = false, double k_p = 0.0, double ff = 1.0,
199+
bool normalize_error = false)
195200
{
196201
SetUpTrajectoryController(executor, use_local_parameters);
197202

198203
// set pid parameters before configure
199-
SetPidParameters();
204+
SetPidParameters(k_p, ff, normalize_error);
200205
for (const auto & param : parameters)
201206
{
202207
traj_controller_->get_node()->set_parameter(param);

0 commit comments

Comments
 (0)