00001 00002 //"Echo" example, SimulatedDevice_Echo.h 00003 #ifndef SIMULATEDDEVICE_ECHO_H_ 00004 #define SIMULATEDDEVICE_ECHO_H_ 00005 #include "SimulatedDevice.h" 00006 using namespace uwsim; 00007 00008 /* 00009 * Example header of driver/rosinterface configuration/factory 00010 * 00011 * Included in SimulatedDevices.cpp 00012 */ 00013 00014 //Driver/ROSInterface configuration 00015 class SimDev_Echo_Config : public SimulatedDeviceConfig 00016 { 00017 public: 00018 //XML members 00019 std::string info; 00020 //constructor 00021 SimDev_Echo_Config(std::string type_) : 00022 SimulatedDeviceConfig(type_) 00023 { 00024 } 00025 }; 00026 00027 //Driver/ROSInterface factory class 00028 class SimDev_Echo_Factory : public SimulatedDeviceFactory 00029 { 00030 public: 00031 //this is the only place the device/interface type is set 00032 SimDev_Echo_Factory(std::string type_ = "echo") : 00033 SimulatedDeviceFactory(type_) 00034 { 00035 } 00036 ; 00037 00038 SimulatedDeviceConfig::Ptr processConfig(const xmlpp::Node* node, ConfigFile * config); 00039 bool applyConfig(SimulatedIAUV * auv, Vehicle &vehicleChars, SceneBuilder *sceneBuilder, size_t iteration); 00040 std::vector<boost::shared_ptr<ROSInterface> > getInterface(ROSInterfaceInfo & rosInterface, 00041 std::vector<boost::shared_ptr<SimulatedIAUV> > & iauvFile); 00042 }; 00043 00044 //can be a sparate header file for actual implementation classes... 00045 00046 #include "ConfigXMLParser.h" 00047 #include "ROSInterface.h" 00048 #include <ros/ros.h> 00049 #include <std_msgs/String.h> 00050 00051 //Driver class 00052 class SimDev_Echo : public SimulatedDevice 00053 { 00054 void applyPhysics(BulletPhysics * bulletPhysics) 00055 { 00056 } 00057 public: 00058 std::string info; //Device's property 00059 00060 SimDev_Echo(SimDev_Echo_Config * cfg); 00061 }; 00062 00063 //ROS publishers and subscribers work exactly as before, no subclassing is needed 00064 class SimDev_Echo_ROSPublisher : public ROSPublisherInterface 00065 { 00066 //this is just an example, use a pointer to SimulatedIAUV, if only ROSInterface is implemented 00067 //pointer to a device 00068 SimDev_Echo * dev; 00069 public: 00070 SimDev_Echo_ROSPublisher(SimDev_Echo *dev, std::string topic, int rate) : 00071 ROSPublisherInterface(topic, rate), dev(dev) 00072 { 00073 } 00074 00075 void createPublisher(ros::NodeHandle &nh); 00076 void publish(); 00077 00078 ~SimDev_Echo_ROSPublisher() 00079 { 00080 } 00081 }; 00082 00083 #endif