Skip to content
Original file line number Diff line number Diff line change
Expand Up @@ -1313,9 +1313,11 @@ void JointTrajectoryController::publish_state(
if (state_publisher_)
{
state_msg_.header.stamp = time;
state_msg_.reference.time_from_start = desired_state.time_from_start;
state_msg_.reference.positions = desired_state.positions;
state_msg_.reference.velocities = desired_state.velocities;
state_msg_.reference.accelerations = desired_state.accelerations;
state_msg_.feedback.time_from_start = current_state.time_from_start;
state_msg_.feedback.positions = current_state.positions;
state_msg_.error.positions = state_error.positions;
if (has_velocity_state_interface_)
Expand Down
1 change: 1 addition & 0 deletions joint_trajectory_controller/src/trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,7 @@ bool Trajectory::sample(
}
start_segment_itr = begin() + static_cast<TrajectoryPointConstIter::difference_type>(i);
end_segment_itr = begin() + static_cast<TrajectoryPointConstIter::difference_type>(i + 1);
output_state.time_from_start = next_point.time_from_start;
if (search_monotonically_increasing)
{
last_sample_idx_ = i;
Expand Down
27 changes: 27 additions & 0 deletions joint_trajectory_controller/test/test_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -460,6 +460,33 @@ TEST_P(TrajectoryControllerTestParameterized, state_topic_consistency_command_jo
}
}

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 = 100000000u;
publish(tfs, {INITIAL_POS_JOINTS}, rclcpp::Time(0));
traj_controller_->wait_for_trajectory(executor);

// update for 0.2s
updateController(rclcpp::Duration::from_seconds(0.2));
// give the publish timer one more spin
executor.spin_some();

auto state = getState();
ASSERT_TRUE(state);
// should be around 0.2s
EXPECT_EQ(state->feedback.time_from_start.sec, 0u);
EXPECT_NEAR(state->feedback.time_from_start.nanosec, 200000000u, 10000000u);
EXPECT_EQ(state->reference.time_from_start.sec, 0u);
EXPECT_NEAR(state->reference.time_from_start.nanosec, 200000000u, 10000000u);
}

/**
* @brief check if dynamic parameters are updated
*/
Expand Down