You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
We are working on a feature where we wanted to check collisions between the end-effector and some piece in a editor for grasps. However there were often no collisions at all.
Turns out that while one can define a JointModelGroup via a list of links in SRDF, the collision checking will only consider child links of any active joint:
So for a magnetic gripper or a suction gripper this will do no collision checks at all.
Should this rather check the union of getUpdatedLinkModelSet and getLinkModels? The first one to keep the current and expected behavior of including the gripper/end-effector when checking the robot, the second to include also non-actuated links?
The text was updated successfully, but these errors were encountered:
Are you sure that getUpdatedLinkModelsSet() doesn't include fixed joints, but only active ones?
I couldn't find a hint for that in code. Did you use the correct group?
We are working on a feature where we wanted to check collisions between the end-effector and some piece in a editor for grasps. However there were often no collisions at all.
Turns out that while one can define a JointModelGroup via a list of links in SRDF, the collision checking will only consider child links of any active joint:
https://github.com/ros-planning/moveit/blob/6863b711dde4b03e952ffdaf3fef3e8745a5a099/moveit_core/collision_detection_fcl/src/collision_common.cpp#L941
So for a magnetic gripper or a suction gripper this will do no collision checks at all.
Should this rather check the union of
getUpdatedLinkModelSet
andgetLinkModels
? The first one to keep the current and expected behavior of including the gripper/end-effector when checking the robot, the second to include also non-actuated links?The text was updated successfully, but these errors were encountered: