@@ -480,6 +480,180 @@ TEST_P(TrajectoryControllerTestParameterized, hold_on_startup)
480480
481481// Floating-point value comparison threshold
482482const 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 */
0 commit comments