python_move_group.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import unittest
4 import numpy as np
5 import rospy
6 import rostest
7 import os
8 
9 from moveit_ros_planning_interface._moveit_move_group_interface import MoveGroupInterface
10 
11 
12 class PythonMoveGroupTest(unittest.TestCase):
13  PLANNING_GROUP = "manipulator"
14 
15  @classmethod
16  def setUpClass(self):
17  self.group = MoveGroupInterface(self.PLANNING_GROUP, "robot_description", rospy.get_namespace())
18 
19  @classmethod
20  def tearDown(self):
21  pass
22 
23  def check_target_setting(self, expect, *args):
24  if len(args) == 0:
25  args = [expect]
26  self.group.set_joint_value_target(*args)
27  res = self.group.get_joint_value_target()
28  self.assertTrue(np.all(np.asarray(res) == np.asarray(expect)),
29  "Setting failed for %s, values: %s" % (type(args[0]), res))
30 
32  n = self.group.get_variable_count()
33  self.check_target_setting([0.1] * n)
34  self.check_target_setting((0.2,) * n)
35  self.check_target_setting(np.zeros(n))
36  self.check_target_setting([0.3] * n, {name: 0.3 for name in self.group.get_active_joints()})
37  self.check_target_setting([0.5] + [0.3]*(n-1), "joint_1", 0.5)
38 
39  def plan(self, target):
40  self.group.set_joint_value_target(target)
41  return self.group.compute_plan()
42 
43  def test_validation(self):
44  current = np.asarray(self.group.get_current_joint_values())
45 
46  plan1 = self.plan(current + 0.2)
47  plan2 = self.plan(current + 0.2)
48 
49  # first plan should execute
50  self.assertTrue(self.group.execute(plan1))
51 
52  # second plan should be invalid now (due to modified start point) and rejected
53  self.assertFalse(self.group.execute(plan2))
54 
55  # newly planned trajectory should execute again
56  plan3 = self.plan(current)
57  self.assertTrue(self.group.execute(plan3))
58 
60  current = self.group.get_current_joint_values()
61  result = self.group.get_jacobian_matrix(current)
62  # Value check by known value at the initial pose
63  expected = np.array([[ 0. , 0.8 , -0.2 , 0. , 0. , 0. ],
64  [ 0.89, 0. , 0. , 0. , 0. , 0. ],
65  [ 0. , -0.74, 0.74, 0. , 0.1 , 0. ],
66  [ 0. , 0. , 0. , -1. , 0. , -1. ],
67  [ 0. , 1. , -1. , 0. , -1. , 0. ],
68  [ 1. , 0. , 0. , 0. , 0. , 0. ]])
69  self.assertTrue(np.allclose(result, expected))
70 
71 
72 if __name__ == '__main__':
73  PKGNAME = 'moveit_ros_planning_interface'
74  NODENAME = 'moveit_test_python_move_group'
75  rospy.init_node(NODENAME)
76  rostest.rosrun(PKGNAME, NODENAME, PythonMoveGroupTest)
77 
78  # suppress cleanup segfault
79  os._exit(0)
def check_target_setting(self, expect, args)


planning_interface
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:50