46 from sensor_msgs.msg
import JointState
48 from moveit_commander
import RobotCommander, PlanningSceneInterface
52 PLANNING_GROUP =
"manipulator"
73 with self.assertRaises(genpy.DeserializationError):
74 self.group.enforce_bounds(in_msg)
78 in_msg.joint_state.header.frame_id =
"base_link"
79 in_msg.joint_state.name = self.
JOINT_NAMESJOINT_NAMES
80 in_msg.joint_state.position = [0] * 6
81 in_msg.joint_state.position[0] = 1000
83 out_msg = self.
groupgroup.enforce_bounds(in_msg)
85 self.assertEqual(in_msg.joint_state.position[0], 1000)
86 self.assertLess(out_msg.joint_state.position[0], 1000)
89 expected_state = RobotState()
90 expected_state.joint_state.header.frame_id =
"base_link"
91 expected_state.multi_dof_joint_state.header.frame_id =
"base_link"
92 expected_state.joint_state.name = self.
JOINT_NAMESJOINT_NAMES
93 expected_state.joint_state.position = [0] * 6
94 self.assertEqual(self.
groupgroup.get_current_state(), expected_state)
99 self.
groupgroup.set_joint_value_target(*args)
100 res = self.
groupgroup.get_joint_value_target()
102 np.all(np.asarray(res) == np.asarray(expect)),
103 "Setting failed for %s, values: %s" % (
type(args[0]), res),
107 n = self.
groupgroup.get_variable_count()
112 [0.3] * n, {name: 0.3
for name
in self.
groupgroup.get_active_joints()}
117 self.
groupgroup.set_joint_value_target(target)
121 current = np.asarray(self.
groupgroup.get_current_joint_values())
123 success1, plan1, time1, err1 = self.
planplan(current + 0.2)
124 success2, plan2, time2, err2 = self.
planplan(current + 0.2)
125 self.assertTrue(success1)
126 self.assertTrue(success2)
129 self.assertTrue(self.
groupgroup.execute(plan1))
132 self.assertFalse(self.
groupgroup.execute(plan2))
135 success3, plan3, time3, err3 = self.
planplan(current)
136 self.assertTrue(success3)
137 self.assertTrue(self.
groupgroup.execute(plan3))
140 current_joints = np.asarray(self.
groupgroup.get_current_joint_values())
142 self.
groupgroup.set_joint_value_target(current_joints)
143 self.assertTrue(self.
groupgroup.go(
True))
145 self.assertTrue(self.
groupgroup.go(current_joints))
146 self.assertTrue(self.
groupgroup.go(list(current_joints)))
147 self.assertTrue(self.
groupgroup.go(tuple(current_joints)))
149 self.
groupgroup.go(JointState(name=self.
JOINT_NAMESJOINT_NAMES, position=current_joints))
152 self.
groupgroup.remember_joint_values(
"current")
153 self.assertTrue(self.
groupgroup.go(
"current"))
155 current_pose = self.
groupgroup.get_current_pose()
156 self.assertTrue(self.
groupgroup.go(current_pose))
162 if __name__ ==
"__main__":
163 PKGNAME =
"moveit_ros_planning_interface"
164 NODENAME =
"moveit_test_python_moveit_commander"
165 rospy.init_node(NODENAME)
166 rostest.rosrun(PKGNAME, NODENAME, PythonMoveitCommanderTest)
def test_planning_scene_interface(self)
def check_target_setting(self, expect, *args)
def test_validation(self)
def test_get_current_state(self)
def test_enforce_bounds(self)
def test_target_setting(self)
def test_enforce_bounds_empty_state(self)