As discussed in the MoveIt 2 documentation, you can use the MoveIt Setup Assistant or change the kinematics.yaml
file for your robot setup to use pick_ik
as the IK solver.
An example kinematics.yaml
file might look as follows:
panda_arm:
kinematics_solver: pick_ik/PickIkPlugin
kinematics_solver_timeout: 0.05
kinematics_solver_attempts: 3
mode: global
rotation_scale: 0.5
twist_threshold: 0.001
cost_threshold: 0.001
minimal_displacement_weight: 0.0
gd_step_size: 0.0001
As a sanity check, you could follow the MoveIt Quickstart in RViz tutorial and change the moveit_resources/panda_moveit_config/config/kinematics.yaml/kinematics.yaml
file to use a configuration like the one above.
For an exhaustive list of parameters, refer to the parameters YAML file.
Some key parameters you may want to start with are:
mode
: If you chooselocal
, this solver will only do local gradient descent; If you chooseglobal
, it will also enable the evolutionary algorithm. Using the global solver will be less performant, but if you're having trouble getting out of local minima, this could help you. We recommend usinglocal
for things like relative motion / Cartesian interpolation / endpoint jogging, andglobal
if you need to solve for goals with a far-away initial conditions.memetic_<property>
: All the properties that only kick in if you use theglobal
solver. The key one ismemetic_num_threads
, as we have enabled the evolutionary algorithm to solve on multiple threads.cost_threshold
: This solver works by setting up cost functions based on how far away your pose is, how much your joints move relative to the initial guess, and custom cost functions you can add. Optimization succeeds only if the cost is less thancost_threshold
. Note that if you're adding custom cost functions, you may want to set this threshold fairly high and rely ontwist_threshold
to be your deciding factor whereas this is more of a guideline.twist_threshold
: Optimization succeeds only if the pose difference is less thantwist_threshold
. So, e.g., assuming your orientation was perfectly met, atwist_threshold
of 0.001 would mean a 1 mm accuracy.rotation_scale
: If you want position-only IK, set this to 0.0. If you want to treat position and orientation equally, set this to 1.0. You can also use any value in between; it's part of the cost function. Note that the exit condition ontwist_threshold
will ignore orientation if you userotation_scale = 0.0
.minimal_displacement_weight
: This is one of the standard cost functions that checks for the joint angle difference between the initial guess and the solution. If you're solving for far-away goals, leave it to zero or it will hike up your cost function for no reason. Have this to a small non-zero value (e.g., 0.001) if you're doing things like Cartesian interpolation along a path, or endpoint jogging for servoing.
You can test out this solver live in RViz, as this plugin uses the generate_parameter_library
package to respond to parameter changes at every solve. This means that you can change values on the fly using the ROS 2 command-line interface, e.g.,
ros2 param set /rviz2 robot_description_kinematics.panda_arm.mode global
ros2 param set /rviz2 robot_description_kinematics.panda_arm.minimal_displacement_weight 0.001
The kinematics plugin allows you to pass in an additional argument of type IkCostFn
, which can be passed in from common entrypoints such as RobotState::setFromIK()
. See this page for a usage example.
Alternatively, consider adding your own cost functions to the pick_ik
source code (specifically, in goal.hpp
and goal.cpp
and submit a pull request with the new functionality you add.