Base class for Inverse Kinematics (IK) solvers. More...
#include <ik_solver_base.h>
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 () |
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.
|
inline |
Definition at line 49 of file ik_solver_base.h.
|
inlinevirtual |
Definition at line 50 of file ik_solver_base.h.
|
pure virtual |
Compute Inverse Kinematics.
q_init | Vector of initial joint positions |
goal | Goal pose with respect to the robot base |
q_out | Vector of suitable joint positions |
Implemented in ros_controllers_cartesian::ExampleIKSolver.
|
pure virtual |
Initialize the solver.
robot_chain | Representation of the robot kinematics |
root_nh | A NodeHandle in the root of the controller manager namespace. |
controller_nh | A NodeHandle in the namespace of the controller. This is where the Cartesian trajectory controller-specific configuration resides. |
Implemented in ros_controllers_cartesian::ExampleIKSolver.