Skip to content

Commit 487760e

Browse files
bmagyarmergify[bot]
authored andcommitted
Add time_from_start to action feedback and state message (cherry-pick #1755) (#1820)
(cherry picked from commit 4c4a13e)
1 parent 8676ab0 commit 487760e

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
@@ -1218,9 +1218,11 @@ void JointTrajectoryController::publish_state(
12181218
if (state_publisher_)
12191219
{
12201220
state_msg_.header.stamp = time;
1221+
state_msg_.reference.time_from_start = desired_state.time_from_start;
12211222
state_msg_.reference.positions = desired_state.positions;
12221223
state_msg_.reference.velocities = desired_state.velocities;
12231224
state_msg_.reference.accelerations = desired_state.accelerations;
1225+
state_msg_.feedback.time_from_start = current_state.time_from_start;
12241226
state_msg_.feedback.positions = current_state.positions;
12251227
state_msg_.error.positions = state_error.positions;
12261228
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
@@ -461,6 +461,33 @@ TEST_P(TrajectoryControllerTestParameterized, state_topic_consistency_command_jo
461461
}
462462
}
463463

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

0 commit comments

Comments
 (0)