1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 10:00:48 +02:00

Changed how trajectories are handled to try and speed things up

This commit is contained in:
Thomas Timm Andersen
2015-09-22 10:34:09 +02:00
2 changed files with 5 additions and 4 deletions

View File

@@ -146,7 +146,7 @@ public:
t.push_back(0.);
t.push_back(4.);
t.push_back(8.);
robot_.doTraj(t, pos, vel); */
robot_.doTraj(t, pos, vel);*/
}
@@ -295,7 +295,8 @@ private:
traj.points[i].positions[mapping[j]]);
new_point.velocities.push_back(
traj.points[i].velocities[mapping[j]]);
new_point.accelerations.push_back(
if (traj.points[i].accelerations.size() != 0)
new_point.accelerations.push_back(
traj.points[i].accelerations[mapping[j]]);
}
new_point.time_from_start = traj.points[i].time_from_start;