Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Adding constrained_ik to MoveIt kinematics
Description: Covers the steps to expose constrained_ik as an IK solver for MoveItKeywords: industrial, moveit, kinematics
Tutorial Level: INTERMEDIATE
Contents
In this tutorial we will learn to use the constrained_ik IK solver in MoveIt
Link IK Solver to Robot Moveit Package
Create a catkin workspace (http://wiki.ros.org/catkin/Tutorials/create_a_workspace)
- Add a symlink to both the robot moveit package and industrial_moveit package
cd <path_to_catkin_ws>/src ln -s <path_to_robot_moveit_package> <name_of_robot_moveit_package> ln -s <path_to_industrial_moveit_package> industrial_moveit
- Build the workspace
catkin_make
- IMPORTANT: source the catkin workspace first, in EVERY terminal
source devel/setup.bash
Add IK Solver to MoveIt Config File
Locate the kinematics.yaml file in your <robot>_moveit_config/config directory
Edit the kinematics_solver definition to reference the constrained_ik solver
kinematics_solver: constrained_ik/ConstrainedIKPlugin
Run Your Planner
- Run planner for robot. For example:
roslaunch <robot>_moveit_config demo.launch
Explicit Example Code
(I wish every tutorial had this for clarity)
Assumtions:
ROS-Industrial repository abb is checked out to ~/ros/abb
ROS-Industrial repository industrial_moveit is checked out to ~/ros/industrial_moveit
cd ~/ros mkdir -p catkin_ws/src cd catkin_ws catkin_make cd src ln -s ~/ros/abb/ abb ln -s ~/ros/industrial_moveit/ industrial_moveit cd ~/ros/catkin_ws catkin_make source devel/setup.bash roscd irb_2400_moveit_config/config gedit kinematics.yaml
Edit the kinematics_solver line to read kinematics_solver: constrained_ik/ConstrainedIKPlugin. The whole file should look like this:
manipulator: kinematics_solver: constrained_ik/ConstrainedIKPlugin kinematics_solver_search_resolution: 0.005 kinematics_solver_timeout: 0.05 kinematics_solver_attempts: 3
Run the demo code to test the kinematics
roslaunch irb_2400_moveit_config demo.launch