Closed Yadunund closed 1 year ago
Thank you for asking. We do have plans to better document this. @sea-bass will be able to better answer your questions about the general usefulness of this as he is actively using it.
On the parameters, one thing you can check out is this file which describes what each of the parameters is and how they work: https://github.com/PickNikRobotics/pick_ik/blob/main/src/pick_ik_parameters.yaml
I hope to have better documentation than that in the future, but for now, I think reading that is the best information we have.
@tylerjw the parameters schema is very helpful, thanks for pointing me to that 🙇🏼♂️
I'll take the action to actually fill in the README of this repo -- thanks for the prompt @Yadunund!
You should be able to default to pick_ik
as your solver. It does a few fancier things compared to the default KDL solver, which means it may not be as fast, but is more flexible. So my first recommendation is if the default works fine, probably stick with that. The benefits of pick_ik
are:
As you asked about caching, that is not handled directly by pick_ik
, but the cached plugin approach should work. I actually haven't tried it, so if you end up going that route, I would appreciate your feedback.
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
@tylerjw graciously pointed to all the parameters, but there are some key properties to look out for:
mode
: If you choose local
, this solver will only do local gradient descent; If you choose global
, it will also do the evolutionary/genetic part. Will be less performant, but if you're having trouble getting out of local minima, this could help you. My recommendation is use local
for things like relative motion / Cartesian interpolation / servoing, and global
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 the global
solver. The key one is memetic_num_threads
, as we implemented a cool multi-threaded approach.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 than cost_threshold
. Note that if you're adding some fancy cost functions, you may want to turn this up fairly high and rely on twist_threshold
to be your deciding factor whereas this is more of a guideline.twist_threshold
: Optimization succeeds only if the pose difference is less than twist_threshold
. So, e.g., assuming your orientation was spot-on, a twist_threshold
of 0.001 would mean a 1 mm accuracy.rotation_scale
: You specifically asked about this for "position-only IK". 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 on twist_threshold
will ignore orientation if you use rotation_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 play with this solver live in RViz, as this plugin is programmed to respond to parameter changes at every solve. This means that you can change values on the fly from the command line, 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
Hope this is a good starting point, and it helps me also figure out how to frame a good README.
@sea-bass many thanks for the very descriptive response- they're super useful in understanding more about the plugin! pick_ik
sounds really powerful (especially the local vs global modes). Looking forward to testing it out!
Just wanted to say pick_ik
is awesome! Been using it as the default for a few weeks now in simulation and with a physical robot! Previously the ompl planner was unable to sample goal states when I specified really tight goal tolerances (0.0005
) but with pick_ik
, i'm able to plan successfully (had to increase `kinematics_solver_timeout to 0.5). Cartesian interpolation succeeds a lot more often too with better quality paths!
However the tradeoffs have been longer planning times. The rotation_scale
seems to have a big impact on this duration. My application requires precise orientation so I had set this to 1.0
originally. Had to bring it down to 0.5
.
Wondering if you have any other tips for shortening planning duration? What are the implications of increasing the cost_threshold
?
Here are the parameters i'm using
manipulator:
kinematics_solver: pick_ik/PickIkPlugin
kinematics_solver_timeout: 0.5
kinematics_solver_attempts: 3
mode: local
rotation_scale: 0.5
position_threshold: 0.001
orientation_threshold: 0.01
cost_threshold: 0.001
minimal_displacement_weight: 0.0
gd_step_size: 0.0001
cost_threshold: 0.001
center_joints_weight: 0.0
avoid_joint_limits_weight: 0.0
minimal_displacement_weight: 0.0
Great to hear!
I know the planning times are longer with pick_ik, but a timeout of 0.5 seems high regardless. I guess with tight tolerances it makes some sense.
The way the solver works is you will only get a successful solution if position, rotation, and cost are all below their specific thresholds.
Increasing the cost threshold won't make a huge difference if you're only solving for pose without any other side objectives, as the cost is directly tied to the pose error... but it also means you can increase it with no repercussions.
If you were minimizing joint displacement, for example, then you have the choice of either a) turning up the pose thresholds to prioritize the displacement cost objective b) turning up the cose threshold to prioritize meeting the target pose.
I too have seen that the rotation cost can really get the IK solver bogged down, especially for Cartesian interpolation. What worked for me better was using the global solver with multiple threads, adding a minimal joint displacement cost of 0.005 or so, and bumping up the cost threshold to about 0.01.
As far as other ways to speed up planning, besides trying the global solver, you could see if playing with the local solver's gradient descent options (step size, min cost delta, etc.) help. Specifically, you could increase the step size as long as it's not too coarse to overshoot minima. Coupled with the global solver, this may work out?
Thanks for the explanations and recommendations! Very insightful. I assumed the global planner would incur a higher computational load. Is it intrinsically multi threaded or is that a parameter to enable?
Hi there,
Hate to be that guy asking for more documentation when something is actively being developed but I hope these questions won't take much time to answer.
Here are some basic questions I have:
pick_ik
as the kinematics_solver for my move group which is a kinematic chain from base link to tooltip? ie, can I replace thekdl
plugin withpick_ik
in mykinematics.yaml
? Or do you recommend having a separate group that usespick_ik
and then using this group for only the pick and place motions?pick_ik
for a SCARA type robot where one of the links is prismatic? I was able to getkdl
to work for such a robot only after settingposition_only_ik: true
in mykinematics.yaml
.kdl
? Doespick_ik
do any caching or would the user need to implement a cached ik plugin ofpick_ik
(assuming caching does not worsen performance for this plugin)?kinematics.yaml
file that is configured to usepick_ik
?Thanks in advance!