You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Defining an approach and a retreat vector of Eigen::Isometry3d waypoints
Passing each through CartesianInterpolator::computeCartesianPath
Parameterizing each with TimeOptimalTrajectoryGeneration::computeTimeStamps
Appending them together with a pause in between
I just upgraded from Humble to Jazzy, and the formerly functional code started creating an unexpected motion. I narrowed the problem down to a change in computeTimeStamps (see ros-controls/ros2_controllers#1298 for more information on the observed motion).
In Humble, computeTimeStamps assigns 0 velocity / acceleration to the first point, while in Jazzy it assigns non-zero values. Therefore, when my code appends the two trajectories together with a pause, it ends up with sequential points that are the pause length apart with identical positions, but the first has 0 velocity / acceleration and the second does not.
The (slightly cleaned up) code for steps 3 & 4 is:
trajectory_processing::TimeOptimalTrajectoryGeneration totg;
totg.computeTimeStamps(*robot_trajectory, 1.0, 1.0);
totg.computeTimeStamps(retreat_trajectory, 1.0, 1.0);
// Hack to pause trajectories at final point because TOTG gives non-zero accelerationsconst std::vector<int>& idx = robot_trajectory->getGroup()->getVariableIndexList();
for (size_t i = 0; i < idx.size(); i++)
{
robot_trajectory->getLastWayPointPtr()->setVariableAcceleration(idx[i], 0);
retreat_trajectory.getLastWayPointPtr()->setVariableAcceleration(idx[i], 0);
}
robot_trajectory->append(retreat_trajectory, 3.5);
As you can see I already added a hack because in Humble the last waypoint had non-zero velocities and accelerations (I have not verified if that is still true in Jazzy). I could add the same hack for the first waypoint, but this seems like incorrect (or at best undefined) behavior.
I also suspect the problem is usually masked because normally 1) it's the first point in a trajectory so the robot is starting from rest anyway, and 2) the next point is only a few milliseconds later, so the controller blends them together into a qualitatively correct motion.
ROS Distro
Jazzy
OS and version
Ubuntu 24.04
Source or binary build?
Binary
If binary, which release version?
2.10.0
If source, which branch?
No response
Which RMW are you using?
FastRTPS
Steps to Reproduce
Generate a trajectory with CartesianInterpolator::computeCartesianPath
Parameterize it with TimeOptimalTrajectoryGeneration::computeTimeStamps
Expected behavior
The first (and last?) points should have 0 velocity and acceleration? I'm not sure which one is actually "correct", but I couldn't find any Pull Requests that address the change.
Actual behavior
The first (and last?) points have nonzero velocity and acceleration.
Backtrace or Console output
No response
The text was updated successfully, but these errors were encountered:
Description
I'm creating a UR5e trajectory by:
Eigen::Isometry3d
waypointsCartesianInterpolator::computeCartesianPath
TimeOptimalTrajectoryGeneration::computeTimeStamps
I just upgraded from Humble to Jazzy, and the formerly functional code started creating an unexpected motion. I narrowed the problem down to a change in
computeTimeStamps
(see ros-controls/ros2_controllers#1298 for more information on the observed motion).In Humble,
computeTimeStamps
assigns 0 velocity / acceleration to the first point, while in Jazzy it assigns non-zero values. Therefore, when my code appends the two trajectories together with a pause, it ends up with sequential points that are the pause length apart with identical positions, but the first has 0 velocity / acceleration and the second does not.The (slightly cleaned up) code for steps 3 & 4 is:
As you can see I already added a hack because in Humble the last waypoint had non-zero velocities and accelerations (I have not verified if that is still true in Jazzy). I could add the same hack for the first waypoint, but this seems like incorrect (or at best undefined) behavior.
I also suspect the problem is usually masked because normally 1) it's the first point in a trajectory so the robot is starting from rest anyway, and 2) the next point is only a few milliseconds later, so the controller blends them together into a qualitatively correct motion.
ROS Distro
Jazzy
OS and version
Ubuntu 24.04
Source or binary build?
Binary
If binary, which release version?
2.10.0
If source, which branch?
No response
Which RMW are you using?
FastRTPS
Steps to Reproduce
CartesianInterpolator::computeCartesianPath
TimeOptimalTrajectoryGeneration::computeTimeStamps
Expected behavior
The first (and last?) points should have 0 velocity and acceleration? I'm not sure which one is actually "correct", but I couldn't find any Pull Requests that address the change.
Actual behavior
The first (and last?) points have nonzero velocity and acceleration.
Backtrace or Console output
No response
The text was updated successfully, but these errors were encountered: