Skip to content

Commit b51e4c2

Browse files
JTC trajectory end time validation fix (#1090)
1 parent 4008030 commit b51e4c2

File tree

2 files changed

+19
-11
lines changed

2 files changed

+19
-11
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 8 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -1370,17 +1370,20 @@ bool JointTrajectoryController::validate_trajectory_msg(
13701370
return false;
13711371
}
13721372

1373+
if (trajectory.points.empty())
1374+
{
1375+
RCLCPP_ERROR(get_node()->get_logger(), "Empty trajectory received.");
1376+
return false;
1377+
}
1378+
13731379
const auto trajectory_start_time = static_cast<rclcpp::Time>(trajectory.header.stamp);
13741380
// If the starting time it set to 0.0, it means the controller should start it now.
13751381
// Otherwise we check if the trajectory ends before the current time,
13761382
// in which case it can be ignored.
13771383
if (trajectory_start_time.seconds() != 0.0)
13781384
{
1379-
auto trajectory_end_time = trajectory_start_time;
1380-
for (const auto & p : trajectory.points)
1381-
{
1382-
trajectory_end_time += p.time_from_start;
1383-
}
1385+
auto const trajectory_end_time =
1386+
trajectory_start_time + trajectory.points.back().time_from_start;
13841387
if (trajectory_end_time < get_node()->now())
13851388
{
13861389
RCLCPP_ERROR(
@@ -1405,12 +1408,6 @@ bool JointTrajectoryController::validate_trajectory_msg(
14051408
}
14061409
}
14071410

1408-
if (trajectory.points.empty())
1409-
{
1410-
RCLCPP_ERROR(get_node()->get_logger(), "Empty trajectory received.");
1411-
return false;
1412-
}
1413-
14141411
if (!params_.allow_nonzero_velocity_at_trajectory_end)
14151412
{
14161413
for (size_t i = 0; i < trajectory.points.back().velocities.size(); ++i)

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1384,6 +1384,17 @@ TEST_P(TrajectoryControllerTestParameterized, invalid_message)
13841384
traj_msg = good_traj_msg;
13851385
traj_msg.points.push_back(traj_msg.points.front());
13861386
EXPECT_FALSE(traj_controller_->validate_trajectory_msg(traj_msg));
1387+
1388+
// End time in the past
1389+
traj_msg = good_traj_msg;
1390+
traj_msg.header.stamp = rclcpp::Time(1);
1391+
EXPECT_FALSE(traj_controller_->validate_trajectory_msg(traj_msg));
1392+
1393+
// End time in the future
1394+
traj_msg = good_traj_msg;
1395+
traj_msg.header.stamp = traj_controller_->get_node()->now();
1396+
traj_msg.points[0].time_from_start = rclcpp::Duration::from_seconds(10);
1397+
EXPECT_TRUE(traj_controller_->validate_trajectory_msg(traj_msg));
13871398
}
13881399

13891400
/**

0 commit comments

Comments
 (0)