-
Notifications
You must be signed in to change notification settings - Fork 571
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Handle unsupported position constraints in OMPL #2417
Handle unsupported position constraints in OMPL #2417
Conversation
OMPL constrained planning assumes that all position constraints have three dimensions, meaning that they are represented by a BOX bounding volume. If another shape is used (like a SPHERE from moveit_core/kinematic_constraints/utils.hpp), the constraint adapter implementation will produce a segfault because of the lack of dimensions. This fix prevents this by checking for the required BOX type.
Codecov ReportAttention:
Additional details and impacted files@@ Coverage Diff @@
## main #2417 +/- ##
==========================================
- Coverage 51.10% 50.73% -0.36%
==========================================
Files 387 386 -1
Lines 32262 32092 -170
==========================================
- Hits 16483 16279 -204
- Misses 15779 15813 +34 ☔ View full report in Codecov by Sentry. |
const auto& primitives = constraints.position_constraints.at(0).constraint_region.primitives; | ||
if (primitives.empty() || primitives.at(0).type != shape_msgs::msg::SolidPrimitive::BOX) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Based on how the BoxConstraint
and EqualityPositionConstraint
parsing works, I think we maybe also want a warning if the number of primitives is greater than 1, saying that only the first primitive will be used?
moveit_planners/ompl/ompl_interface/src/detail/ompl_constraints.cpp
Outdated
Show resolved
Hide resolved
This pull request is in conflict. Could you fix it @henningkayser? |
* Handle unsupported position constraints in OMPL OMPL constrained planning assumes that all position constraints have three dimensions, meaning that they are represented by a BOX bounding volume. If another shape is used (like a SPHERE from moveit_core/kinematic_constraints/utils.hpp), the constraint adapter implementation will produce a segfault because of the lack of dimensions. This fix prevents this by checking for the required BOX type. * Add warning if more than one position primitive is used --------- Co-authored-by: Sebastian Jahr <sebastian.jahr@picknik.ai> (cherry picked from commit b0401e9) # Conflicts: # moveit_planners/ompl/ompl_interface/src/detail/ompl_constraints.cpp
* Handle unsupported position constraints in OMPL OMPL constrained planning assumes that all position constraints have three dimensions, meaning that they are represented by a BOX bounding volume. If another shape is used (like a SPHERE from moveit_core/kinematic_constraints/utils.hpp), the constraint adapter implementation will produce a segfault because of the lack of dimensions. This fix prevents this by checking for the required BOX type. * Add warning if more than one position primitive is used --------- Co-authored-by: Sebastian Jahr <sebastian.jahr@picknik.ai> (cherry picked from commit b0401e9) # Conflicts: # moveit_planners/ompl/ompl_interface/src/detail/ompl_constraints.cpp
OMPL constrained planning assumes that all position constraints have three dimensions, meaning that they are represented by a BOX bounding volume. If another shape is used (like a SPHERE from moveit_core/kinematic_constraints/utils.hpp), the constraint adapter implementation will produce a segfault because of the lack of dimensions. This fix prevents this by checking for the required BOX type.