Change MoveIt planner

This commit is contained in:
Michel Breyer 2021-10-13 11:59:10 +02:00
parent e5da49d0a6
commit 8a1b8130dc
2 changed files with 9 additions and 4 deletions

View File

@ -1,6 +1,6 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<launch> <launch>
<arg name="launch_rviz" default="false" /> <arg name="rviz" default="false" />
<!-- Load parameters --> <!-- Load parameters -->
<rosparam command="load" file="$(find active_grasp)/cfg/active_grasp.yaml" subst_value="true" /> <rosparam command="load" file="$(find active_grasp)/cfg/active_grasp.yaml" subst_value="true" />
@ -12,8 +12,10 @@
<!-- Launch MoveIt --> <!-- Launch MoveIt -->
<node pkg="tf2_ros" type="static_transform_publisher" name="to_panda" args="0 0 0 0 0 0 world panda_link0" /> <node pkg="tf2_ros" type="static_transform_publisher" name="to_panda" args="0 0 0 0 0 0 world panda_link0" />
<include file="$(find panda_moveit_config)/launch/move_group.launch" /> <include file="$(find panda_moveit_config)/launch/move_group.launch">
<arg name="pipeline" value="ompl"/>
</include>
<!-- Launch rviz --> <!-- Launch rviz -->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find active_grasp)/launch/active_grasp.rviz" if="$(arg launch_rviz)" /> <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(find active_grasp)/launch/active_grasp.rviz" />
</launch> </launch>

View File

@ -51,6 +51,9 @@ class GraspController:
def init_moveit(self): def init_moveit(self):
self.moveit = MoveItClient("panda_arm") self.moveit = MoveItClient("panda_arm")
rospy.sleep(1.0) # Wait for connections to be established. rospy.sleep(1.0) # Wait for connections to be established.
self.moveit.move_group.set_planner_id("PRMstarkConfigDefault")
self.moveit.move_group.set_num_planning_attempts(10)
self.moveit.move_group.set_planning_time(5.0)
def switch_to_cartesian_velocity_control(self): def switch_to_cartesian_velocity_control(self):
req = SwitchControllerRequest() req = SwitchControllerRequest()
@ -167,7 +170,7 @@ class GraspController:
self.moveit.goto(T_base_grasp * self.T_grasp_ee) self.moveit.goto(T_base_grasp * self.T_grasp_ee)
self.gripper.grasp() self.gripper.grasp()
self.moveit.goto(Transform.t([0, 0, 0.1]) * T_base_grasp * self.T_grasp_ee) self.moveit.goto(Transform.t([0, 0, 0.1]) * T_base_grasp * self.T_grasp_ee)
success = self.gripper.read() > 0.005 success = self.gripper.read() > 0.002
return "succeeded" if success else "failed" return "succeeded" if success else "failed"
def postprocess(self, T_base_grasp): def postprocess(self, T_base_grasp):