Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef MJPEG_SERVER_H_
00037 #define MJPEG_SERVER_H_
00038
00039 #include <ros/ros.h>
00040 #include <sensor_msgs/Image.h>
00041 #include <image_transport/image_transport.h>
00042
00043 #include <cv_bridge/cv_bridge.h>
00044
00045 #include <boost/thread/mutex.hpp>
00046 #include <boost/thread/condition.hpp>
00047
00048
00049
00050
00051 #define MAX_NUM_SOCKETS 100
00052 #define IO_BUFFER 256
00053 #define BUFFER_SIZE 1024
00054
00055 namespace mjpeg_server {
00056
00057
00058 typedef enum {
00059 A_UNKNOWN,
00060 A_STREAM,
00061 A_SNAPSHOT,
00062 } answer_t;
00063
00064
00065
00066
00067
00068 typedef struct {
00069 answer_t type;
00070 char *parameter;
00071 char *client;
00072 char *credentials;
00073 } request;
00074
00075
00076 typedef struct {
00077 int level;
00078 char buffer[IO_BUFFER];
00079 } iobuffer;
00080
00085 class ImageBuffer {
00086 public:
00087 ImageBuffer() {}
00088 sensor_msgs::Image msg;
00089 boost::condition_variable condition_;
00090 boost::mutex mutex_;
00091 };
00092
00097 class MJPEGServer {
00098 public:
00103 MJPEGServer(ros::NodeHandle& node);
00104
00108 virtual ~MJPEGServer();
00109
00116 void execute();
00117
00121 void spin();
00122
00126 void stop();
00127
00131 void cleanUp();
00132
00140 void client(int fd);
00141
00142 private:
00143 typedef std::map<std::string, ImageBuffer*> ImageBufferMap;
00144 typedef std::map<std::string, image_transport::Subscriber> ImageSubscriberMap;
00145 typedef std::map<std::string, std::string> ParameterMap;
00146
00147 std::string header;
00148
00149 ImageBuffer* getImageBuffer(const std::string& topic);
00150
00151
00152 void imageCallback(const sensor_msgs::ImageConstPtr& msg, const std::string& topic);
00153
00159 void invertImage(const cv::Mat& input, cv::Mat& output);
00160
00167 void sendError(int fd, int which, const char *message);
00168
00174 void sendStream(int fd, const char *parameter);
00175
00181 void sendSnapshot(int fd, const char *parameter);
00182
00187 void initIOBuffer(iobuffer *iobuf);
00188
00193 void initRequest(request *req);
00194
00200 void freeRequest(request *req);
00201
00218 int readWithTimeout(int fd, iobuffer *iobuf, char *buffer, size_t len, int timeout);
00219
00236 int readLineWithTimeout(int fd, iobuffer *iobuf, char *buffer, size_t len, int timeout);
00237
00245 void decodeBase64(char *data);
00246
00252 int hexCharToInt(char in);
00253
00259 int unescape(char *string);
00260
00266 void splitString(const std::string& str, std::vector<std::string>& tokens, const std::string& delimiter = " ");
00267
00274 int stringToInt(const std::string& str, const int default_value = 0);
00275
00281 void decodeParameter(const std::string& parameter, ParameterMap& parameter_map);
00282
00283
00284 ros::NodeHandle node_;
00285 image_transport::ImageTransport image_transport_;
00286 int port_;
00287
00288 int sd[MAX_NUM_SOCKETS];
00289 int sd_len;
00290
00291 bool stop_requested_;
00292 char* www_folder_;
00293
00294 ImageBufferMap image_buffers_;
00295 ImageSubscriberMap image_subscribers_;
00296 boost::mutex image_maps_mutex_;
00297
00298 };
00299
00300 }
00301
00302 #endif
00303