43 from moveit_commander
import RobotCommander, PlanningSceneInterface
47 PLANNING_GROUP =
"manipulator" 51 self.
commander = RobotCommander(
"robot_description")
61 self.group.set_joint_value_target(*args)
62 res = self.group.get_joint_value_target()
63 self.assertTrue(np.all(np.asarray(res) == np.asarray(expect)),
64 "Setting failed for %s, values: %s" % (
type(args[0]), res))
67 n = self.group.get_variable_count()
75 self.group.set_joint_value_target(target)
76 return self.group.plan()
79 current = np.asarray(self.group.get_current_joint_values())
81 plan1 = self.
plan(current + 0.2)
82 plan2 = self.
plan(current + 0.2)
85 self.assertTrue(self.group.execute(plan1))
88 self.assertFalse(self.group.execute(plan2))
91 plan3 = self.
plan(current)
92 self.assertTrue(self.group.execute(plan3))
95 planning_scene = PlanningSceneInterface()
98 if __name__ ==
'__main__':
99 PKGNAME =
'moveit_ros_planning_interface' 100 NODENAME =
'moveit_test_python_moveit_commander' 101 rospy.init_node(NODENAME)
102 rostest.rosrun(PKGNAME, NODENAME, PythonMoveitCommanderTest)
def test_planning_scene_interface(self)
def test_validation(self)
def test_target_setting(self)
def check_target_setting(self, expect, args)