moveit2
The MoveIt Motion Planning Framework for ROS 2.
python_move_group_planning.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2021, Cristian C. Beltran-Hernandez
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of Cristian C. Beltran-Hernandez nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #
35 # Author: Cristian C. Beltran-Hernandez
36 #
37 # This test is used to ensure planning with an attached object
38 # correctly validates collision states between the attached objects
39 # and the environment
40 
41 import unittest
42 import numpy as np
43 import rospy
44 import rostest
45 import os
46 
47 from moveit_msgs.msg import MoveItErrorCodes
48 import moveit_commander
49 
50 from geometry_msgs.msg import PoseStamped
51 
52 
53 class PythonMoveGroupPlanningTest(unittest.TestCase):
54  @classmethod
55  def setUpClass(self):
56  PLANNING_GROUP = "panda_arm"
57  self.groupgroup = moveit_commander.MoveGroupCommander(PLANNING_GROUP)
59  synchronous=True
60  )
61 
62  @classmethod
63  def tearDown(self):
64  pass
65 
67  # Add obstacle to the world
68  ps = PoseStamped()
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)
75  )
76 
77  # Attach object to robot's TCP
78  ps2 = PoseStamped()
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(
83  link=tcp_link,
84  name="box2",
85  pose=ps2,
86  size=(0.1, 0.1, 0.1),
87  touch_links=["panda_rightfinger", "panda_leftfinger"],
88  )
89 
90  # Plan a motion where the attached object 'box2' collides with the obstacle 'box1'
91  target_pose = self.group.get_current_pose(tcp_link)
92  target_pose.pose.position.y += 0.1
93 
94  # # Set planner to be Pilz's Linear Planner
95  # self.group.set_planning_pipeline_id("pilz_industrial_motion_planner")
96  # self.group.set_planner_id("LIN")
97  # self.group.set_pose_target(target_pose)
98  # success, plan, time, error_code = self.group.plan()
99 
100  # # Planning should fail
101  # self.assertEqual(error_code.val, MoveItErrorCodes.INVALID_MOTION_PLAN)
102 
103  # Set planner to be Pilz's Point-To-Point Planner
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()
108 
109  # Planning should fail
110  self.assertFalse(success)
111  self.assertEqual(error_code.val, MoveItErrorCodes.INVALID_MOTION_PLAN)
112 
113 
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)
Definition: plan.py:1