python_moveit_commander.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage, Inc. 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: William Baker
36 
37 import unittest
38 
39 import genpy
40 import numpy as np
41 import rospy
42 import rostest
43 import os
44 
45 from moveit_msgs.msg import (
46  RobotState,
47  PlanningSceneComponents,
48  PlanningScene,
49 )
50 from sensor_msgs.msg import JointState
51 
52 from moveit_commander import (
53  RobotCommander,
54  PlanningSceneInterface,
55  MoveItCommanderException,
56 )
57 
58 
59 class PythonMoveitCommanderTest(unittest.TestCase):
60  PLANNING_GROUP = "manipulator"
61  JOINT_NAMES = [
62  "joint_1",
63  "joint_2",
64  "joint_3",
65  "joint_4",
66  "joint_5",
67  "joint_6",
68  ]
69 
70  @classmethod
71  def setUpClass(self):
72  self.commander = RobotCommander("robot_description")
73  self.group = self.commander.get_group(self.PLANNING_GROUP)
74 
75  @classmethod
76  def tearDown(self):
77  pass
78 
80  in_msg = RobotState()
81  with self.assertRaises(genpy.DeserializationError):
82  self.group.enforce_bounds(in_msg)
83 
85  in_msg = RobotState()
86  in_msg.joint_state.header.frame_id = "base_link"
87  in_msg.joint_state.name = self.JOINT_NAMES
88  in_msg.joint_state.position = [0] * 6
89  in_msg.joint_state.position[0] = 1000
90 
91  out_msg = self.group.enforce_bounds(in_msg)
92 
93  self.assertEqual(in_msg.joint_state.position[0], 1000)
94  self.assertLess(out_msg.joint_state.position[0], 1000)
95 
97  expected_state = RobotState()
98  expected_state.joint_state.header.frame_id = "base_link"
99  expected_state.multi_dof_joint_state.header.frame_id = "base_link"
100  expected_state.joint_state.name = self.JOINT_NAMES
101  expected_state.joint_state.position = [0] * 6
102  self.assertEqual(self.group.get_current_state(), expected_state)
103 
104  def check_target_setting(self, expect, *args):
105  if len(args) == 0:
106  args = [expect]
107  self.group.set_joint_value_target(*args)
108  res = self.group.get_joint_value_target()
109  self.assertTrue(
110  np.all(np.asarray(res) == np.asarray(expect)),
111  "Setting failed for %s, values: %s" % (type(args[0]), res),
112  )
113 
115  n = self.group.get_variable_count()
116  self.check_target_setting([0.1] * n)
117  self.check_target_setting((0.2,) * n)
118  self.check_target_setting(np.zeros(n))
120  [0.3] * n, {name: 0.3 for name in self.group.get_active_joints()}
121  )
122  self.check_target_setting([0.5] + [0.3] * (n - 1), "joint_1", 0.5)
123 
124  js_target = JointState(name=self.JOINT_NAMES, position=[0.1] * n)
125  self.check_target_setting([0.1] * n, js_target)
126  # name and position should have the same size, or raise exception
127  with self.assertRaises(MoveItCommanderException):
128  js_target.position = []
129  self.check_target_setting(None, js_target)
130 
131  def plan(self, target):
132  self.group.set_joint_value_target(target)
133  return self.group.plan()
134 
135  def test_plan(self):
136  state = JointState(name=self.JOINT_NAMES, position=[0, 0, 0, 0, 0, 0])
137  self.assertTrue(self.group.plan(state.position)[0])
138  self.assertTrue(self.group.plan("current")[0])
139  self.assertTrue(state, self.group.plan()[0])
140 
141  def test_validation(self):
142  current = np.asarray(self.group.get_current_joint_values())
143 
144  success1, plan1, time1, err1 = self.plan(current + 0.2)
145  success2, plan2, time2, err2 = self.plan(current + 0.2)
146  self.assertTrue(success1)
147  self.assertTrue(success2)
148 
149  # first plan should execute
150  self.assertTrue(self.group.execute(plan1))
151 
152  # second plan should be invalid now (due to modified start point) and rejected
153  self.assertFalse(self.group.execute(plan2))
154 
155  # newly planned trajectory should execute again
156  success3, plan3, time3, err3 = self.plan(current)
157  self.assertTrue(success3)
158  self.assertTrue(self.group.execute(plan3))
159 
160  def test_gogogo(self):
161  current_joints = np.asarray(self.group.get_current_joint_values())
162 
163  self.group.set_joint_value_target(current_joints)
164  self.assertTrue(self.group.go(True))
165 
166  self.assertTrue(self.group.go(current_joints))
167  self.assertTrue(self.group.go(list(current_joints)))
168  self.assertTrue(self.group.go(tuple(current_joints)))
169  self.assertTrue(
170  self.group.go(JointState(name=self.JOINT_NAMES, position=current_joints))
171  )
172 
173  self.group.remember_joint_values("current")
174  self.assertTrue(self.group.go("current"))
175 
176  current_pose = self.group.get_current_pose()
177  self.assertTrue(self.group.go(current_pose))
178 
179 
180 class PythonPSITest(unittest.TestCase):
181  @classmethod
182  def setUpClass(self):
184 
185  def get_acm(self):
186  return self.psi.get_planning_scene(
187  PlanningSceneComponents.ALLOWED_COLLISION_MATRIX
188  ).allowed_collision_matrix
189 
190  def apply_acm(self, acm):
191  scene = PlanningScene()
192  scene.allowed_collision_matrix = acm
193  scene.is_diff = True
194  scene.robot_state.is_diff = True
195  self.psi.apply_planning_scene(scene)
196 
198  self.assertEqual(len(self.psi.get_known_object_names()), 0)
199 
200  self.psi.add_box("obj", [0.5, 0.5, 0.5], [0.5, 0.5, 0.5])
201  self.assertEqual(self.psi.get_known_object_names(), ["obj"])
202 
203  self.psi.remove_world_object("obj")
204  self.assertEqual(len(self.psi.get_known_object_names()), 0)
205 
206  def test_acm(self):
207  acm = self.get_acm()
208  self.assertFalse("obj" in acm.entry_names)
209  self.assertFalse("obj" in acm.default_entry_names)
210 
211  acm.set_allowed("obj")
212  self.assertTrue("obj" in acm.default_entry_names)
213  self.apply_acm(acm)
214 
215  acm = self.get_acm()
216  self.assertTrue("obj" in acm.default_entry_names)
217 
218 
219 if __name__ == "__main__":
220  PKGNAME = "moveit_ros_planning_interface"
221  NODENAME = "moveit_test_python_moveit_commander"
222  rospy.init_node(NODENAME)
223  rostest.rosrun(PKGNAME, NODENAME, PythonMoveitCommanderTest)
224 
225  # suppress cleanup segfault
226  os._exit(0)
python_moveit_commander.PythonPSITest.test_acm
def test_acm(self)
Definition: python_moveit_commander.py:206
python_moveit_commander.PythonMoveitCommanderTest.PLANNING_GROUP
string PLANNING_GROUP
Definition: python_moveit_commander.py:60
python_moveit_commander.PythonMoveitCommanderTest.test_enforce_bounds_empty_state
def test_enforce_bounds_empty_state(self)
Definition: python_moveit_commander.py:79
python_moveit_commander.PythonMoveitCommanderTest.test_enforce_bounds
def test_enforce_bounds(self)
Definition: python_moveit_commander.py:84
python_moveit_commander.PythonMoveitCommanderTest.test_validation
def test_validation(self)
Definition: python_moveit_commander.py:141
python_moveit_commander.PythonMoveitCommanderTest.test_target_setting
def test_target_setting(self)
Definition: python_moveit_commander.py:114
python_moveit_commander.PythonMoveitCommanderTest.test_plan
def test_plan(self)
Definition: python_moveit_commander.py:135
python_moveit_commander.PythonMoveitCommanderTest.setUpClass
def setUpClass(self)
Definition: python_moveit_commander.py:71
python_moveit_commander.PythonMoveitCommanderTest.test_gogogo
def test_gogogo(self)
Definition: python_moveit_commander.py:160
python_moveit_commander.PythonMoveitCommanderTest.group
group
Definition: python_moveit_commander.py:73
python_moveit_commander.PythonMoveitCommanderTest.plan
def plan(self, target)
Definition: python_moveit_commander.py:131
moveit_commander_cmdline.type
type
Definition: moveit_commander_cmdline.py:202
python_moveit_commander.PythonMoveitCommanderTest.JOINT_NAMES
list JOINT_NAMES
Definition: python_moveit_commander.py:61
python_moveit_commander.PythonPSITest
Definition: python_moveit_commander.py:180
python_moveit_commander.PythonMoveitCommanderTest.test_get_current_state
def test_get_current_state(self)
Definition: python_moveit_commander.py:96
plan
Definition: plan.py:1
python_moveit_commander.PythonMoveitCommanderTest
Definition: python_moveit_commander.py:59
python_moveit_commander.PythonPSITest.get_acm
def get_acm(self)
Definition: python_moveit_commander.py:185
python_moveit_commander.PythonPSITest.test_add_remove_object
def test_add_remove_object(self)
Definition: python_moveit_commander.py:197
python_moveit_commander.PythonPSITest.psi
psi
Definition: python_moveit_commander.py:183
python_moveit_commander.PythonMoveitCommanderTest.commander
commander
Definition: python_moveit_commander.py:72
python_moveit_commander.PythonPSITest.setUpClass
def setUpClass(self)
Definition: python_moveit_commander.py:182
python_moveit_commander.PythonMoveitCommanderTest.tearDown
def tearDown(self)
Definition: python_moveit_commander.py:76
python_moveit_commander.PythonPSITest.apply_acm
def apply_acm(self, acm)
Definition: python_moveit_commander.py:190
moveit_commander.robot.RobotCommander
Definition: robot.py:43
python_moveit_commander.PythonMoveitCommanderTest.check_target_setting
def check_target_setting(self, expect, *args)
Definition: python_moveit_commander.py:104
moveit_commander.planning_scene_interface.PlanningSceneInterface
Definition: planning_scene_interface.py:60


moveit_commander
Author(s): Ioan Sucan
autogenerated on Sat Mar 15 2025 02:27:15