Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_PLANNING_MODELS_LOADER_ROBOT_MODEL_LOADER_
00038 #define MOVEIT_PLANNING_MODELS_LOADER_ROBOT_MODEL_LOADER_
00039
00040 #include <moveit/macros/class_forward.h>
00041 #include <moveit/robot_model/robot_model.h>
00042 #include <moveit/rdf_loader/rdf_loader.h>
00043 #include <moveit/kinematics_plugin_loader/kinematics_plugin_loader.h>
00044
00045 namespace robot_model_loader
00046 {
00047 MOVEIT_CLASS_FORWARD(RobotModelLoader);
00048
00050 class RobotModelLoader
00051 {
00052 public:
00054 struct Options
00055 {
00056 Options(const std::string& robot_description = "robot_description")
00057 : robot_description_(robot_description), urdf_doc_(NULL), srdf_doc_(NULL), load_kinematics_solvers_(true)
00058 {
00059 }
00060
00061 Options(const std::string& urdf_string, const std::string& srdf_string)
00062 : urdf_string_(urdf_string)
00063 , srdf_string_(srdf_string)
00064 , urdf_doc_(NULL)
00065 , srdf_doc_(NULL)
00066 , load_kinematics_solvers_(true)
00067 {
00068 }
00069
00070 Options(TiXmlDocument* urdf_doc, TiXmlDocument* srdf_doc)
00071 : urdf_doc_(urdf_doc), srdf_doc_(srdf_doc), load_kinematics_solvers_(true)
00072 {
00073 }
00074
00078 std::string robot_description_;
00079
00082 std::string urdf_string_, srdf_string_;
00083
00085 TiXmlDocument *urdf_doc_, *srdf_doc_;
00086
00089 bool load_kinematics_solvers_;
00090 };
00091
00093 RobotModelLoader(const Options& opt = Options());
00094
00095 RobotModelLoader(const std::string& robot_description, bool load_kinematics_solvers = true);
00096
00097 ~RobotModelLoader();
00098
00100 const robot_model::RobotModelPtr& getModel() const
00101 {
00102 return model_;
00103 }
00104
00106 const std::string& getRobotDescription() const
00107 {
00108 return rdf_loader_->getRobotDescription();
00109 }
00110
00112 const boost::shared_ptr<urdf::ModelInterface>& getURDF() const
00113 {
00114 return rdf_loader_->getURDF();
00115 }
00116
00118 const boost::shared_ptr<srdf::Model>& getSRDF() const
00119 {
00120 return rdf_loader_->getSRDF();
00121 }
00122
00124 const rdf_loader::RDFLoaderPtr& getRDFLoader() const
00125 {
00126 return rdf_loader_;
00127 }
00128
00131 const kinematics_plugin_loader::KinematicsPluginLoaderPtr& getKinematicsPluginLoader() const
00132 {
00133 return kinematics_loader_;
00134 }
00135
00138 void loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr& kloader =
00139 kinematics_plugin_loader::KinematicsPluginLoaderPtr());
00140
00141 private:
00142 void configure(const Options& opt);
00143
00144 robot_model::RobotModelPtr model_;
00145 rdf_loader::RDFLoaderPtr rdf_loader_;
00146 kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_;
00147 };
00148 }
00149 #endif