Skip to content

Commit 0e23548

Browse files
christophfroehlichmergify[bot]
authored andcommitted
[JTC] Convert lambda to class functions (#945)
* Convert lambdas to member functions * Make member function const * Add a test for compute_error function * Make reference_wrapper argument const * Iterate over error fields (cherry picked from commit 833ed7f) # Conflicts: # joint_trajectory_controller/include/joint_trajectory_controller/tolerances.hpp
1 parent 5f2279b commit 0e23548

File tree

5 files changed

+264
-43
lines changed

5 files changed

+264
-43
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 33 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -209,6 +209,20 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
209209
void goal_accepted_callback(
210210
std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle);
211211

212+
using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
213+
214+
/**
215+
* Computes the error for a specific joint in the trajectory.
216+
*
217+
* @param[out] error The computed error for the joint.
218+
* @param[in] index The index of the joint in the trajectory.
219+
* @param[in] current The current state of the joints.
220+
* @param[in] desired The desired state of the joints.
221+
*/
222+
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
223+
void compute_error_for_joint(
224+
JointTrajectoryPoint & error, const size_t index, const JointTrajectoryPoint & current,
225+
const JointTrajectoryPoint & desired) const;
212226
// fill trajectory_msg so it matches joints controlled by this controller
213227
// positions set to current position, velocities, accelerations and efforts to 0.0
214228
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
@@ -217,7 +231,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
217231
// sorts the joints of the incoming message to our local order
218232
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
219233
void sort_to_local_joint_order(
220-
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg);
234+
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const;
221235
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
222236
bool validate_trajectory_msg(const trajectory_msgs::msg::JointTrajectory & trajectory) const;
223237
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
@@ -241,7 +255,6 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
241255
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
242256
bool has_active_trajectory() const;
243257

244-
using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
245258
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
246259
void publish_state(
247260
const rclcpp::Time & time, const JointTrajectoryPoint & desired_state,
@@ -273,6 +286,24 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
273286
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
274287
void resize_joint_trajectory_point_command(
275288
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size);
289+
290+
/**
291+
* @brief Assigns the values from a trajectory point interface to a joint interface.
292+
*
293+
* @tparam T The type of the joint interface.
294+
* @param[out] joint_interface The reference_wrapper to assign the values to
295+
* @param[in] trajectory_point_interface Containing the values to assign.
296+
* @todo: Use auto in parameter declaration with c++20
297+
*/
298+
template <typename T>
299+
void assign_interface_from_point(
300+
const T & joint_interface, const std::vector<double> & trajectory_point_interface)
301+
{
302+
for (size_t index = 0; index < dof_; ++index)
303+
{
304+
joint_interface[index].get().set_value(trajectory_point_interface[index]);
305+
}
306+
}
276307
};
277308

278309
} // namespace joint_trajectory_controller

joint_trajectory_controller/include/joint_trajectory_controller/tolerances.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,11 @@ inline bool check_state_tolerance_per_joint(
147147
if (show_errors)
148148
{
149149
const auto logger = rclcpp::get_logger("tolerances");
150+
<<<<<<< HEAD
150151
RCLCPP_ERROR(logger, "State tolerances failed for joint %d:", joint_idx);
152+
=======
153+
RCLCPP_ERROR(logger, "State tolerances failed for joint %lu:", joint_idx);
154+
>>>>>>> 833ed7f ([JTC] Convert lambda to class functions (#945))
151155

152156
if (state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position)
153157
{

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 29 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -131,35 +131,6 @@ controller_interface::return_type JointTrajectoryController::update(
131131
}
132132
}
133133

134-
auto compute_error_for_joint = [&](
135-
JointTrajectoryPoint & error, size_t index,
136-
const JointTrajectoryPoint & current,
137-
const JointTrajectoryPoint & desired)
138-
{
139-
// error defined as the difference between current and desired
140-
if (joints_angle_wraparound_[index])
141-
{
142-
// if desired, the shortest_angular_distance is calculated, i.e., the error is
143-
// normalized between -pi<error<pi
144-
error.positions[index] =
145-
angles::shortest_angular_distance(current.positions[index], desired.positions[index]);
146-
}
147-
else
148-
{
149-
error.positions[index] = desired.positions[index] - current.positions[index];
150-
}
151-
if (
152-
has_velocity_state_interface_ &&
153-
(has_velocity_command_interface_ || has_effort_command_interface_))
154-
{
155-
error.velocities[index] = desired.velocities[index] - current.velocities[index];
156-
}
157-
if (has_acceleration_state_interface_ && has_acceleration_command_interface_)
158-
{
159-
error.accelerations[index] = desired.accelerations[index] - current.accelerations[index];
160-
}
161-
};
162-
163134
// don't update goal after we sampled the trajectory to avoid any racecondition
164135
const auto active_goal = *rt_active_goal_.readFromRT();
165136

@@ -177,17 +148,6 @@ controller_interface::return_type JointTrajectoryController::update(
177148
traj_external_point_ptr_->update(*new_external_msg);
178149
}
179150

180-
// TODO(anyone): can I here also use const on joint_interface since the reference_wrapper is not
181-
// changed, but its value only?
182-
auto assign_interface_from_point =
183-
[&](auto & joint_interface, const std::vector<double> & trajectory_point_interface)
184-
{
185-
for (size_t index = 0; index < dof_; ++index)
186-
{
187-
joint_interface[index].get().set_value(trajectory_point_interface[index]);
188-
}
189-
};
190-
191151
// current state update
192152
state_current_.time_from_start.set__sec(0);
193153
read_state_from_state_interfaces(state_current_);
@@ -1216,6 +1176,34 @@ void JointTrajectoryController::goal_accepted_callback(
12161176
std::bind(&RealtimeGoalHandle::runNonRealtime, rt_goal));
12171177
}
12181178

1179+
void JointTrajectoryController::compute_error_for_joint(
1180+
JointTrajectoryPoint & error, const size_t index, const JointTrajectoryPoint & current,
1181+
const JointTrajectoryPoint & desired) const
1182+
{
1183+
// error defined as the difference between current and desired
1184+
if (joints_angle_wraparound_[index])
1185+
{
1186+
// if desired, the shortest_angular_distance is calculated, i.e., the error is
1187+
// normalized between -pi<error<pi
1188+
error.positions[index] =
1189+
angles::shortest_angular_distance(current.positions[index], desired.positions[index]);
1190+
}
1191+
else
1192+
{
1193+
error.positions[index] = desired.positions[index] - current.positions[index];
1194+
}
1195+
if (
1196+
has_velocity_state_interface_ &&
1197+
(has_velocity_command_interface_ || has_effort_command_interface_))
1198+
{
1199+
error.velocities[index] = desired.velocities[index] - current.velocities[index];
1200+
}
1201+
if (has_acceleration_state_interface_ && has_acceleration_command_interface_)
1202+
{
1203+
error.accelerations[index] = desired.accelerations[index] - current.accelerations[index];
1204+
}
1205+
}
1206+
12191207
void JointTrajectoryController::fill_partial_goal(
12201208
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const
12211209
{
@@ -1277,7 +1265,7 @@ void JointTrajectoryController::fill_partial_goal(
12771265
}
12781266

12791267
void JointTrajectoryController::sort_to_local_joint_order(
1280-
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg)
1268+
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> trajectory_msg) const
12811269
{
12821270
// rearrange all points in the trajectory message based on mapping
12831271
std::vector<size_t> mapping_vector = mapping(trajectory_msg->joint_names, params_.joints);

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 174 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -480,6 +480,180 @@ TEST_P(TrajectoryControllerTestParameterized, hold_on_startup)
480480

481481
// Floating-point value comparison threshold
482482
const double EPS = 1e-6;
483+
484+
/**
485+
* @brief check if calculated trajectory error is correct with angle wraparound=true
486+
*/
487+
TEST_P(TrajectoryControllerTestParameterized, compute_error_angle_wraparound_true)
488+
{
489+
rclcpp::executors::MultiThreadedExecutor executor;
490+
std::vector<rclcpp::Parameter> params = {};
491+
SetUpAndActivateTrajectoryController(
492+
executor, params, true, 0.0, 1.0, true /* angle_wraparound */);
493+
494+
size_t n_joints = joint_names_.size();
495+
496+
// send msg
497+
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
498+
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)};
499+
// *INDENT-OFF*
500+
std::vector<std::vector<double>> points{
501+
{{3.3, 4.4, 6.6}}, {{7.7, 8.8, 9.9}}, {{10.10, 11.11, 12.12}}};
502+
std::vector<std::vector<double>> points_velocities{
503+
{{0.01, 0.01, 0.01}}, {{0.05, 0.05, 0.05}}, {{0.06, 0.06, 0.06}}};
504+
std::vector<std::vector<double>> points_accelerations{
505+
{{0.1, 0.1, 0.1}}, {{0.5, 0.5, 0.5}}, {{0.6, 0.6, 0.6}}};
506+
// *INDENT-ON*
507+
508+
trajectory_msgs::msg::JointTrajectoryPoint error, current, desired;
509+
current.positions = {points[0].begin(), points[0].end()};
510+
current.velocities = {points_velocities[0].begin(), points_velocities[0].end()};
511+
current.accelerations = {points_accelerations[0].begin(), points_accelerations[0].end()};
512+
traj_controller_->resize_joint_trajectory_point(error, n_joints);
513+
514+
// zero error
515+
desired = current;
516+
for (size_t i = 0; i < n_joints; ++i)
517+
{
518+
traj_controller_->testable_compute_error_for_joint(error, i, current, desired);
519+
EXPECT_NEAR(error.positions[i], 0., EPS);
520+
if (
521+
traj_controller_->has_velocity_state_interface() &&
522+
(traj_controller_->has_velocity_command_interface() ||
523+
traj_controller_->has_effort_command_interface()))
524+
{
525+
// expect: error.velocities = desired.velocities - current.velocities;
526+
EXPECT_NEAR(error.velocities[i], 0., EPS);
527+
}
528+
if (
529+
traj_controller_->has_acceleration_state_interface() &&
530+
traj_controller_->has_acceleration_command_interface())
531+
{
532+
// expect: error.accelerations = desired.accelerations - current.accelerations;
533+
EXPECT_NEAR(error.accelerations[i], 0., EPS);
534+
}
535+
}
536+
537+
// angle wraparound of position error
538+
desired.positions[0] += 3.0 * M_PI_2;
539+
desired.velocities[0] += 1.0;
540+
desired.accelerations[0] += 1.0;
541+
traj_controller_->resize_joint_trajectory_point(error, n_joints);
542+
for (size_t i = 0; i < n_joints; ++i)
543+
{
544+
traj_controller_->testable_compute_error_for_joint(error, i, current, desired);
545+
if (i == 0)
546+
{
547+
EXPECT_NEAR(
548+
error.positions[i], desired.positions[i] - current.positions[i] - 2.0 * M_PI, EPS);
549+
}
550+
else
551+
{
552+
EXPECT_NEAR(error.positions[i], desired.positions[i] - current.positions[i], EPS);
553+
}
554+
555+
if (
556+
traj_controller_->has_velocity_state_interface() &&
557+
(traj_controller_->has_velocity_command_interface() ||
558+
traj_controller_->has_effort_command_interface()))
559+
{
560+
// expect: error.velocities = desired.velocities - current.velocities;
561+
EXPECT_NEAR(error.velocities[i], desired.velocities[i] - current.velocities[i], EPS);
562+
}
563+
if (
564+
traj_controller_->has_acceleration_state_interface() &&
565+
traj_controller_->has_acceleration_command_interface())
566+
{
567+
// expect: error.accelerations = desired.accelerations - current.accelerations;
568+
EXPECT_NEAR(error.accelerations[i], desired.accelerations[i] - current.accelerations[i], EPS);
569+
}
570+
}
571+
572+
executor.cancel();
573+
}
574+
575+
/**
576+
* @brief check if calculated trajectory error is correct with angle wraparound=false
577+
*/
578+
TEST_P(TrajectoryControllerTestParameterized, compute_error_angle_wraparound_false)
579+
{
580+
rclcpp::executors::MultiThreadedExecutor executor;
581+
std::vector<rclcpp::Parameter> params = {};
582+
SetUpAndActivateTrajectoryController(
583+
executor, params, true, 0.0, 1.0, false /* angle_wraparound */);
584+
585+
size_t n_joints = joint_names_.size();
586+
587+
// send msg
588+
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
589+
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)};
590+
// *INDENT-OFF*
591+
std::vector<std::vector<double>> points{
592+
{{3.3, 4.4, 6.6}}, {{7.7, 8.8, 9.9}}, {{10.10, 11.11, 12.12}}};
593+
std::vector<std::vector<double>> points_velocities{
594+
{{0.01, 0.01, 0.01}}, {{0.05, 0.05, 0.05}}, {{0.06, 0.06, 0.06}}};
595+
std::vector<std::vector<double>> points_accelerations{
596+
{{0.1, 0.1, 0.1}}, {{0.5, 0.5, 0.5}}, {{0.6, 0.6, 0.6}}};
597+
// *INDENT-ON*
598+
599+
trajectory_msgs::msg::JointTrajectoryPoint error, current, desired;
600+
current.positions = {points[0].begin(), points[0].end()};
601+
current.velocities = {points_velocities[0].begin(), points_velocities[0].end()};
602+
current.accelerations = {points_accelerations[0].begin(), points_accelerations[0].end()};
603+
traj_controller_->resize_joint_trajectory_point(error, n_joints);
604+
605+
// zero error
606+
desired = current;
607+
for (size_t i = 0; i < n_joints; ++i)
608+
{
609+
traj_controller_->testable_compute_error_for_joint(error, i, current, desired);
610+
EXPECT_NEAR(error.positions[i], 0., EPS);
611+
if (
612+
traj_controller_->has_velocity_state_interface() &&
613+
(traj_controller_->has_velocity_command_interface() ||
614+
traj_controller_->has_effort_command_interface()))
615+
{
616+
// expect: error.velocities = desired.velocities - current.velocities;
617+
EXPECT_NEAR(error.velocities[i], 0., EPS);
618+
}
619+
if (
620+
traj_controller_->has_acceleration_state_interface() &&
621+
traj_controller_->has_acceleration_command_interface())
622+
{
623+
// expect: error.accelerations = desired.accelerations - current.accelerations;
624+
EXPECT_NEAR(error.accelerations[i], 0., EPS);
625+
}
626+
}
627+
628+
// no normalization of position error
629+
desired.positions[0] += 3.0 * M_PI_4;
630+
desired.velocities[0] += 1.0;
631+
desired.accelerations[0] += 1.0;
632+
traj_controller_->resize_joint_trajectory_point(error, n_joints);
633+
for (size_t i = 0; i < n_joints; ++i)
634+
{
635+
traj_controller_->testable_compute_error_for_joint(error, i, current, desired);
636+
EXPECT_NEAR(error.positions[i], desired.positions[i] - current.positions[i], EPS);
637+
if (
638+
traj_controller_->has_velocity_state_interface() &&
639+
(traj_controller_->has_velocity_command_interface() ||
640+
traj_controller_->has_effort_command_interface()))
641+
{
642+
// expect: error.velocities = desired.velocities - current.velocities;
643+
EXPECT_NEAR(error.velocities[i], desired.velocities[i] - current.velocities[i], EPS);
644+
}
645+
if (
646+
traj_controller_->has_acceleration_state_interface() &&
647+
traj_controller_->has_acceleration_command_interface())
648+
{
649+
// expect: error.accelerations = desired.accelerations - current.accelerations;
650+
EXPECT_NEAR(error.accelerations[i], desired.accelerations[i] - current.accelerations[i], EPS);
651+
}
652+
}
653+
654+
executor.cancel();
655+
}
656+
483657
/**
484658
* @brief check if position error of revolute joints are angle_wraparound if not configured so
485659
*/

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -107,6 +107,13 @@ class TestableJointTrajectoryController
107107

108108
void trigger_declare_parameters() { param_listener_->declare_params(); }
109109

110+
void testable_compute_error_for_joint(
111+
JointTrajectoryPoint & error, const size_t index, const JointTrajectoryPoint & current,
112+
const JointTrajectoryPoint & desired)
113+
{
114+
compute_error_for_joint(error, index, current, desired);
115+
}
116+
110117
trajectory_msgs::msg::JointTrajectoryPoint get_current_state_when_offset() const
111118
{
112119
return last_commanded_state_;
@@ -154,6 +161,23 @@ class TestableJointTrajectoryController
154161
trajectory_msgs::msg::JointTrajectoryPoint get_state_reference() { return state_desired_; }
155162
trajectory_msgs::msg::JointTrajectoryPoint get_state_error() { return state_error_; }
156163

164+
/**
165+
* a copy of the private member function
166+
*/
167+
void resize_joint_trajectory_point(
168+
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size)
169+
{
170+
point.positions.resize(size, 0.0);
171+
if (has_velocity_state_interface_)
172+
{
173+
point.velocities.resize(size, 0.0);
174+
}
175+
if (has_acceleration_state_interface_)
176+
{
177+
point.accelerations.resize(size, 0.0);
178+
}
179+
}
180+
157181
rclcpp::WaitSet joint_cmd_sub_wait_set_;
158182
};
159183

0 commit comments

Comments
 (0)