moveit2
The MoveIt Motion Planning Framework for ROS 2.
python_moveit_commander_ns.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 # This test is used to ensure planning with a RobotCommander is
38 # possbile if the robot's move_group node is in a different namespace
39 
40 import unittest
41 import numpy as np
42 import rospy
43 import rostest
44 import os
45 
46 from moveit_commander import RobotCommander
47 
48 
49 class PythonMoveitCommanderNsTest(unittest.TestCase):
50  PLANNING_GROUP = "manipulator"
51  PLANNING_NS = "test_ns/"
52 
53  @classmethod
54  def setUpClass(self):
55  self.commandercommander = RobotCommander(
56  "%srobot_description" % self.PLANNING_NSPLANNING_NS, self.PLANNING_NSPLANNING_NS
57  )
58  self.groupgroup = self.commandercommander.get_group(self.PLANNING_GROUPPLANNING_GROUP)
59 
60  @classmethod
61  def tearDown(self):
62  pass
63 
64  def check_target_setting(self, expect, *args):
65  if len(args) == 0:
66  args = [expect]
67  self.group.set_joint_value_target(*args)
68  res = self.group.get_joint_value_target()
69  self.assertTrue(
70  np.all(np.asarray(res) == np.asarray(expect)),
71  "Setting failed for %s, values: %s" % (type(args[0]), res),
72  )
73 
75  n = self.groupgroup.get_variable_count()
76  self.check_target_settingcheck_target_setting([0.1] * n)
77  self.check_target_settingcheck_target_setting((0.2,) * n)
78  self.check_target_settingcheck_target_setting(np.zeros(n))
79  self.check_target_settingcheck_target_setting(
80  [0.3] * n, {name: 0.3 for name in self.groupgroup.get_active_joints()}
81  )
82  self.check_target_settingcheck_target_setting([0.5] + [0.3] * (n - 1), "joint_1", 0.5)
83 
84  def plan(self, target):
85  self.groupgroup.set_joint_value_target(target)
86  return self.groupgroup.plan()
87 
88  def test_validation(self):
89  current = np.asarray(self.groupgroup.get_current_joint_values())
90 
91  success1, plan1, time1, err1 = self.planplan(current + 0.2)
92  success2, plan2, time2, err2 = self.planplan(current + 0.2)
93  self.assertTrue(success1)
94  self.assertTrue(success2)
95 
96  # first plan should execute
97  self.assertTrue(self.groupgroup.execute(plan1))
98 
99  # second plan should be invalid now (due to modified start point) and rejected
100  self.assertFalse(self.groupgroup.execute(plan2))
101 
102  # newly planned trajectory should execute again
103  success3, plan3, time3, err3 = self.planplan(current)
104  self.assertTrue(success3)
105  self.assertTrue(self.groupgroup.execute(plan3))
106 
107 
108 if __name__ == "__main__":
109  PKGNAME = "moveit_ros_planning_interface"
110  NODENAME = "moveit_test_python_moveit_commander_ns"
111  rospy.init_node(NODENAME)
112  rostest.rosrun(PKGNAME, NODENAME, PythonMoveitCommanderNsTest)
113 
114  # suppress cleanup segfault
115  os._exit(0)
Definition: plan.py:1