48 import moveit_commander
50 from geometry_msgs.msg
import PoseStamped
56 PLANNING_GROUP =
"panda_arm"
69 ps.header.frame_id =
"world"
70 ps.pose.position.x = 0.4
71 ps.pose.position.y = 0.1
72 ps.pose.position.z = 0.25
73 self.planning_scene_interface.add_box(
74 name=
"box1", pose=ps, size=(0.1, 0.1, 0.5)
79 tcp_link = self.group.get_end_effector_link()
80 ps2.header.frame_id = tcp_link
81 ps2.pose.position.z = 0.15
82 self.planning_scene_interface.attach_box(
87 touch_links=[
"panda_rightfinger",
"panda_leftfinger"],
91 target_pose = self.group.get_current_pose(tcp_link)
92 target_pose.pose.position.y += 0.1
104 self.group.set_planning_pipeline_id(
"pilz_industrial_motion_planner")
105 self.group.set_planner_id(
"PTP")
106 self.group.set_pose_target(target_pose)
107 success, plan, time, error_code = self.group.
plan()
110 self.assertFalse(success)
111 self.assertEqual(error_code.val, MoveItErrorCodes.INVALID_MOTION_PLAN)
114 if __name__ ==
"__main__":
115 PKGNAME =
"moveit_ros_planning_interface"
116 NODENAME =
"moveit_test_python_move_group"
117 rospy.init_node(NODENAME)
118 rostest.rosrun(PKGNAME, NODENAME, PythonMoveGroupPlanningTest)
def test_planning_with_collision_objects(self)