Skip to content

Commit

Permalink
Fix Pilz blending times... the right way (#2961)
Browse files Browse the repository at this point in the history
* Fix Pilz blending times... the right way

* Remove more debugs

* Format
  • Loading branch information
sea-bass authored Aug 11, 2024
1 parent f8738b2 commit 11b90d5
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 24 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -113,25 +113,7 @@ RobotTrajCont CommandListManager::solve(const planning_scene::PlanningSceneConst
(i > 0 ? radii.at(i - 1) : 0.));
}

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;
return plan_comp_builder_.build();
}

bool CommandListManager::checkRadiiForOverlap(const robot_trajectory::RobotTrajectory& traj_A, const double radii_A,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,13 +54,17 @@ std::vector<robot_trajectory::RobotTrajectoryPtr> PlanComponentsBuilder::build()
void PlanComponentsBuilder::appendWithStrictTimeIncrease(robot_trajectory::RobotTrajectory& result,
const robot_trajectory::RobotTrajectory& source)
{
if (result.empty() ||
!pilz_industrial_motion_planner::isRobotStateEqual(result.getLastWayPoint(), source.getFirstWayPoint(),
result.getGroupName(), ROBOT_STATE_EQUALITY_EPSILON))
if (result.empty())
{
result.append(source, 0.0);
return;
}
if (!pilz_industrial_motion_planner::isRobotStateEqual(result.getLastWayPoint(), source.getFirstWayPoint(),
result.getGroupName(), ROBOT_STATE_EQUALITY_EPSILON))
{
result.append(source, source.getWayPointDurationFromStart(0));
return;
}

for (size_t i = 1; i < source.getWayPointCount(); ++i)
{
Expand Down Expand Up @@ -94,7 +98,8 @@ void PlanComponentsBuilder::blend(const planning_scene::PlanningSceneConstPtr& p

// Append the new trajectory elements
appendWithStrictTimeIncrease(*(traj_cont_.back()), *blend_response.first_trajectory);
traj_cont_.back()->append(*blend_response.blend_trajectory, 0.0);
appendWithStrictTimeIncrease(*(traj_cont_.back()), *blend_response.blend_trajectory);

// Store the last new trajectory element for future processing
traj_tail_ = blend_response.second_trajectory; // first for next blending segment
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ bool pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::blend(
std::size_t second_intersection_index;
if (!searchIntersectionPoints(req, first_intersection_index, second_intersection_index))
{
RCLCPP_ERROR(getLogger(), "Blend radius to large.");
RCLCPP_ERROR(getLogger(), "Blend radius too large.");
res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
return false;
}
Expand Down Expand Up @@ -127,6 +127,7 @@ bool pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::blend(

// append the blend trajectory
res.blend_trajectory->setRobotTrajectoryMsg(req.first_trajectory->getFirstWayPoint(), blend_joint_trajectory);

// copy the points [second_intersection_index, len] from the second trajectory
for (size_t i = second_intersection_index + 1; i < req.second_trajectory->getWayPointCount(); ++i)
{
Expand Down

0 comments on commit 11b90d5

Please sign in to comment.