45 from moveit_msgs.msg
import (
47 PlanningSceneComponents,
50 from sensor_msgs.msg
import JointState
52 from moveit_commander
import (
54 PlanningSceneInterface,
55 MoveItCommanderException,
60 PLANNING_GROUP =
"manipulator"
81 with self.assertRaises(genpy.DeserializationError):
82 self.group.enforce_bounds(in_msg)
86 in_msg.joint_state.header.frame_id =
"base_link"
88 in_msg.joint_state.position = [0] * 6
89 in_msg.joint_state.position[0] = 1000
91 out_msg = self.
group.enforce_bounds(in_msg)
93 self.assertEqual(in_msg.joint_state.position[0], 1000)
94 self.assertLess(out_msg.joint_state.position[0], 1000)
97 expected_state = RobotState()
98 expected_state.joint_state.header.frame_id =
"base_link"
99 expected_state.multi_dof_joint_state.header.frame_id =
"base_link"
101 expected_state.joint_state.position = [0] * 6
102 self.assertEqual(self.
group.get_current_state(), expected_state)
107 self.
group.set_joint_value_target(*args)
108 res = self.
group.get_joint_value_target()
110 np.all(np.asarray(res) == np.asarray(expect)),
111 "Setting failed for %s, values: %s" % (
type(args[0]), res),
115 n = self.
group.get_variable_count()
120 [0.3] * n, {name: 0.3
for name
in self.
group.get_active_joints()}
124 js_target = JointState(name=self.
JOINT_NAMES, position=[0.1] * n)
127 with self.assertRaises(MoveItCommanderException):
128 js_target.position = []
132 self.
group.set_joint_value_target(target)
136 state = JointState(name=self.
JOINT_NAMES, position=[0, 0, 0, 0, 0, 0])
137 self.assertTrue(self.
group.
plan(state.position)[0])
138 self.assertTrue(self.
group.
plan(
"current")[0])
139 self.assertTrue(state, self.
group.
plan()[0])
142 current = np.asarray(self.
group.get_current_joint_values())
144 success1, plan1, time1, err1 = self.
plan(current + 0.2)
145 success2, plan2, time2, err2 = self.
plan(current + 0.2)
146 self.assertTrue(success1)
147 self.assertTrue(success2)
150 self.assertTrue(self.
group.execute(plan1))
153 self.assertFalse(self.
group.execute(plan2))
156 success3, plan3, time3, err3 = self.
plan(current)
157 self.assertTrue(success3)
158 self.assertTrue(self.
group.execute(plan3))
161 current_joints = np.asarray(self.
group.get_current_joint_values())
163 self.
group.set_joint_value_target(current_joints)
164 self.assertTrue(self.
group.go(
True))
166 self.assertTrue(self.
group.go(current_joints))
167 self.assertTrue(self.
group.go(list(current_joints)))
168 self.assertTrue(self.
group.go(tuple(current_joints)))
173 self.
group.remember_joint_values(
"current")
174 self.assertTrue(self.
group.go(
"current"))
176 current_pose = self.
group.get_current_pose()
177 self.assertTrue(self.
group.go(current_pose))
186 return self.
psi.get_planning_scene(
187 PlanningSceneComponents.ALLOWED_COLLISION_MATRIX
188 ).allowed_collision_matrix
191 scene = PlanningScene()
192 scene.allowed_collision_matrix = acm
194 scene.robot_state.is_diff =
True
195 self.
psi.apply_planning_scene(scene)
198 self.assertEqual(len(self.
psi.get_known_object_names()), 0)
200 self.
psi.add_box(
"obj", [0.5, 0.5, 0.5], [0.5, 0.5, 0.5])
201 self.assertEqual(self.
psi.get_known_object_names(), [
"obj"])
203 self.
psi.remove_world_object(
"obj")
204 self.assertEqual(len(self.
psi.get_known_object_names()), 0)
208 self.assertFalse(
"obj" in acm.entry_names)
209 self.assertFalse(
"obj" in acm.default_entry_names)
211 acm.set_allowed(
"obj")
212 self.assertTrue(
"obj" in acm.default_entry_names)
216 self.assertTrue(
"obj" in acm.default_entry_names)
219 if __name__ ==
"__main__":
220 PKGNAME =
"moveit_ros_planning_interface"
221 NODENAME =
"moveit_test_python_moveit_commander"
222 rospy.init_node(NODENAME)
223 rostest.rosrun(PKGNAME, NODENAME, PythonMoveitCommanderTest)