Skip to content

Commit d50b6ba

Browse files
MikeWrockbmagyar
authored andcommitted
[JTC] added time_from_start to action feedback (ros-controls#1755)
1 parent a10c564 commit d50b6ba

File tree

3 files changed

+24
-0
lines changed

3 files changed

+24
-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
@@ -1240,8 +1240,10 @@ void JointTrajectoryController::publish_state(
12401240
state_publisher_->msg_.reference.positions = desired_state.positions;
12411241
state_publisher_->msg_.reference.velocities = desired_state.velocities;
12421242
state_publisher_->msg_.reference.accelerations = desired_state.accelerations;
1243+
state_publisher_->msg_.reference.time_from_start = desired_state.time_from_start;
12431244
state_publisher_->msg_.feedback.positions = current_state.positions;
12441245
state_publisher_->msg_.error.positions = state_error.positions;
1246+
state_publisher_->msg_.feedback.time_from_start = desired_state.time_from_start;
12451247
if (has_velocity_state_interface_)
12461248
{
12471249
state_publisher_->msg_.feedback.velocities = current_state.velocities;

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: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -461,6 +461,27 @@ TEST_P(TrajectoryControllerTestParameterized, state_topic_consistency_command_jo
461461
EXPECT_EQ(n_joints, state->output.effort.size());
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; tfs.sec = 0; tfs.nanosec = 100000000;
472+
publish(tfs, {INITIAL_POS_JOINTS}, rclcpp::Time(0));
473+
traj_controller_->wait_for_trajectory(executor);
474+
475+
updateController();
476+
// give the publish timer one more spin
477+
executor.spin_some();
478+
479+
auto state = getState();
480+
ASSERT_TRUE(state);
481+
EXPECT_EQ(state->feedback.time_from_start.sec, 0u);
482+
EXPECT_EQ(state->feedback.time_from_start.nanosec, 100000000u);
483+
}
484+
464485

465486
/**
466487
* @brief check if dynamic parameters are updated

0 commit comments

Comments
 (0)