Skip to content

Commit 4c4a13e

Browse files
authored
Add time_from_start to action feedback and state message (cherry-pick #1755) (#1820)
1 parent 63bae1b commit 4c4a13e

File tree

3 files changed

+30
-0
lines changed

3 files changed

+30
-0
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1313,9 +1313,11 @@ void JointTrajectoryController::publish_state(
13131313
if (state_publisher_)
13141314
{
13151315
state_msg_.header.stamp = time;
1316+
state_msg_.reference.time_from_start = desired_state.time_from_start;
13161317
state_msg_.reference.positions = desired_state.positions;
13171318
state_msg_.reference.velocities = desired_state.velocities;
13181319
state_msg_.reference.accelerations = desired_state.accelerations;
1320+
state_msg_.feedback.time_from_start = current_state.time_from_start;
13191321
state_msg_.feedback.positions = current_state.positions;
13201322
state_msg_.error.positions = state_error.positions;
13211323
if (has_velocity_state_interface_)

joint_trajectory_controller/src/trajectory.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -177,6 +177,7 @@ bool Trajectory::sample(
177177
}
178178
start_segment_itr = begin() + static_cast<TrajectoryPointConstIter::difference_type>(i);
179179
end_segment_itr = begin() + static_cast<TrajectoryPointConstIter::difference_type>(i + 1);
180+
output_state.time_from_start = next_point.time_from_start;
180181
if (search_monotonically_increasing)
181182
{
182183
last_sample_idx_ = i;

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -460,6 +460,33 @@ TEST_P(TrajectoryControllerTestParameterized, state_topic_consistency_command_jo
460460
}
461461
}
462462

463+
TEST_F(TrajectoryControllerTest, time_from_start_populated)
464+
{
465+
rclcpp::executors::SingleThreadedExecutor executor;
466+
SetUpAndActivateTrajectoryController(executor, {});
467+
subscribeToState(executor);
468+
469+
// schedule a single waypoint at 100ms:
470+
builtin_interfaces::msg::Duration tfs;
471+
tfs.sec = 0;
472+
tfs.nanosec = 100000000u;
473+
publish(tfs, {INITIAL_POS_JOINTS}, rclcpp::Time(0));
474+
traj_controller_->wait_for_trajectory(executor);
475+
476+
// update for 0.2s
477+
updateController(rclcpp::Duration::from_seconds(0.2));
478+
// give the publish timer one more spin
479+
executor.spin_some();
480+
481+
auto state = getState();
482+
ASSERT_TRUE(state);
483+
// should be around 0.2s
484+
EXPECT_EQ(state->feedback.time_from_start.sec, 0u);
485+
EXPECT_NEAR(state->feedback.time_from_start.nanosec, 200000000u, 10000000u);
486+
EXPECT_EQ(state->reference.time_from_start.sec, 0u);
487+
EXPECT_NEAR(state->reference.time_from_start.nanosec, 200000000u, 10000000u);
488+
}
489+
463490
/**
464491
* @brief check if dynamic parameters are updated
465492
*/

0 commit comments

Comments
 (0)