Skip to content

Commit

Permalink
MoveRelative: handle equal min/max distance
Browse files Browse the repository at this point in the history
When min_distance == max_distance > 0.0, the minimal distance
might be missed due to numerical errors.
To avoid this, deactivate minimal distance check and
run the full distance as given by max_distance.
  • Loading branch information
rhaschke committed Jul 15, 2024
1 parent 8d2baf2 commit 160c48b
Showing 1 changed file with 5 additions and 0 deletions.
5 changes: 5 additions & 0 deletions core/src/stages/move_relative.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,11 @@ bool MoveRelative::compute(const InterfaceState& state, planning_scene::Planning

double max_distance = props.get<double>("max_distance");
double min_distance = props.get<double>("min_distance");

// if min_distance == max_distance, resort to moving full distance (negative min_distance)
if (max_distance > 0.0 && std::fabs(max_distance - min_distance) < std::numeric_limits<double>::epsilon())
min_distance = -1.0;

const auto& path_constraints = props.get<moveit_msgs::Constraints>("path_constraints");

robot_trajectory::RobotTrajectoryPtr robot_trajectory;
Expand Down

0 comments on commit 160c48b

Please sign in to comment.