GenericObjectHandler.h
Go to the documentation of this file.
00001 #ifndef GENERIC_OBJECT_HANDLER_H
00002 #define GENERIC_OBJECT_HANDLER_H
00003 
00004 #include <vector>
00005 
00006 #include <ros/ros.h>
00007 #include <v_repTypes.h>
00008 
00012 class GenericObjectHandler
00013 {
00014 public:
00015         GenericObjectHandler();
00016         virtual ~GenericObjectHandler();
00017 
00022         void setID(int newID);
00023 
00028         int getID();
00029 
00035         void setAssociatedObject(int objID,int objUniqueID);
00036 
00041         int getAssociatedObject();
00042 
00047         int getAssociatedObjectUniqueId();
00048 
00052         void synchronizeSceneObject();
00053 
00057         virtual void synchronize();
00058 
00062         void getDeveloperCustomData(std::vector<unsigned char> &developerCustomData);
00063 
00067         void startOfSimulation();
00068 
00072         virtual bool endOfSimulation();
00073 
00077         virtual void handleSimulation() = 0;
00078 
00082         virtual unsigned int getObjectType() const = 0;
00083 
00084 protected:
00085         
00090         virtual void _initialize() = 0;
00091 
00095         int _id;
00096 
00100         int _associatedObjectUniqueID;
00101 
00105         int _associatedObjectID;
00106 
00110         std::string _associatedObjectName;
00111 
00115     bool _initialized;
00116 
00120     ros::NodeHandle _nh;
00121 
00122 };
00123 
00124 
00125 #endif // ndef GENERIC_OBJECT_HANDLER_H


vrep_ros_plugin
Author(s): Riccardo Spica , Giovanni Claudio
autogenerated on Sat Jun 8 2019 20:22:41