The kinematics.yaml
contains default parameters and I would like to change for certain planning operations the solve_type
parameters.
I don't believe this will work. That file is only read once, during startup (of roslaunch
actually).
MoveIt instantiates the IK solver then once (well: depending on how many groups you have configured of course), which reads the parameters, once, and those get used until a new Trac IK instance is created.
This is the only time TRAC_IKKinematicsPlugin
(ie: the plugin class) reads that parameter: link.
So how to retrieve the IK solver pointer in order to change some parameters, and so that it is updated for the MoveGroupInterface?
Internally, Trac IK stores the value of that parameter in a private member variable called solve_type_
(here). There doesn't appear to be any setter (nor a getter) for that member variable.
So even with a reference to the IK solver's instance, you would not be able to change the value of that member variable.
Having written that: the plugin does check how it's been configured before solving a query (here).
So theoretically, you could add dynamic_reconfigure support to the MoveIt plugin, expose that solve_type_
member as a dynamic_reconfigure
variable, and then use dynamic_reconfigure
's service API to update the solve type dynamically. Note: you'd still need to add a setter though.
It would not be linked to any particular query though, as it wouldn't be part of the IK request. But it would allow you to change the solve type after the MoveIt IK plugin has been instantiated.
Edit:
I want to change this parameters in the code and without user intervention.
dynamic_reconfigure
has a service interface which is non-user-facing. It's exactly there to be used "from code". It does not require any user interaction.
Any advices about how could I maybe dynamically cast it to a "TRAC-IK solver" in oder to set this parameter?
Without creating that setter you'll not be able to change anything.
But if you're willing to do all sorts of nasty things, then:
- add the setter
- downcast the reference to the specific
TRAC_IKKinematicsPlugin
- use the setter
It would be very brittle though, as you'd have to be sure what you have is actually an instance of TRAC_IKKinematicsPlugin
.
And using dynamic_cast
this way is not what most people consider proper use.
Yes, this matters, as only Trac IK uses the
solve_type
parameter.I've updated the title of your question to mention your use of Trac IK.