Skip to content

Commit 11e8ad7

Browse files
JTC trajectory end time validation fix (#1090) (#1140)
(cherry picked from commit b51e4c2) Co-authored-by: Henry Moore <[email protected]>
1 parent 25d8036 commit 11e8ad7

File tree

2 files changed

+19
-11
lines changed

2 files changed

+19
-11
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

+8-11
Original file line numberDiff line numberDiff line change
@@ -1442,17 +1442,20 @@ bool JointTrajectoryController::validate_trajectory_msg(
14421442
return false;
14431443
}
14441444

1445+
if (trajectory.points.empty())
1446+
{
1447+
RCLCPP_ERROR(get_node()->get_logger(), "Empty trajectory received.");
1448+
return false;
1449+
}
1450+
14451451
const auto trajectory_start_time = static_cast<rclcpp::Time>(trajectory.header.stamp);
14461452
// If the starting time it set to 0.0, it means the controller should start it now.
14471453
// Otherwise we check if the trajectory ends before the current time,
14481454
// in which case it can be ignored.
14491455
if (trajectory_start_time.seconds() != 0.0)
14501456
{
1451-
auto trajectory_end_time = trajectory_start_time;
1452-
for (const auto & p : trajectory.points)
1453-
{
1454-
trajectory_end_time += p.time_from_start;
1455-
}
1457+
auto const trajectory_end_time =
1458+
trajectory_start_time + trajectory.points.back().time_from_start;
14561459
if (trajectory_end_time < get_node()->now())
14571460
{
14581461
RCLCPP_ERROR(
@@ -1477,12 +1480,6 @@ bool JointTrajectoryController::validate_trajectory_msg(
14771480
}
14781481
}
14791482

1480-
if (trajectory.points.empty())
1481-
{
1482-
RCLCPP_ERROR(get_node()->get_logger(), "Empty trajectory received.");
1483-
return false;
1484-
}
1485-
14861483
if (!params_.allow_nonzero_velocity_at_trajectory_end)
14871484
{
14881485
for (size_t i = 0; i < trajectory.points.back().velocities.size(); ++i)

joint_trajectory_controller/test/test_trajectory_controller.cpp

+11
Original file line numberDiff line numberDiff line change
@@ -1304,6 +1304,17 @@ TEST_P(TrajectoryControllerTestParameterized, invalid_message)
13041304
traj_msg = good_traj_msg;
13051305
traj_msg.points.push_back(traj_msg.points.front());
13061306
EXPECT_FALSE(traj_controller_->validate_trajectory_msg(traj_msg));
1307+
1308+
// End time in the past
1309+
traj_msg = good_traj_msg;
1310+
traj_msg.header.stamp = rclcpp::Time(1);
1311+
EXPECT_FALSE(traj_controller_->validate_trajectory_msg(traj_msg));
1312+
1313+
// End time in the future
1314+
traj_msg = good_traj_msg;
1315+
traj_msg.header.stamp = traj_controller_->get_node()->now();
1316+
traj_msg.points[0].time_from_start = rclcpp::Duration::from_seconds(10);
1317+
EXPECT_TRUE(traj_controller_->validate_trajectory_msg(traj_msg));
13071318
}
13081319

13091320
/**

0 commit comments

Comments
 (0)