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/robot_model/robot_model.h>
00041 #include <moveit/rdf_loader/rdf_loader.h>
00042 #include <moveit/kinematics_plugin_loader/kinematics_plugin_loader.h>
00043
00044 namespace robot_model_loader
00045 {
00046
00048 class RobotModelLoader
00049 {
00050 public:
00051
00053 struct Options
00054 {
00055 Options(const std::string &robot_description = "robot_description") :
00056 robot_description_(robot_description),
00057 urdf_doc_(NULL),
00058 srdf_doc_(NULL),
00059 load_kinematics_solvers_(true)
00060 {
00061 }
00062
00063 Options(const std::string &urdf_string, const std::string &srdf_string) :
00064 urdf_string_(urdf_string),
00065 srdf_string_(srdf_string),
00066 urdf_doc_(NULL),
00067 srdf_doc_(NULL),
00068 load_kinematics_solvers_(true)
00069 {
00070 }
00071
00072 Options(TiXmlDocument *urdf_doc, TiXmlDocument *srdf_doc) :
00073 urdf_doc_(urdf_doc),
00074 srdf_doc_(srdf_doc),
00075 load_kinematics_solvers_(true)
00076 {
00077 }
00078
00081 std::string robot_description_;
00082
00084 std::string urdf_string_, srdf_string_;
00085
00087 TiXmlDocument *urdf_doc_, *srdf_doc_;
00088
00090 bool load_kinematics_solvers_;
00091
00092 };
00093
00094
00096 RobotModelLoader(const Options &opt = Options());
00097
00098 RobotModelLoader(const std::string &robot_description, bool load_kinematics_solvers = true);
00099
00100 ~RobotModelLoader();
00101
00103 const robot_model::RobotModelPtr& getModel() const
00104 {
00105 return model_;
00106 }
00107
00109 const std::string& getRobotDescription() const
00110 {
00111 return rdf_loader_->getRobotDescription();
00112 }
00113
00115 const boost::shared_ptr<urdf::ModelInterface>& getURDF() const
00116 {
00117 return rdf_loader_->getURDF();
00118 }
00119
00121 const boost::shared_ptr<srdf::Model>& getSRDF() const
00122 {
00123 return rdf_loader_->getSRDF();
00124 }
00125
00127 const rdf_loader::RDFLoaderPtr& getRDFLoader() const
00128 {
00129 return rdf_loader_;
00130 }
00131
00134 const kinematics_plugin_loader::KinematicsPluginLoaderPtr& getKinematicsPluginLoader() const
00135 {
00136 return kinematics_loader_;
00137 }
00138
00140 void loadKinematicsSolvers(const kinematics_plugin_loader::KinematicsPluginLoaderPtr &kloader = kinematics_plugin_loader::KinematicsPluginLoaderPtr());
00141
00142 private:
00143
00144 void configure(const Options &opt);
00145
00146 robot_model::RobotModelPtr model_;
00147 rdf_loader::RDFLoaderPtr rdf_loader_;
00148 kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_;
00149
00150 };
00151
00152 typedef boost::shared_ptr<RobotModelLoader> RobotModelLoaderPtr;
00153 typedef boost::shared_ptr<const RobotModelLoader> RobotModelLoaderConstPtr;
00154
00155 }
00156 #endif