#ifndef NEWDEVICE_H_ #define NEWDEVICE_H_ #include "SimulatedDevice.h" #include using namespace uwsim; /* You will need to add your code HERE */ class NewDevice_Factory : public SimulatedDeviceFactory { public: //this is the only place the device/interface type is set NewDevice_Factory(std::string type_ = "NewDevice") : SimulatedDeviceFactory(type_) { } ; SimulatedDeviceConfig::Ptr processConfig(const xmlpp::Node* node, ConfigFile * config); bool applyConfig(SimulatedIAUV * auv, Vehicle &vehicleChars, SceneBuilder *sceneBuilder, size_t iteration); std::vector > getInterface(ROSInterfaceInfo & rosInterface, std::vector > & iauvFile); }; #include "ConfigXMLParser.h" #include #include "SimulatedIAUV.h" #include class NewDevice_Config : public SimulatedDeviceConfig { public: //XML members std::string relativeTo; double position[3], orientation[3]; //constructor NewDevice_Config(std::string type_) : SimulatedDeviceConfig(type_) { } }; class NewDevice : public SimulatedDevice { public: osg::Node *parent; NewDevice(NewDevice_Config * cfg,osg::Node *trackNode); }; #include "ROSInterface.h" class NewDevice_ROSPublisher : public ROSPublisherInterface { NewDevice * dev; public: NewDevice_ROSPublisher(NewDevice *dev, std::string topic, int rate) : ROSPublisherInterface(topic, rate), dev(dev) { } void createPublisher(ros::NodeHandle &nh); void publish(); ~NewDevice_ROSPublisher() { } }; #endif