Public Member Functions | Private Attributes | List of all members
ros_controllers_cartesian::ExampleIKSolver Class Reference

A wrapper around KDL's Levenberg Marquardt solver. More...

#include <ik_solver_example.h>

Inheritance diagram for ros_controllers_cartesian::ExampleIKSolver:
Inheritance graph
[legend]

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 ()
 
- Public Member Functions inherited from ros_controllers_cartesian::IKSolver
 IKSolver ()
 
virtual ~IKSolver ()
 

Private Attributes

std::unique_ptr< KDL::ChainIkSolverPos_LMA > lma_solver_
 
KDL::Chain robot_chain_
 

Detailed Description

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:

<name_of_your_controller>:
type: "position_controllers/CartesianTrajectoryController"
ik_solver: "example_solver"
...

Definition at line 42 of file ik_solver_example.h.

Constructor & Destructor Documentation

◆ ExampleIKSolver()

ros_controllers_cartesian::ExampleIKSolver::ExampleIKSolver ( )
inline

Definition at line 45 of file ik_solver_example.h.

◆ ~ExampleIKSolver()

ros_controllers_cartesian::ExampleIKSolver::~ExampleIKSolver ( )
inline

Definition at line 46 of file ik_solver_example.h.

Member Function Documentation

◆ cartToJnt()

virtual int ros_controllers_cartesian::ExampleIKSolver::cartToJnt ( const KDL::JntArray &  q_init,
const KDL::Frame &  goal,
KDL::JntArray &  q_out 
)
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.

◆ init()

bool ros_controllers_cartesian::ExampleIKSolver::init ( const KDL::Chain &  robot_chain,
ros::NodeHandle ,
ros::NodeHandle  
)
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.

Member Data Documentation

◆ lma_solver_

std::unique_ptr<KDL::ChainIkSolverPos_LMA> ros_controllers_cartesian::ExampleIKSolver::lma_solver_
private

Definition at line 68 of file ik_solver_example.h.

◆ robot_chain_

KDL::Chain ros_controllers_cartesian::ExampleIKSolver::robot_chain_
private

Definition at line 72 of file ik_solver_example.h.


The documentation for this class was generated from the following file:


cartesian_trajectory_controller
Author(s):
autogenerated on Tue Oct 15 2024 02:09:16