A wrapper around KDL's Levenberg Marquardt solver. More...
#include <ik_solver_example.h>
Public Member Functions | |
virtual int | cartToJnt (const KDL::JntArray &q_init, const KDL::Frame &goal, KDL::JntArray &q_out) override |
Compute Inverse Kinematics with KDL's Levenberg Marquardt solver. More... | |
ExampleIKSolver () | |
bool | init (const KDL::Chain &robot_chain, ros::NodeHandle &, ros::NodeHandle &) override |
Initialize the solver. More... | |
~ExampleIKSolver () | |
![]() | |
IKSolver () | |
virtual | ~IKSolver () |
Private Attributes | |
std::unique_ptr< KDL::ChainIkSolverPos_LMA > | lma_solver_ |
KDL::Chain | robot_chain_ |
A wrapper around KDL's Levenberg Marquardt solver.
This is the default Inverse Kinematics (IK) solver for the cartesian_trajectory_controller.
You may explicitly specify this solver with "example_solver" as ik_solver in the controllers.yaml configuration file:
Definition at line 42 of file ik_solver_example.h.
|
inline |
Definition at line 45 of file ik_solver_example.h.
|
inline |
Definition at line 46 of file ik_solver_example.h.
|
inlineoverridevirtual |
Compute Inverse Kinematics with KDL's Levenberg Marquardt solver.
Implements ros_controllers_cartesian::IKSolver.
Definition at line 65 of file ik_solver_example.h.
|
inlineoverridevirtual |
Initialize the solver.
Only the kinematics chain is used.
Implements ros_controllers_cartesian::IKSolver.
Definition at line 54 of file ik_solver_example.h.
|
private |
Definition at line 68 of file ik_solver_example.h.
|
private |
Definition at line 72 of file ik_solver_example.h.