Skip to content

Commit

Permalink
Merge branch 'main' into forward-ports
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr authored Aug 2, 2024
2 parents 9e5dbc2 + 955f308 commit 6f5a385
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -244,6 +244,17 @@ class RobotTrajectory

void swap(robot_trajectory::RobotTrajectory& other) noexcept;

/**
* \brief Remove a point from the trajectory
* \param index - the index to remove
*/
RobotTrajectory& removeWayPoint(std::size_t index)
{
waypoints_.erase(waypoints_.begin() + index);
duration_from_previous_.erase(duration_from_previous_.begin() + index);
return *this;
}

RobotTrajectory& clear()
{
waypoints_.clear();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@

#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <geometry_msgs/msg/twist.hpp>

namespace pilz_industrial_motion_planner
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,26 @@ RobotTrajCont CommandListManager::solve(const planning_scene::PlanningSceneConst
// therefore: "i-1".
(i > 0 ? radii.at(i - 1) : 0.));
}
return plan_comp_builder_.build();

const auto res_vec = plan_comp_builder_.build();

// De-duplicate trajectory points with the same time value.
// This is necessary since some controllers do not allow times that are not monotonically increasing.
// TODO: Ideally, we would not need this code if the trajectory segments were created without
// duplicate time points in the first place. Leaving this note to revisit this with a more principled fix.
for (const auto& traj : res_vec)
{
for (size_t i = 0; i < traj->size() - 1; ++i)
{
if (traj->getWayPointDurationFromStart(i) == traj->getWayPointDurationFromStart(i + 1))
{
RCLCPP_WARN(getLogger(), "Removed duplicate point at time=%f", traj->getWayPointDurationFromStart(i));
traj->removeWayPoint(i + 1);
}
}
}

return res_vec;
}

bool CommandListManager::checkRadiiForOverlap(const robot_trajectory::RobotTrajectory& traj_A, const double radii_A,
Expand Down

0 comments on commit 6f5a385

Please sign in to comment.