GenericObjectContainer.h
Go to the documentation of this file.
00001 #ifndef GENERIC_OBJECT_CONTAINER_H
00002 #define GENERIC_OBJECT_CONTAINER_H
00003 
00004 #include <pluginlib/class_loader.h>
00005 
00006 #include <vector>
00007 #include "GenericObjectHandler.h"
00008 
00009 #include <map>
00010 
00011 #include <rosgraph_msgs/Clock.h>
00012 
00013 class GenericObjectContainer
00014 {
00015 
00016 public:
00017 
00021         GenericObjectContainer();
00022 
00026         virtual ~GenericObjectContainer();
00027 
00031         void removeAll();
00032 
00037         void removeFromID(int theID);
00038 
00044         int insert(boost::shared_ptr<GenericObjectHandler> objectHandler);
00045 
00051         boost::shared_ptr<GenericObjectHandler> getFromID(int theID);
00052 
00058         boost::shared_ptr<GenericObjectHandler> getFromAssociatedObject(int theAssociatedObjectID);
00059 
00065         boost::shared_ptr<GenericObjectHandler> getFromIndex(int ind);
00066 
00071         int getCount();
00072 
00077         void actualizeForSceneContent();
00078 
00082         void startOfSimulation();
00083 
00087         void endOfSimulation();
00088 
00092         void handleSimulation();
00093 
00098     static void simExtGetAllCustomData(SLuaCallBack* p);
00099 
00104     static void simExtGetCustomDataFromHeader(SLuaCallBack* p);
00105 
00111     static void simExtSetFloatCustomDataFromHeader(SLuaCallBack* p);
00112 
00118     static void simExtSetFloatArrayCustomDataFromHeader(SLuaCallBack* p);
00119 
00125     static void simExtSetIntCustomDataFromHeader(SLuaCallBack* p);
00126 
00127 protected:
00128 
00129         std::vector<boost::shared_ptr<GenericObjectHandler> > _allObjects;
00130 
00131         pluginlib::ClassLoader<GenericObjectHandler> _object_handler_loader;
00132         std::map<std::string, boost::shared_ptr<GenericObjectHandler> > _allExistingPlugins;
00133 
00134   ros::NodeHandle _nh;
00135   ros::Publisher _pubClock;
00136   rosgraph_msgs::Clock _clock_msg;
00137 };
00138 
00139 #endif // GENERIC_OBJECT_CONTAINER_H
00140 
00141 
00142 
00143 
00144 
00145 
00146 
00147 
00148 
00149 
00150 
00151 
00152 
00153 
00154 
00155 
00156 
00157 
00158 


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