9 from moveit_ros_planning_interface._moveit_move_group_interface 
import (
 
   12 from moveit_msgs.msg 
import MoveItErrorCodes
 
   16     PLANNING_GROUP = 
"manipulator" 
   20         self.
group = MoveGroupInterface(
 
   31         self.group.set_joint_value_target(*args)
 
   32         res = self.group.get_joint_value_target()
 
   34             np.all(np.asarray(res) == np.asarray(expect)),
 
   35             "Setting failed for %s, values: %s" % (type(args[0]), res),
 
   39         n = self.
group.get_variable_count()
 
   44             [0.3] * n, {name: 0.3 
for name 
in self.
group.get_active_joints()}
 
   49         self.
group.set_joint_value_target(target)
 
   53         current = np.asarray(self.
group.get_current_joint_values())
 
   55         error_code1, plan1, time = self.
plan(current + 0.2)
 
   56         error_code2, plan2, time = self.
plan(current + 0.2)
 
   59         error_code = MoveItErrorCodes()
 
   60         error_code.deserialize(error_code1)
 
   61         self.assertEqual(error_code.val, MoveItErrorCodes.SUCCESS)
 
   62         error_code = MoveItErrorCodes()
 
   63         error_code.deserialize(error_code2)
 
   64         self.assertEqual(error_code.val, MoveItErrorCodes.SUCCESS)
 
   67         self.assertTrue(self.
group.execute(plan1))
 
   70         self.assertFalse(self.
group.execute(plan2))
 
   73         error_code3, plan3, time = self.
plan(current)
 
   74         error_code = MoveItErrorCodes()
 
   75         error_code.deserialize(error_code3)
 
   76         self.assertEqual(error_code.val, MoveItErrorCodes.SUCCESS)
 
   77         self.assertTrue(self.
group.execute(plan3))
 
   80         current = self.
group.get_current_joint_values()
 
   81         result = self.
group.get_jacobian_matrix(current)
 
   85                 [0.0, 0.8, -0.2, 0.0, 0.0, 0.0],
 
   86                 [0.89, 0.0, 0.0, 0.0, 0.0, 0.0],
 
   87                 [0.0, -0.74, 0.74, 0.0, 0.1, 0.0],
 
   88                 [0.0, 0.0, 0.0, -1.0, 0.0, -1.0],
 
   89                 [0.0, 1.0, -1.0, 0.0, -1.0, 0.0],
 
   90                 [1.0, 0.0, 0.0, 0.0, 0.0, 0.0],
 
   93         self.assertTrue(np.allclose(result, expected))
 
   95         result = self.
group.get_jacobian_matrix(current, [1.0, 1.0, 1.0])
 
   98                 [1.0, 1.8, -1.2, 0.0, -1.0, 0.0],
 
   99                 [1.89, 0.0, 0.0, 1.0, 0.0, 1.0],
 
  100                 [0.0, -1.74, 1.74, 1.0, 1.1, 1.0],
 
  101                 [0.0, 0.0, 0.0, -1.0, 0.0, -1.0],
 
  102                 [0.0, 1.0, -1.0, 0.0, -1.0, 0.0],
 
  103                 [1.0, 0.0, 0.0, 0.0, 0.0, 0.0],
 
  108 if __name__ == 
"__main__":
 
  109     PKGNAME = 
"moveit_ros_planning_interface" 
  110     NODENAME = 
"moveit_test_python_move_group" 
  111     rospy.init_node(NODENAME)
 
  112     rostest.rosrun(PKGNAME, NODENAME, PythonMoveGroupTest)