Skip to content

Commit fe85da4

Browse files
JTC trajectory end time validation fix (#1090)
(cherry picked from commit b51e4c2)
1 parent 12a2ef2 commit fe85da4

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
@@ -1361,17 +1361,20 @@ bool JointTrajectoryController::validate_trajectory_msg(
13611361
return false;
13621362
}
13631363

1364+
if (trajectory.points.empty())
1365+
{
1366+
RCLCPP_ERROR(get_node()->get_logger(), "Empty trajectory received.");
1367+
return false;
1368+
}
1369+
13641370
const auto trajectory_start_time = static_cast<rclcpp::Time>(trajectory.header.stamp);
13651371
// If the starting time it set to 0.0, it means the controller should start it now.
13661372
// Otherwise we check if the trajectory ends before the current time,
13671373
// in which case it can be ignored.
13681374
if (trajectory_start_time.seconds() != 0.0)
13691375
{
1370-
auto trajectory_end_time = trajectory_start_time;
1371-
for (const auto & p : trajectory.points)
1372-
{
1373-
trajectory_end_time += p.time_from_start;
1374-
}
1376+
auto const trajectory_end_time =
1377+
trajectory_start_time + trajectory.points.back().time_from_start;
13751378
if (trajectory_end_time < get_node()->now())
13761379
{
13771380
RCLCPP_ERROR(
@@ -1396,12 +1399,6 @@ bool JointTrajectoryController::validate_trajectory_msg(
13961399
}
13971400
}
13981401

1399-
if (trajectory.points.empty())
1400-
{
1401-
RCLCPP_ERROR(get_node()->get_logger(), "Empty trajectory received.");
1402-
return false;
1403-
}
1404-
14051402
if (!params_.allow_nonzero_velocity_at_trajectory_end)
14061403
{
14071404
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
@@ -1398,6 +1398,17 @@ TEST_P(TrajectoryControllerTestParameterized, invalid_message)
13981398
traj_msg = good_traj_msg;
13991399
traj_msg.points.push_back(traj_msg.points.front());
14001400
EXPECT_FALSE(traj_controller_->validate_trajectory_msg(traj_msg));
1401+
1402+
// End time in the past
1403+
traj_msg = good_traj_msg;
1404+
traj_msg.header.stamp = rclcpp::Time(1);
1405+
EXPECT_FALSE(traj_controller_->validate_trajectory_msg(traj_msg));
1406+
1407+
// End time in the future
1408+
traj_msg = good_traj_msg;
1409+
traj_msg.header.stamp = traj_controller_->get_node()->now();
1410+
traj_msg.points[0].time_from_start = rclcpp::Duration::from_seconds(10);
1411+
EXPECT_TRUE(traj_controller_->validate_trajectory_msg(traj_msg));
14011412
}
14021413

14031414
/**

0 commit comments

Comments
 (0)