Public Member Functions | List of all members
ros_controllers_cartesian::IKSolver Class Referenceabstract

Base class for Inverse Kinematics (IK) solvers. More...

#include <ik_solver_base.h>

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

Public Member Functions

virtual int cartToJnt (const KDL::JntArray &q_init, const KDL::Frame &goal, KDL::JntArray &q_out)=0
 Compute Inverse Kinematics. More...
 
 IKSolver ()
 
virtual bool init (const KDL::Chain &robot_chain, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)=0
 Initialize the solver. More...
 
virtual ~IKSolver ()
 

Detailed Description

Base class for Inverse Kinematics (IK) solvers.

This base class is meant to provide an interface for custom IK implementations. The joint-based control policies in the Cartesian trajectory controller will need some form of IK solver. This allows you to implement your own (possibly more advanced) algorithm. For instance, you may wish to consider collision checking by reacting ad-hoc to objects that additional sensors perceive in your environment.

Definition at line 46 of file ik_solver_base.h.

Constructor & Destructor Documentation

◆ IKSolver()

ros_controllers_cartesian::IKSolver::IKSolver ( )
inline

Definition at line 49 of file ik_solver_base.h.

◆ ~IKSolver()

virtual ros_controllers_cartesian::IKSolver::~IKSolver ( )
inlinevirtual

Definition at line 50 of file ik_solver_base.h.

Member Function Documentation

◆ cartToJnt()

virtual int ros_controllers_cartesian::IKSolver::cartToJnt ( const KDL::JntArray &  q_init,
const KDL::Frame &  goal,
KDL::JntArray &  q_out 
)
pure virtual

Compute Inverse Kinematics.

Parameters
q_initVector of initial joint positions
goalGoal pose with respect to the robot base
q_outVector of suitable joint positions
Returns
0 if successful. Derived classes implement specializations.

Implemented in ros_controllers_cartesian::ExampleIKSolver.

◆ init()

virtual bool ros_controllers_cartesian::IKSolver::init ( const KDL::Chain &  robot_chain,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
pure virtual

Initialize the solver.

Parameters
robot_chainRepresentation of the robot kinematics
root_nhA NodeHandle in the root of the controller manager namespace.
controller_nhA NodeHandle in the namespace of the controller. This is where the Cartesian trajectory controller-specific configuration resides.
Returns
True if initialization was successful.

Implemented in ros_controllers_cartesian::ExampleIKSolver.


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