@@ -295,128 +295,3 @@ def js_cb(msg):
295295 # result = self.get_result("/scaled_joint_trajectory_controller/follow_joint_trajectory", goal_response, TIMEOUT_EXECUTE_TRAJECTORY)
296296 # self.assertEqual(result.error_code, FollowJointTrajectory.Result.GOAL_TOLERANCE_VIOLATED)
297297 # self.node.get_logger().info("Received result GOAL_TOLERANCE_VIOLATED")
298-
299- def test_passthrough_trajectory (self , tf_prefix ):
300- if self .mock_hardware :
301- return True
302- self .assertTrue (
303- self ._controller_manager_interface .switch_controller (
304- strictness = SwitchController .Request .BEST_EFFORT ,
305- activate_controllers = ["passthrough_trajectory_controller" ],
306- deactivate_controllers = ["scaled_joint_trajectory_controller" ],
307- ).ok
308- )
309- waypts = [
310- [- 1.58 , - 1.692 , - 1.4311 , - 0.0174 , 1.5882 , 0.0349 ],
311- [- 2.5 , - 1.692 , - 1.4311 , - 0.0174 , 1.5882 , 0.0349 ],
312- [- 1.58 , - 1.692 , - 1.4311 , - 0.0174 , 1.5882 , 0.0349 ],
313- ]
314- time_vec = [
315- Duration (sec = 4 , nanosec = 0 ),
316- Duration (sec = 8 , nanosec = 0 ),
317- Duration (sec = 12 , nanosec = 0 ),
318- ]
319- goal_tolerance = [
320- JointTolerance (position = 0.01 , velocity = 5e-5 , name = tf_prefix + ROBOT_JOINTS [i ])
321- for i in range (len (ROBOT_JOINTS ))
322- ]
323- goal_time_tolerance = Duration (sec = 1 , nanosec = 0 )
324- test_trajectory = zip (time_vec , waypts )
325- trajectory = JointTrajectory (
326- points = [
327- JointTrajectoryPoint (positions = pos , time_from_start = times )
328- for (times , pos ) in test_trajectory
329- ],
330- joint_names = [tf_prefix + ROBOT_JOINTS [i ] for i in range (len (ROBOT_JOINTS ))],
331- )
332- goal_handle = self ._passthrough_forward_joint_trajectory .send_goal (
333- trajectory = trajectory ,
334- goal_time_tolerance = goal_time_tolerance ,
335- goal_tolerance = goal_tolerance ,
336- )
337- self .assertTrue (goal_handle .accepted )
338- if goal_handle .accepted :
339- result = self ._passthrough_forward_joint_trajectory .get_result (
340- goal_handle , TIMEOUT_EXECUTE_TRAJECTORY
341- )
342- self .assertEqual (result .error_code , FollowJointTrajectory .Result .SUCCESSFUL )
343-
344- # Full quintic trajectory
345- test_trajectory = zip (time_vec , waypts )
346- trajectory = JointTrajectory (
347- points = [
348- JointTrajectoryPoint (
349- positions = pos ,
350- time_from_start = times ,
351- velocities = [0.0 , 0.0 , 0.0 , 0.0 , 0.0 , 0.0 ],
352- accelerations = [0.0 , 0.0 , 0.0 , 0.0 , 0.0 , 0.0 ],
353- )
354- for (times , pos ) in test_trajectory
355- ],
356- joint_names = [tf_prefix + ROBOT_JOINTS [i ] for i in range (len (ROBOT_JOINTS ))],
357- )
358- goal_handle = self ._passthrough_forward_joint_trajectory .send_goal (
359- trajectory = trajectory ,
360- goal_time_tolerance = goal_time_tolerance ,
361- goal_tolerance = goal_tolerance ,
362- )
363- self .assertTrue (goal_handle .accepted )
364- if goal_handle .accepted :
365- result = self ._passthrough_forward_joint_trajectory .get_result (
366- goal_handle , TIMEOUT_EXECUTE_TRAJECTORY
367- )
368- self .assertEqual (result .error_code , FollowJointTrajectory .Result .SUCCESSFUL )
369-
370- # Test impossible goal tolerance, should fail.
371- test_trajectory = zip (time_vec , waypts )
372- trajectory = JointTrajectory (
373- points = [
374- JointTrajectoryPoint (positions = pos , time_from_start = times )
375- for (times , pos ) in test_trajectory
376- ],
377- joint_names = [tf_prefix + ROBOT_JOINTS [i ] for i in range (len (ROBOT_JOINTS ))],
378- )
379- goal_tolerance = [
380- JointTolerance (position = 0.000000001 , name = tf_prefix + ROBOT_JOINTS [i ])
381- for i in range (len (ROBOT_JOINTS ))
382- ]
383- goal_handle = self ._passthrough_forward_joint_trajectory .send_goal (
384- trajectory = trajectory ,
385- goal_time_tolerance = goal_time_tolerance ,
386- goal_tolerance = goal_tolerance ,
387- )
388- self .assertTrue (goal_handle .accepted )
389- if goal_handle .accepted :
390- result = self ._passthrough_forward_joint_trajectory .get_result (
391- goal_handle , TIMEOUT_EXECUTE_TRAJECTORY
392- )
393- self .assertEqual (
394- result .error_code , FollowJointTrajectory .Result .GOAL_TOLERANCE_VIOLATED
395- )
396-
397- # Test impossible goal time
398- goal_tolerance = [
399- JointTolerance (position = 0.01 , name = tf_prefix + ROBOT_JOINTS [i ]) for i in range (6 )
400- ]
401- goal_time_tolerance .sec = 0
402- goal_time_tolerance .nanosec = 10
403- goal_handle = self ._passthrough_forward_joint_trajectory .send_goal (
404- trajectory = trajectory ,
405- goal_time_tolerance = goal_time_tolerance ,
406- goal_tolerance = goal_tolerance ,
407- )
408- self .assertTrue (goal_handle .accepted )
409- if goal_handle .accepted :
410- result = self ._passthrough_forward_joint_trajectory .get_result (
411- goal_handle , TIMEOUT_EXECUTE_TRAJECTORY
412- )
413- self .assertEqual (
414- result .error_code , FollowJointTrajectory .Result .GOAL_TOLERANCE_VIOLATED
415- )
416- self .assertTrue (
417- self ._controller_manager_interface .switch_controller (
418- strictness = SwitchController .Request .BEST_EFFORT ,
419- deactivate_controllers = ["passthrough_trajectory_controller" ],
420- activate_controllers = ["scaled_joint_trajectory_controller" ],
421- ).ok
422- )
0 commit comments