46 from moveit_commander
import RobotCommander
50 PLANNING_GROUP =
"manipulator"
51 PLANNING_NS =
"test_ns/"
67 self.group.set_joint_value_target(*args)
68 res = self.group.get_joint_value_target()
70 np.all(np.asarray(res) == np.asarray(expect)),
71 "Setting failed for %s, values: %s" % (
type(args[0]), res),
75 n = self.
groupgroup.get_variable_count()
80 [0.3] * n, {name: 0.3
for name
in self.
groupgroup.get_active_joints()}
85 self.
groupgroup.set_joint_value_target(target)
89 current = np.asarray(self.
groupgroup.get_current_joint_values())
91 success1, plan1, time1, err1 = self.
planplan(current + 0.2)
92 success2, plan2, time2, err2 = self.
planplan(current + 0.2)
93 self.assertTrue(success1)
94 self.assertTrue(success2)
97 self.assertTrue(self.
groupgroup.execute(plan1))
100 self.assertFalse(self.
groupgroup.execute(plan2))
103 success3, plan3, time3, err3 = self.
planplan(current)
104 self.assertTrue(success3)
105 self.assertTrue(self.
groupgroup.execute(plan3))
108 if __name__ ==
"__main__":
109 PKGNAME =
"moveit_ros_planning_interface"
110 NODENAME =
"moveit_test_python_moveit_commander_ns"
111 rospy.init_node(NODENAME)
112 rostest.rosrun(PKGNAME, NODENAME, PythonMoveitCommanderNsTest)
def test_validation(self)
def check_target_setting(self, expect, *args)
def test_target_setting(self)