|
56 | 56 | "passthrough_trajectory_controller", |
57 | 57 | "force_mode_controller", |
58 | 58 | "freedrive_mode_controller", |
| 59 | + "motion_primitive_forward_controller", |
59 | 60 | ] |
60 | 61 |
|
61 | 62 |
|
@@ -483,3 +484,109 @@ def test_tool_contact_compatibility(self): |
483 | 484 | ], |
484 | 485 | ).ok |
485 | 486 | ) |
| 487 | + |
| 488 | + self.assertTrue( |
| 489 | + self._controller_manager_interface.switch_controller( |
| 490 | + strictness=SwitchController.Request.STRICT, |
| 491 | + activate_controllers=[ |
| 492 | + "motion_primitive_forward_controller", |
| 493 | + "tool_contact_controller", |
| 494 | + ], |
| 495 | + ).ok |
| 496 | + ) |
| 497 | + self.assertTrue( |
| 498 | + self._controller_manager_interface.switch_controller( |
| 499 | + strictness=SwitchController.Request.STRICT, |
| 500 | + deactivate_controllers=[ |
| 501 | + "motion_primitive_forward_controller", |
| 502 | + "tool_contact_controller", |
| 503 | + ], |
| 504 | + ).ok |
| 505 | + ) |
| 506 | + |
| 507 | + def test_moprim_compatibility(self): |
| 508 | + # Deactivate all writing controllers |
| 509 | + self.assertTrue( |
| 510 | + self._controller_manager_interface.switch_controller( |
| 511 | + strictness=SwitchController.Request.BEST_EFFORT, |
| 512 | + deactivate_controllers=ALL_CONTROLLERS, |
| 513 | + ).ok |
| 514 | + ) |
| 515 | + |
| 516 | + time.sleep(3) |
| 517 | + |
| 518 | + # moprim controller should not start with any other joint controller |
| 519 | + self.assertFalse( |
| 520 | + self._controller_manager_interface.switch_controller( |
| 521 | + strictness=SwitchController.Request.STRICT, |
| 522 | + activate_controllers=[ |
| 523 | + "motion_primitive_forward_controller", |
| 524 | + "joint_trajectory_controller", |
| 525 | + ], |
| 526 | + ).ok |
| 527 | + ) |
| 528 | + self.assertFalse( |
| 529 | + self._controller_manager_interface.switch_controller( |
| 530 | + strictness=SwitchController.Request.STRICT, |
| 531 | + activate_controllers=[ |
| 532 | + "motion_primitive_forward_controller", |
| 533 | + "forward_effort_controller", |
| 534 | + ], |
| 535 | + ).ok |
| 536 | + ) |
| 537 | + self.assertFalse( |
| 538 | + self._controller_manager_interface.switch_controller( |
| 539 | + strictness=SwitchController.Request.STRICT, |
| 540 | + activate_controllers=[ |
| 541 | + "motion_primitive_forward_controller", |
| 542 | + "forward_velocity_controller", |
| 543 | + ], |
| 544 | + ).ok |
| 545 | + ) |
| 546 | + self.assertFalse( |
| 547 | + self._controller_manager_interface.switch_controller( |
| 548 | + strictness=SwitchController.Request.STRICT, |
| 549 | + activate_controllers=[ |
| 550 | + "motion_primitive_forward_controller", |
| 551 | + "forward_position_controller", |
| 552 | + ], |
| 553 | + ).ok |
| 554 | + ) |
| 555 | + self.assertFalse( |
| 556 | + self._controller_manager_interface.switch_controller( |
| 557 | + strictness=SwitchController.Request.STRICT, |
| 558 | + activate_controllers=[ |
| 559 | + "motion_primitive_forward_controller", |
| 560 | + "passthrough_trajectory_controller", |
| 561 | + ], |
| 562 | + ).ok |
| 563 | + ) |
| 564 | + self.assertFalse( |
| 565 | + self._controller_manager_interface.switch_controller( |
| 566 | + strictness=SwitchController.Request.STRICT, |
| 567 | + activate_controllers=[ |
| 568 | + "motion_primitive_forward_controller", |
| 569 | + "freedrive_mode_controller", |
| 570 | + ], |
| 571 | + ).ok |
| 572 | + ) |
| 573 | + |
| 574 | + # MoPrim controller and force_mode should be possible to combine |
| 575 | + self.assertTrue( |
| 576 | + self._controller_manager_interface.switch_controller( |
| 577 | + strictness=SwitchController.Request.STRICT, |
| 578 | + activate_controllers=[ |
| 579 | + "motion_primitive_forward_controller", |
| 580 | + "force_mode_controller", |
| 581 | + ], |
| 582 | + ).ok |
| 583 | + ) |
| 584 | + self.assertTrue( |
| 585 | + self._controller_manager_interface.switch_controller( |
| 586 | + strictness=SwitchController.Request.STRICT, |
| 587 | + deactivate_controllers=[ |
| 588 | + "motion_primitive_forward_controller", |
| 589 | + "force_mode_controller", |
| 590 | + ], |
| 591 | + ).ok |
| 592 | + ) |
0 commit comments