Tesseract
Motion Planning Environment
|
Define a forward kinematics plugin which the factory can create an instance. More...
#include <kinematics_plugin_factory.h>
Public Types | |
using | Ptr = std::shared_ptr< FwdKinFactory > |
using | ConstPtr = std::shared_ptr< const FwdKinFactory > |
Public Member Functions | |
virtual | ~FwdKinFactory ()=default |
virtual ForwardKinematics::UPtr | 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... | |
Static Protected Attributes | |
static const std::string | SECTION_NAME = "FwdKin" |
Friends | |
class | PluginLoader |
Define a forward kinematics plugin which the factory can create an instance.
using tesseract_kinematics::FwdKinFactory::ConstPtr = std::shared_ptr<const FwdKinFactory> |
using tesseract_kinematics::FwdKinFactory::Ptr = std::shared_ptr<FwdKinFactory> |
|
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::KDLFwdKinChainFactory.
|
friend |
|
staticprotected |