rop_factory.h
Go to the documentation of this file.
1 
26 #ifndef TESSERACT_KINEMATICS_ROP_FACTORY_H
27 #define TESSERACT_KINEMATICS_ROP_FACTORY_H
28 
30 #include <boost_plugin_loader/macros.h>
31 
32 namespace tesseract_kinematics
33 {
35 {
36  std::unique_ptr<InverseKinematics> create(const std::string& solver_name,
37  const tesseract_scene_graph::SceneGraph& scene_graph,
38  const tesseract_scene_graph::SceneState& scene_state,
39  const KinematicsPluginFactory& plugin_factory,
40  const YAML::Node& config) const override final;
41 };
42 
43 PLUGIN_ANCHOR_DECL(ROPInvKinFactoriesAnchor)
44 
45 } // namespace tesseract_kinematics
46 
47 #endif // TESSERACT_KINEMATICS_ROP_FACTORY_H
tesseract_kinematics::InvKinFactory
Define a inverse kinematics plugin which the factory can create an instance.
Definition: kinematics_plugin_factory.h:61
tesseract_kinematics::ROPInvKinFactory::create
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 override final
Create Inverse Kinematics Object.
Definition: rop_factory.cpp:37
tesseract_scene_graph::SceneGraph
tesseract_scene_graph::SceneState
tesseract_kinematics::ROPInvKinFactory
Definition: rop_factory.h:34
kinematics_plugin_factory.h
Kinematics Plugin Factory.
tesseract_kinematics
Definition: forward_kinematics.h:40
tesseract_kinematics::KinematicsPluginFactory
Definition: kinematics_plugin_factory.h:116


tesseract_kinematics
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:02:14