Define a inverse kinematics plugin which the factory can create an instance. More...
#include <kinematics_plugin_factory.h>
Public Types | |
using | ConstPtr = std::shared_ptr< const InvKinFactory > |
using | Ptr = std::shared_ptr< InvKinFactory > |
Public Member Functions | |
virtual std::unique_ptr< InverseKinematics > | create (const std::string &solver_name, const tesseract_scene_graph::SceneGraph &scene_graph, const tesseract_scene_graph::SceneState &scene_state, const KinematicsPluginFactory &plugin_factory, const YAML::Node &config) const =0 |
Create Inverse Kinematics Object. More... | |
virtual | ~InvKinFactory ()=default |
Static Protected Member Functions | |
static std::string | getSection () |
Friends | |
class | boost_plugin_loader::PluginLoader |
Define a inverse kinematics plugin which the factory can create an instance.
Definition at line 61 of file kinematics_plugin_factory.h.
using tesseract_kinematics::InvKinFactory::ConstPtr = std::shared_ptr<const InvKinFactory> |
Definition at line 65 of file kinematics_plugin_factory.h.
using tesseract_kinematics::InvKinFactory::Ptr = std::shared_ptr<InvKinFactory> |
Definition at line 64 of file kinematics_plugin_factory.h.
|
virtualdefault |
|
pure virtual |
Create Inverse Kinematics Object.
solver_name | The solver name of the kinematic object |
scene_graph | The Tesseract Scene Graph |
scene_state | The state of the scene graph |
plugin_factory | Provide access to the plugin factory so plugins and load plugins |
Implemented in tesseract_kinematics::KDLInvKinChainNR_JLFactory, tesseract_kinematics::KDLInvKinChainNRFactory, tesseract_kinematics::KDLInvKinChainLMAFactory, tesseract_kinematics::REPInvKinFactory, tesseract_kinematics::ROPInvKinFactory, tesseract_kinematics::OPWInvKinFactory, tesseract_kinematics::URInvKinFactory, and tesseract_kinematics::IKFastInvKinFactory.
|
staticprotected |
Definition at line 50 of file kinematics_plugin_factory.cpp.
|
friend |
Definition at line 85 of file kinematics_plugin_factory.h.