diff --git a/.github/upstream.repos b/.github/upstream.repos index c58ba8069e..39117f15a8 100644 --- a/.github/upstream.repos +++ b/.github/upstream.repos @@ -15,3 +15,7 @@ repositories: type: git url: https://github.com/PickNikRobotics/rosparam_shortcuts version: ros2 + moveit2: + type: git + url: https://github.com/ros-planning/moveit2.git + version: 2.5.2 diff --git a/doc/examples/realtime_servo/realtime_servo_tutorial.rst b/doc/examples/realtime_servo/realtime_servo_tutorial.rst index 35620f1355..796070d0fa 100644 --- a/doc/examples/realtime_servo/realtime_servo_tutorial.rst +++ b/doc/examples/realtime_servo/realtime_servo_tutorial.rst @@ -107,6 +107,41 @@ Servo includes a number of nice features: 5. Joint position and velocity limits enforced 6. Inputs are generic ROS messages +Inverse Kinematics in Servo +^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Inverse Kinematics may be handled internally by MoveIt Servo via inverse Jacobian calculations. However, you may also use an IK plugin. +To configure an IK plugin for use in Servo, your robot config package must define one in a :code:`kinematics.yaml` file, such as the one +in the `Panda config package `_. +Several IK plugins are available `within MoveIt `_, +as well as `externally `_. +:code:`bio_ik/BioIKKinematicsPlugin` is the most common choice. + +Once your :code:`kinematics.yaml` file has been populated, include it with the ROS parameters passed to the servo node in your launch file: + +.. code-block:: python + + moveit_config = ( + MoveItConfigsBuilder("moveit_resources_panda") + .robot_description(file_path="config/panda.urdf.xacro") + .to_moveit_configs() + ) + servo_node = Node( + package="moveit_servo", + executable="servo_node_main", + parameters=[ + servo_params, + moveit_config.robot_description, + moveit_config.robot_description_semantic, + moveit_config.robot_description_kinematics, # here is where kinematics plugin parameters are passed + ], + ) + + +The above excerpt is taken from `servo_example.launch.py `_ in MoveIt. +In the above example, the :code:`kinematics.yaml` file is taken from the `moveit_resources `_ repository in the workspace, specifically :code:`moveit_resources/panda_moveit_config/config/kinematics.yaml`. +The actual ROS parameter names that get passed by loading the yaml file are of the form :code:`robot_description_kinematics..`, e.g. :code:`robot_description_kinematics.panda_arm.kinematics_solver`. + Setup on a New Robot --------------------