@@ -617,6 +617,147 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_not_normalized)
617617 executor.cancel ();
618618}
619619
620+ /* *
621+ * @brief cmd_timeout must be greater than constraints.goal_time
622+ */
623+ TEST_P (TrajectoryControllerTestParameterized, accept_correct_cmd_timeout)
624+ {
625+ rclcpp::executors::MultiThreadedExecutor executor;
626+ // zero is default value, just for demonstration
627+ double cmd_timeout = 3.0 ;
628+ rclcpp::Parameter cmd_timeout_parameter (" cmd_timeout" , cmd_timeout);
629+ rclcpp::Parameter goal_time_parameter (" constraints.goal_time" , 2.0 );
630+ SetUpAndActivateTrajectoryController (
631+ executor, {cmd_timeout_parameter, goal_time_parameter}, false );
632+
633+ EXPECT_DOUBLE_EQ (cmd_timeout, traj_controller_->get_cmd_timeout ());
634+ }
635+
636+ /* *
637+ * @brief cmd_timeout must be greater than constraints.goal_time
638+ */
639+ TEST_P (TrajectoryControllerTestParameterized, decline_false_cmd_timeout)
640+ {
641+ rclcpp::executors::MultiThreadedExecutor executor;
642+ // zero is default value, just for demonstration
643+ rclcpp::Parameter cmd_timeout_parameter (" cmd_timeout" , 1.0 );
644+ rclcpp::Parameter goal_time_parameter (" constraints.goal_time" , 2.0 );
645+ SetUpAndActivateTrajectoryController (
646+ executor, {cmd_timeout_parameter, goal_time_parameter}, false );
647+
648+ EXPECT_DOUBLE_EQ (0.0 , traj_controller_->get_cmd_timeout ());
649+ }
650+
651+ /* *
652+ * @brief check if no timeout is triggered
653+ */
654+ TEST_P (TrajectoryControllerTestParameterized, no_timeout)
655+ {
656+ rclcpp::executors::MultiThreadedExecutor executor;
657+ // zero is default value, just for demonstration
658+ rclcpp::Parameter cmd_timeout_parameter (" cmd_timeout" , 0.0 );
659+ SetUpAndActivateTrajectoryController (executor, {cmd_timeout_parameter}, false );
660+ subscribeToState ();
661+
662+ size_t n_joints = joint_names_.size ();
663+
664+ // send msg
665+ constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds (250 );
666+ builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration (FIRST_POINT_TIME)};
667+ // *INDENT-OFF*
668+ std::vector<std::vector<double >> points{
669+ {{3.3 , 4.4 , 6.6 }}, {{7.7 , 8.8 , 9.9 }}, {{10.10 , 11.11 , 12.12 }}};
670+ std::vector<std::vector<double >> points_velocities{
671+ {{0.01 , 0.01 , 0.01 }}, {{0.05 , 0.05 , 0.05 }}, {{0.06 , 0.06 , 0.06 }}};
672+ // *INDENT-ON*
673+ publish (time_from_start, points, rclcpp::Time (0 , 0 , RCL_STEADY_TIME), {}, points_velocities);
674+ traj_controller_->wait_for_trajectory (executor);
675+
676+ // first update
677+ updateController (rclcpp::Duration (FIRST_POINT_TIME) * 4 );
678+
679+ // Spin to receive latest state
680+ executor.spin_some ();
681+ auto state_msg = getState ();
682+ ASSERT_TRUE (state_msg);
683+
684+ // has the msg the correct vector sizes?
685+ EXPECT_EQ (n_joints, state_msg->reference .positions .size ());
686+
687+ // is the trajectory still active?
688+ EXPECT_TRUE (traj_controller_->has_active_traj ());
689+ // should still hold the points from above
690+ EXPECT_TRUE (traj_controller_->has_nontrivial_traj ());
691+ EXPECT_NEAR (state_msg->reference .positions [0 ], points.at (2 ).at (0 ), 1e-2 );
692+ EXPECT_NEAR (state_msg->reference .positions [1 ], points.at (2 ).at (1 ), 1e-2 );
693+ EXPECT_NEAR (state_msg->reference .positions [2 ], points.at (2 ).at (2 ), 1e-2 );
694+ // value of velocities is different from above due to spline interpolation
695+ EXPECT_GT (state_msg->reference .velocities [0 ], 0.0 );
696+ EXPECT_GT (state_msg->reference .velocities [1 ], 0.0 );
697+ EXPECT_GT (state_msg->reference .velocities [2 ], 0.0 );
698+
699+ executor.cancel ();
700+ }
701+
702+ /* *
703+ * @brief check if timeout is triggered
704+ */
705+ TEST_P (TrajectoryControllerTestParameterized, timeout)
706+ {
707+ rclcpp::executors::MultiThreadedExecutor executor;
708+ constexpr double cmd_timeout = 0.1 ;
709+ rclcpp::Parameter cmd_timeout_parameter (" cmd_timeout" , cmd_timeout);
710+ double kp = 1.0 ; // activate feedback control for testing velocity/effort PID
711+ SetUpAndActivateTrajectoryController (executor, {cmd_timeout_parameter}, false , kp);
712+ subscribeToState ();
713+
714+ // send msg
715+ constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds (250 );
716+ builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration (FIRST_POINT_TIME)};
717+ // *INDENT-OFF*
718+ std::vector<std::vector<double >> points{
719+ {{3.3 , 4.4 , 6.6 }}, {{7.7 , 8.8 , 9.9 }}, {{10.10 , 11.11 , 12.12 }}};
720+ std::vector<std::vector<double >> points_velocities{
721+ {{0.01 , 0.01 , 0.01 }}, {{0.05 , 0.05 , 0.05 }}, {{0.06 , 0.06 , 0.06 }}};
722+ // *INDENT-ON*
723+
724+ publish (time_from_start, points, rclcpp::Time (0 , 0 , RCL_STEADY_TIME), {}, points_velocities);
725+ traj_controller_->wait_for_trajectory (executor);
726+
727+ // update until end of trajectory -> no timeout should have occurred
728+ updateController (rclcpp::Duration (FIRST_POINT_TIME) * 3 );
729+ // is a trajectory active?
730+ EXPECT_TRUE (traj_controller_->has_active_traj ());
731+ // should have the trajectory with three points
732+ EXPECT_TRUE (traj_controller_->has_nontrivial_traj ());
733+
734+ // update until timeout should have happened
735+ updateController (rclcpp::Duration (FIRST_POINT_TIME));
736+
737+ // Spin to receive latest state
738+ executor.spin_some ();
739+ auto state_msg = getState ();
740+ ASSERT_TRUE (state_msg);
741+
742+ // after timeout, set_hold_position adds a new trajectory
743+ // is a trajectory active?
744+ EXPECT_TRUE (traj_controller_->has_active_traj ());
745+ // should be not more than one point now (from hold position)
746+ EXPECT_FALSE (traj_controller_->has_nontrivial_traj ());
747+ // should hold last position with zero velocity
748+ if (traj_controller_->has_position_command_interface ())
749+ {
750+ expectHoldingPoint (points.at (2 ));
751+ }
752+ else
753+ {
754+ // no integration to position state interface from velocity/acceleration
755+ expectHoldingPoint (INITIAL_POS_JOINTS);
756+ }
757+
758+ executor.cancel ();
759+ }
760+
620761/* *
621762 * @brief check if position error of revolute joints are normalized if configured so
622763 */
0 commit comments