46 from moveit_ros_planning_interface._moveit_move_group_interface 
import (
 
   49 from moveit_msgs.msg 
import MoveItErrorCodes
 
   53     PLANNING_GROUP = 
"manipulator" 
   54     PLANNING_NS = 
"test_ns/" 
   58         self.
group = MoveGroupInterface(
 
   71         self.group.set_joint_value_target(*args)
 
   72         res = self.group.get_joint_value_target()
 
   74             np.all(np.asarray(res) == np.asarray(expect)),
 
   75             "Setting failed for %s, values: %s" % (type(args[0]), res),
 
   79         n = self.
group.get_variable_count()
 
   84             [0.3] * n, {name: 0.3 
for name 
in self.
group.get_active_joints()}
 
   89         self.
group.set_joint_value_target(target)
 
   93         current = np.asarray(self.
group.get_current_joint_values())
 
   95         error_code1, plan1, time = self.
plan(current + 0.2)
 
   96         error_code2, plan2, time = self.
plan(current + 0.2)
 
   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)
 
  107         self.assertTrue(self.
group.execute(plan1))
 
  110         self.assertFalse(self.
group.execute(plan2))
 
  113         error_code3, plan3, time = self.
plan(current)
 
  114         self.assertTrue(self.
group.execute(plan3))
 
  115         error_code = MoveItErrorCodes()
 
  116         error_code.deserialize(error_code3)
 
  117         self.assertEqual(error_code.val, MoveItErrorCodes.SUCCESS)
 
  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)