Specification of move_group in mplib.Planner
Hello,
Thank you for your efforts in developing this lightweight planner!
As a beginner in this field, I have a question regarding the move_group in mplib.Planner. I followed the demonstration and used "panda_hand" as the move group. I also updated the point cloud using self.planner.update_point_cloud to avoid collisions.
However, I've noticed that the grippers still collide with the updated point clouds. Does the planner only consider the move group and not the collision detection for the grippers? If so, how can I resolve this issue?
Thank you for your assistance!
Hi, It should consider the grippers. My guess is somehow the visual mesh is not perfectly aligned with the collision mesh and you can increase the margin of what is considered collision.
Hi, It should consider the grippers. My guess is somehow the visual mesh is not perfectly aligned with the collision mesh and you can increase the margin of what is considered collision.
Thank you for your quick response. I'm currently using mplib==0.2.1, and here is my planner initialization code:
self.planner = mplib.Planner(
urdf=self.asset_prefix + "/panda/panda_v3.urdf",
srdf=self.asset_prefix + "/panda/panda_v3.srdf",
user_link_names=link_names,
user_joint_names=joint_names,
move_group="panda_hand",
joint_vel_limits=np.ones(7),
joint_acc_limits=np.ones(7))
I noticed that the planner initializes a variable called self.move_group_joint_indices, which is [0, 1, 2, 3, 4, 5, 6, 7] when move_group is set to panda_hand (likely from root_link to panda_hand). This seems to exclude the gripper joints.
Then in the Planner.IK() function, the planning world sets move_group_joint_indices and checks for collisions as follows:
self.planning_world.set_qpos_all(ik_qpos[move_joint_idx])
if len(collisions := self.planning_world.check_collision()) > 0:
success = False
It appears that this process does not account for the gripper's joint positions. As a result, the gripper's state might not be properly considered during collision checking.
Finally in the follow_path function, only the planned pose of the joints listed in self.move_group_joint_indices are used to control the franka arm. This means that the gripper's motion is not constrained and can move freely, potentially causing collisions.
I wanted to confirm if my understanding is correct and if there is a way to address this issue. Please let me know if I have missed something or if there is a recommended approach to handle the gripper's joint positions during planning and collision checking.
Thank you for your time and assistance.
It is normal for move group to exclude gripper joints. You usually want to control the gripper separately and don't want to involve the grippers into planning.
As far as I remember, during planning, OMPL has an interface to check if the state is valid. See here. That involves checking for collision. Now, gripper collision with point cloud is checked here.
I cannot remember if the gripper is considered for collision. You are right that we don't set its position but if it is part of the collision consideration, we would just take its current pose.
You can use this function to print out all the collision objects of the fcl model.