diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 1d6f94b7bf..5c5a817ef9 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -1146,6 +1146,7 @@ void JointTrajectoryController::publish_state( state_publisher_legacy_->msg_.desired.velocities = desired_state.velocities; state_publisher_legacy_->msg_.desired.accelerations = desired_state.accelerations; state_publisher_legacy_->msg_.actual.positions = current_state.positions; + state_publisher_legacy_->msg_.actual.time_from_start = current_state.time_from_start; state_publisher_legacy_->msg_.error.positions = state_error.positions; if (has_velocity_state_interface_) { @@ -1175,6 +1176,7 @@ void JointTrajectoryController::publish_state( state_publisher_->msg_.reference.positions = desired_state.positions; state_publisher_->msg_.reference.velocities = desired_state.velocities; state_publisher_->msg_.reference.accelerations = desired_state.accelerations; + state_publisher_->msg_.reference.time_from_start = desired_state.time_from_start; state_publisher_->msg_.feedback.positions = current_state.positions; // DESIRED and ACTUAL are deprecated in the message but we are still // reporting on them @@ -1183,6 +1185,7 @@ void JointTrajectoryController::publish_state( state_publisher_legacy_->msg_.desired.accelerations = desired_state.accelerations; state_publisher_legacy_->msg_.actual.positions = current_state.positions; state_publisher_->msg_.error.positions = state_error.positions; + state_publisher_->msg_.feedback.time_from_start = desired_state.time_from_start; if (has_velocity_state_interface_) { state_publisher_->msg_.feedback.velocities = current_state.velocities; diff --git a/joint_trajectory_controller/src/trajectory.cpp b/joint_trajectory_controller/src/trajectory.cpp index 22d43e1bfb..f5e217869a 100644 --- a/joint_trajectory_controller/src/trajectory.cpp +++ b/joint_trajectory_controller/src/trajectory.cpp @@ -177,6 +177,7 @@ bool Trajectory::sample( } start_segment_itr = begin() + static_cast(i); end_segment_itr = begin() + static_cast(i + 1); + output_state.time_from_start = next_point.time_from_start; last_sample_idx_ = i; return true; } diff --git a/joint_trajectory_controller/test/test_trajectory_controller.cpp b/joint_trajectory_controller/test/test_trajectory_controller.cpp index e82c8bd033..03cf4ac5c2 100644 --- a/joint_trajectory_controller/test/test_trajectory_controller.cpp +++ b/joint_trajectory_controller/test/test_trajectory_controller.cpp @@ -397,6 +397,27 @@ TEST_P(TrajectoryControllerTestParameterized, state_topic_consistency) EXPECT_EQ(n_joints, state->output.effort.size()); } } +TEST_F(TrajectoryControllerTest, time_from_start_populated) +{ + rclcpp::executors::SingleThreadedExecutor executor; + SetUpAndActivateTrajectoryController(executor, {}); + subscribeToState(executor); + + // schedule a single waypoint at 100ms: + builtin_interfaces::msg::Duration tfs; tfs.sec = 0; tfs.nanosec = 100000000; + publish(tfs, {INITIAL_POS_JOINTS}, rclcpp::Time(0)); + traj_controller_->wait_for_trajectory(executor); + + updateController(); + // give the publish timer one more spin + executor.spin_some(); + + auto state = getState(); + ASSERT_TRUE(state); + EXPECT_EQ(state->feedback.time_from_start.sec, 0u); + EXPECT_EQ(state->feedback.time_from_start.nanosec, 100000000u); +} + /** * @brief check if dynamic parameters are updated