moveit2
The MoveIt Motion Planning Framework for ROS 2.
python_move_group_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 MoveGroupInterface 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_ros_planning_interface._moveit_move_group_interface import (
47  MoveGroupInterface,
48 )
49 from moveit_msgs.msg import MoveItErrorCodes
50 
51 
52 class PythonMoveGroupNsTest(unittest.TestCase):
53  PLANNING_GROUP = "manipulator"
54  PLANNING_NS = "test_ns/"
55 
56  @classmethod
57  def setUpClass(self):
58  self.groupgroup = MoveGroupInterface(
59  self.PLANNING_GROUPPLANNING_GROUP,
60  "%srobot_description" % self.PLANNING_NSPLANNING_NS,
61  self.PLANNING_NSPLANNING_NS,
62  )
63 
64  @classmethod
65  def tearDown(self):
66  pass
67 
68  def check_target_setting(self, expect, *args):
69  if len(args) == 0:
70  args = [expect]
71  self.group.set_joint_value_target(*args)
72  res = self.group.get_joint_value_target()
73  self.assertTrue(
74  np.all(np.asarray(res) == np.asarray(expect)),
75  "Setting failed for %s, values: %s" % (type(args[0]), res),
76  )
77 
79  n = self.groupgroup.get_variable_count()
80  self.check_target_settingcheck_target_setting([0.1] * n)
81  self.check_target_settingcheck_target_setting((0.2,) * n)
82  self.check_target_settingcheck_target_setting(np.zeros(n))
83  self.check_target_settingcheck_target_setting(
84  [0.3] * n, {name: 0.3 for name in self.groupgroup.get_active_joints()}
85  )
86  self.check_target_settingcheck_target_setting([0.5] + [0.3] * (n - 1), "joint_1", 0.5)
87 
88  def plan(self, target):
89  self.groupgroup.set_joint_value_target(target)
90  return self.groupgroup.plan()
91 
92  def test_validation(self):
93  current = np.asarray(self.groupgroup.get_current_joint_values())
94 
95  error_code1, plan1, time = self.planplan(current + 0.2)
96  error_code2, plan2, time = self.planplan(current + 0.2)
97 
98  # both plans should have succeeded:
99  error_code = MoveItErrorCodes()
100  error_code.deserialize(error_code1)
101  self.assertEqual(error_code.val, MoveItErrorCodes.SUCCESS)
102  error_code = MoveItErrorCodes()
103  error_code.deserialize(error_code2)
104  self.assertEqual(error_code.val, MoveItErrorCodes.SUCCESS)
105 
106  # first plan should execute
107  self.assertTrue(self.groupgroup.execute(plan1))
108 
109  # second plan should be invalid now (due to modified start point) and rejected
110  self.assertFalse(self.groupgroup.execute(plan2))
111 
112  # newly planned trajectory should execute again
113  error_code3, plan3, time = self.planplan(current)
114  self.assertTrue(self.groupgroup.execute(plan3))
115  error_code = MoveItErrorCodes()
116  error_code.deserialize(error_code3)
117  self.assertEqual(error_code.val, MoveItErrorCodes.SUCCESS)
118 
119 
120 if __name__ == "__main__":
121  PKGNAME = "moveit_ros_planning_interface"
122  NODENAME = "moveit_test_python_move_group"
123  rospy.init_node(NODENAME)
124  rostest.rosrun(PKGNAME, NODENAME, PythonMoveGroupNsTest)
Definition: plan.py:1