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 #ifndef _ROS_POPULATION_PLUGIN_HH_
00019 #define _ROS_POPULATION_PLUGIN_HH_
00020
00021 #include <memory>
00022 #include <gazebo/physics/PhysicsTypes.hh>
00023 #include <sdf/sdf.hh>
00024 #include "osrf_gear/PopulationControl.h"
00025 #include "osrf_gear/PopulationPlugin.hh"
00026
00027 namespace gazebo
00028 {
00030 class ROSPopulationPluginPrivate;
00031
00033 class ROSPopulationPlugin : public PopulationPlugin
00034 {
00036 public: ROSPopulationPlugin();
00037
00039 public: virtual ~ROSPopulationPlugin();
00040
00041
00042 public: virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf);
00043
00045 public: virtual void Reset();
00046
00051 public: bool OnPopulationControl(
00052 osrf_gear::PopulationControl::Request &_req,
00053 osrf_gear::PopulationControl::Response &_res);
00054
00055
00056 private: virtual void Publish() const;
00057
00060 private: std::unique_ptr<ROSPopulationPluginPrivate> dataPtr;
00061 };
00062 }
00063 #endif