Skip to content

Commit 338cece

Browse files
authored
Fill point_before_trajectory with same information as trajectory (backport #2043) (#2049)
1 parent a0a562a commit 338cece

File tree

3 files changed

+71
-0
lines changed

3 files changed

+71
-0
lines changed

doc/release_notes.rst

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,10 @@ joint_trajectory_controller
4545
allowed to move without restriction.
4646
4747
* Add the boolean parameter ``set_last_command_interface_value_as_state_on_activation``. When set to ``true``, the last command interface value is used as both the current state and the last commanded state upon activation. When set to ``false``, the current state is used for both (`#1231 <https://github.com/ros-controls/ros2_controllers/pull/1231>`_).
48+
* Fill in 0 velocities and accelerations into point before trajectories if the state interfaces
49+
don't contain velocity / acceleration information, but the trajectory does. This way, the segment
50+
up to the first waypoint will use the same interpolation as the rest of the trajectory. (`#2043
51+
<https://github.com/ros-controls/ros2_controllers/pull/2043>`_)
4852

4953
mecanum_drive_controller
5054
************************

joint_trajectory_controller/src/trajectory.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,20 @@ void Trajectory::set_point_before_trajectory_msg(
5151
time_before_traj_msg_ = current_time;
5252
state_before_traj_msg_ = current_point;
5353

54+
// If the current state doesn't contain velocities / accelerations, but the first trajectory
55+
// point does, initialize them to zero. Otherwise the segment going from the current state to the
56+
// first trajectory point will use another degree of spline interpolation than the rest of the
57+
// trajectory.
58+
if (current_point.velocities.empty() && !trajectory_msg_->points[0].velocities.empty())
59+
{
60+
state_before_traj_msg_.velocities.resize(trajectory_msg_->points[0].velocities.size(), 0.0);
61+
}
62+
if (current_point.accelerations.empty() && !trajectory_msg_->points[0].accelerations.empty())
63+
{
64+
state_before_traj_msg_.accelerations.resize(
65+
trajectory_msg_->points[0].accelerations.size(), 0.0);
66+
}
67+
5468
// Compute offsets due to wrapping joints
5569
wraparound_joint(
5670
state_before_traj_msg_.positions, trajectory_msg_->points[0].positions,

joint_trajectory_controller/test/test_trajectory.cpp

Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -728,6 +728,59 @@ TEST(TestTrajectory, sample_trajectory_acceleration_with_interpolation)
728728
}
729729
}
730730

731+
TEST(TestTrajectory, fill_point_before_with_same_degree_as_traj)
732+
{
733+
auto full_msg = std::make_shared<trajectory_msgs::msg::JointTrajectory>();
734+
full_msg->header.stamp = rclcpp::Time(0);
735+
736+
// definitions
737+
double time_first_seg = 1.0;
738+
double time_second_seg = 2.0;
739+
double position_first_seg = 1.0;
740+
double position_second_seg = 2.0;
741+
double velocity_first_seg = 0.0;
742+
double velocity_second_seg = 0.0;
743+
double acceleration_first_seg = 0.0;
744+
double acceleration_second_seg = 0.0;
745+
746+
trajectory_msgs::msg::JointTrajectoryPoint p1;
747+
p1.time_from_start = rclcpp::Duration::from_seconds(time_first_seg);
748+
p1.positions.push_back(position_first_seg);
749+
p1.velocities.push_back(velocity_first_seg);
750+
p1.accelerations.push_back(acceleration_first_seg);
751+
full_msg->points.push_back(p1);
752+
753+
trajectory_msgs::msg::JointTrajectoryPoint p2;
754+
p2.time_from_start = rclcpp::Duration::from_seconds(time_second_seg);
755+
p2.positions.push_back(position_second_seg);
756+
p2.velocities.push_back(velocity_second_seg);
757+
p2.accelerations.push_back(acceleration_second_seg);
758+
full_msg->points.push_back(p2);
759+
760+
trajectory_msgs::msg::JointTrajectoryPoint point_before_msg;
761+
point_before_msg.time_from_start = rclcpp::Duration::from_seconds(0.0);
762+
point_before_msg.positions.push_back(0.0);
763+
764+
const rclcpp::Time time_now = rclcpp::Clock().now();
765+
auto traj = joint_trajectory_controller::Trajectory(time_now, point_before_msg, full_msg);
766+
767+
trajectory_msgs::msg::JointTrajectoryPoint expected_state;
768+
joint_trajectory_controller::TrajectoryPointConstIter start, end;
769+
770+
// sample at trajectory starting time
771+
// Since the trajectory defines positions, velocities, and accelerations, we expect quintic
772+
// spline interpolation. Due to the unspecified initial acceleration, it should be zero.
773+
{
774+
traj.sample(time_now, DEFAULT_INTERPOLATION, expected_state, start, end);
775+
EXPECT_EQ(0, traj.last_sample_index());
776+
ASSERT_EQ(traj.begin(), start);
777+
ASSERT_EQ(traj.begin(), end);
778+
EXPECT_NEAR(point_before_msg.positions[0], expected_state.positions[0], EPS);
779+
EXPECT_NEAR(0.0, expected_state.velocities[0], EPS);
780+
EXPECT_NEAR(0.0, expected_state.accelerations[0], EPS);
781+
}
782+
}
783+
731784
TEST(TestTrajectory, skip_interpolation)
732785
{
733786
// Simple passthrough without extra interpolation

0 commit comments

Comments
 (0)