moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 RobotState
46 from sensor_msgs.msg import JointState
47 
48 from moveit_commander import RobotCommander, PlanningSceneInterface
49 
50 
51 class PythonMoveitCommanderTest(unittest.TestCase):
52  PLANNING_GROUP = "manipulator"
53  JOINT_NAMES = [
54  "joint_1",
55  "joint_2",
56  "joint_3",
57  "joint_4",
58  "joint_5",
59  "joint_6",
60  ]
61 
62  @classmethod
63  def setUpClass(self):
64  self.commandercommander = RobotCommander("robot_description")
65  self.groupgroup = self.commandercommander.get_group(self.PLANNING_GROUPPLANNING_GROUP)
66 
67  @classmethod
68  def tearDown(self):
69  pass
70 
72  in_msg = RobotState()
73  with self.assertRaises(genpy.DeserializationError):
74  self.group.enforce_bounds(in_msg)
75 
77  in_msg = RobotState()
78  in_msg.joint_state.header.frame_id = "base_link"
79  in_msg.joint_state.name = self.JOINT_NAMESJOINT_NAMES
80  in_msg.joint_state.position = [0] * 6
81  in_msg.joint_state.position[0] = 1000
82 
83  out_msg = self.groupgroup.enforce_bounds(in_msg)
84 
85  self.assertEqual(in_msg.joint_state.position[0], 1000)
86  self.assertLess(out_msg.joint_state.position[0], 1000)
87 
89  expected_state = RobotState()
90  expected_state.joint_state.header.frame_id = "base_link"
91  expected_state.multi_dof_joint_state.header.frame_id = "base_link"
92  expected_state.joint_state.name = self.JOINT_NAMESJOINT_NAMES
93  expected_state.joint_state.position = [0] * 6
94  self.assertEqual(self.groupgroup.get_current_state(), expected_state)
95 
96  def check_target_setting(self, expect, *args):
97  if len(args) == 0:
98  args = [expect]
99  self.groupgroup.set_joint_value_target(*args)
100  res = self.groupgroup.get_joint_value_target()
101  self.assertTrue(
102  np.all(np.asarray(res) == np.asarray(expect)),
103  "Setting failed for %s, values: %s" % (type(args[0]), res),
104  )
105 
107  n = self.groupgroup.get_variable_count()
108  self.check_target_settingcheck_target_setting([0.1] * n)
109  self.check_target_settingcheck_target_setting((0.2,) * n)
110  self.check_target_settingcheck_target_setting(np.zeros(n))
111  self.check_target_settingcheck_target_setting(
112  [0.3] * n, {name: 0.3 for name in self.groupgroup.get_active_joints()}
113  )
114  self.check_target_settingcheck_target_setting([0.5] + [0.3] * (n - 1), "joint_1", 0.5)
115 
116  def plan(self, target):
117  self.groupgroup.set_joint_value_target(target)
118  return self.groupgroup.plan()
119 
120  def test_validation(self):
121  current = np.asarray(self.groupgroup.get_current_joint_values())
122 
123  success1, plan1, time1, err1 = self.planplan(current + 0.2)
124  success2, plan2, time2, err2 = self.planplan(current + 0.2)
125  self.assertTrue(success1)
126  self.assertTrue(success2)
127 
128  # first plan should execute
129  self.assertTrue(self.groupgroup.execute(plan1))
130 
131  # second plan should be invalid now (due to modified start point) and rejected
132  self.assertFalse(self.groupgroup.execute(plan2))
133 
134  # newly planned trajectory should execute again
135  success3, plan3, time3, err3 = self.planplan(current)
136  self.assertTrue(success3)
137  self.assertTrue(self.groupgroup.execute(plan3))
138 
139  def test_gogogo(self):
140  current_joints = np.asarray(self.groupgroup.get_current_joint_values())
141 
142  self.groupgroup.set_joint_value_target(current_joints)
143  self.assertTrue(self.groupgroup.go(True))
144 
145  self.assertTrue(self.groupgroup.go(current_joints))
146  self.assertTrue(self.groupgroup.go(list(current_joints)))
147  self.assertTrue(self.groupgroup.go(tuple(current_joints)))
148  self.assertTrue(
149  self.groupgroup.go(JointState(name=self.JOINT_NAMESJOINT_NAMES, position=current_joints))
150  )
151 
152  self.groupgroup.remember_joint_values("current")
153  self.assertTrue(self.groupgroup.go("current"))
154 
155  current_pose = self.groupgroup.get_current_pose()
156  self.assertTrue(self.groupgroup.go(current_pose))
157 
159  planning_scene = PlanningSceneInterface()
160 
161 
162 if __name__ == "__main__":
163  PKGNAME = "moveit_ros_planning_interface"
164  NODENAME = "moveit_test_python_moveit_commander"
165  rospy.init_node(NODENAME)
166  rostest.rosrun(PKGNAME, NODENAME, PythonMoveitCommanderTest)
167 
168  # suppress cleanup segfault
169  os._exit(0)
Definition: plan.py:1