@@ -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+
502706void TrajectoryControllerTest::test_state_publish_rate_target (int target_msg_count)
503707{
504708 rclcpp::Parameter state_publish_rate_param (
0 commit comments