VrMagicRosBridge_host.h
Go to the documentation of this file.
00001 
00002 #ifndef VRMAGICROSBRIDGE_SERVER_H_
00003 #define VRMAGICROSBRIDGE_SERVER_H_
00004 
00005 #include <ros/ros.h>
00006 #include <sensor_msgs/Image.h>
00007 #include <sensor_msgs/image_encodings.h>
00008 
00009 #include <string>
00010 #include <sstream>
00011 #include <map>
00012 
00013 #include "VrMagicHandler_roshost/VrMagicHandler_roshost.h"
00014 
00015 class VrMagicRosBridge_host
00016 {
00017 
00018 public:
00019     VrMagicRosBridge_host();
00020     virtual ~VrMagicRosBridge_host();
00021 
00033     void start(const unsigned int rate = 10);
00034 
00035 private:    //functions
00036 
00046     void run();
00047 
00048     int addPublisher(unsigned int id);
00049 
00050     int removePublischer(unsigned int id);
00051 
00052     bool provePublisherExist(unsigned int id);
00053 
00054     void setMsgImage(unsigned int id);
00055 
00056 private:    //dataelements
00057     unsigned int _loopRate;
00058     std::string _pubName_base;
00059 
00060     ohm::ImageType _imgSmarcam;
00061 
00062     ohm::VrMagicHandler_roshost* _smartcamHandler;
00063 
00064     ros::Rate* _rate;
00065     ros::NodeHandle _nh;
00066 
00067     std::map<unsigned int, ros::Publisher> _publishers;
00068     std::map<unsigned int, sensor_msgs::Image*> _msgImgs;
00069     std::map<unsigned int, unsigned int> _seq;
00070 };
00071 
00072 #endif /* VRMAGICROSBRIDGE_SERVER_H_ */


vrmagic_ros_bridge_server
Author(s): Michael Schmidpeter
autogenerated on Thu Aug 27 2015 15:40:39