From ce55506748f74471b9c90b8498f252b745c825d0 Mon Sep 17 00:00:00 2001 From: AndyZe Date: Sun, 15 Sep 2024 20:45:09 -0500 Subject: [PATCH] Update the IKFast tutorial for ROS2 (#966) * Update the IKFast tutorial for ROS2 * Grammar update Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> * Better description of docker script --------- Co-authored-by: Sebastian Castro <4603398+sea-bass@users.noreply.github.com> --- doc/examples/ikfast/ikfast_tutorial.rst | 46 ++++--------------------- 1 file changed, 7 insertions(+), 39 deletions(-) diff --git a/doc/examples/ikfast/ikfast_tutorial.rst b/doc/examples/ikfast/ikfast_tutorial.rst index d20dbb408c..def94ed939 100644 --- a/doc/examples/ikfast/ikfast_tutorial.rst +++ b/doc/examples/ikfast/ikfast_tutorial.rst @@ -1,8 +1,3 @@ -:moveit1: - -.. - Once updated for MoveIt 2, remove all lines above title (including this comment and :moveit1: tag) - IKFast Kinematics Solver ======================== @@ -34,32 +29,7 @@ You should have a MoveIt configuration package for your robot that was created b OpenRAVE is a planning framework as complex as MoveIt itself and installing it is tricky -- particularly because its public documentation is not maintained anymore. Fortunately, personalrobotics provide a `docker image `_ based on Ubuntu 14.04 with OpenRAVE 0.9.0 and ROS Indigo installed, which can be used to generate the solver code once. -So the easiest way to run the IKFast code generator is through this docker image. -For manual building instructions (tailored towards Ubuntu 16.04), please see the `Kinetic version of this tutorial `_. -To follow the recommended, docker-based approach, ensure you have docker installed and started: :: - - sudo apt-get install docker.io - sudo service docker start - -The following command will ensure that you can run docker with your user account (adding $USER to the docker group): :: - - sudo usermod -a -G docker $USER - -You need to log off/log on in order to actually activate this permission change. - -Install the MoveIt IKFast package either from Debian packages or from source. - -**Binary Install**: :: - - sudo apt-get install ros-${ROS_DISTRO}-moveit-kinematics - -**Source** - -Inside your catkin workspace's ``./src`` directory: :: - - git clone https://github.com/moveit/moveit.git - rosdep install -y --from-paths . --ignore-src --rosdistro ${ROS_DISTRO} - catkin build +The commands provided in this tutorial automatically download and start this Docker image, so no extra steps are needed for now. Creating the IKFast MoveIt plugin --------------------------------- @@ -71,7 +41,7 @@ To facilitate copy-and-paste, we suggest to define the robot name as an environm OpenRAVE uses Collada instead of URDF to describe the robot. In order to automatically convert your robot's URDF to Collada, you need to provide the .urdf file. If your .urdf file is generated from `xacro `_ files, you can generate the URDF using the following command: :: - rosrun xacro xacro -o $MYROBOT_NAME.urdf $MYROBOT_NAME.urdf.xacro + ros2 run xacro xacro -o $MYROBOT_NAME.urdf $MYROBOT_NAME.urdf.xacro Select IK Type ^^^^^^^^^^^^^^ @@ -88,21 +58,19 @@ Generate IKFast MoveIt plugin To generate the IKFast MoveIt plugin, issue the following command: :: - rosrun moveit_kinematics auto_create_ikfast_moveit_plugin.sh --iktype Transform6D $MYROBOT_NAME.urdf + ros2 run moveit_kinematics auto_create_ikfast_moveit_plugin.sh --iktype Transform6D $MYROBOT_NAME.urdf The speed and success of this process will depend on the complexity of your robot. A typical 6 DOF manipulator with 3 intersecting axes at the base or wrist will take only a few minutes to generate the solver code. For a detailed explanation of the creation procedure and additional tweaks of the process, see `Tweaking the creation process`_. The command above creates a new ROS package named ``$MYROBOT_NAME__ikfast_plugin`` within the current folder. Thus, you need to rebuild your workspace so the new package is detected: :: - catkin build + colcon build Usage ----- The IKFast plugin can be used as a drop-in replacement for the default KDL IK Solver, but with greatly increased performance. The MoveIt configuration file should be automatically edited by the generator script but in some cases this might fail. In this situation you can switch between the KDL and IKFast solvers using the *kinematics_solver* parameter in the robot's kinematics.yaml file: :: - rosed "$MYROBOT_NAME"_moveit_config kinematics.yaml - Edit these parts: :: : @@ -125,13 +93,13 @@ The process of creating the IKFast MoveIt plugin comprises several steps, perfor 1. Downloading the docker image provided by `personalrobotics `_ 2. Converting the ROS URDF file to Collada required for OpenRAVE: :: - rosrun collada_urdf urdf_to_collada $MYROBOT_NAME.urdf $MYROBOT_NAME.dae + ros2 run collada_urdf urdf_to_collada $MYROBOT_NAME.urdf $MYROBOT_NAME.dae - Sometimes floating point issues arise in converting a URDF file to Collada, which prevents OpenRAVE to find IK solutions. + Sometimes floating point issues arise in converting a URDF file to Collada, which prevents OpenRAVE from finding IK solutions. Using a utility script, one can easily round all numbers down to n decimal places in your .dae file. From experience we recommend 5 decimal places, but if the OpenRave ikfast generator takes too long to find a solution (say more than an hour), lowering the accuracy should help. For example: :: - rosrun moveit_kinematics round_collada_numbers.py $MYROBOT_NAME.dae $MYROBOT_NAME.rounded.dae 5 + ros2 run moveit_kinematics round_collada_numbers.py $MYROBOT_NAME.dae $MYROBOT_NAME.rounded.dae 5 3. Running the OpenRAVE IKFast tool to generate C++ solver code 4. Creating the MoveIt IKFast plugin package wrapping the generated solver