diff --git a/doc/wiki/Home.md b/doc/wiki/Home.md index b4fbeea5..226e0070 100644 --- a/doc/wiki/Home.md +++ b/doc/wiki/Home.md @@ -115,7 +115,7 @@ Note: The examples need user interaction in `rviz`, the `Next` button (`RvizVisu ### Planning in impedance mode -Planning with `Moveit`, or simply moving the robot in impedance mode is quite tricky, as often there is a mismatch between the actual and commanded positions. +Planning with `Moveit`, or simply moving the robot in impedance mode is quite tricky, as often there is a mismatch between the actual and commanded positions. Both `Moveit` and the `joint_trajectory_controller` start planning/execution from the actually measured values, creating a jump in the commands (from the previous command to the measured state), which can trigger a joint limit violation. To solve this issue, the planning request must be modified to start from the commanded position instead of the measured one. For example in the `moveit_basic_planners_example` the following lines must be added before each planning request: ```C++ @@ -126,7 +126,7 @@ For example in the `moveit_basic_planners_example` the following lines must be a example_node->moveGroupInterface()->setStartState(start_state); ``` Additionally the `trajectory_execution.allowed_start_tolerfance` parameter in `moveit_controllers.yaml` (found in the moveit support packages) should be increased based on the actual displacement between commanded and measured joint values. - + If you would like to only move the robot by sending a goal to the `joint_trajectory_controller` for interpolation (e.g. with the [example trajectory publisher](https://github.com/kroshu/kuka_drivers/blob/master/examples/iiqka_moveit_example/launch/launch_trajectory_publisher.launch.py)), the following line should be added to the controller configuration file: ```yaml open_loop_control: true