Public Member Functions | Private Types | Private Member Functions | Private Attributes
mjpeg_server::MJPEGServer Class Reference

#include <mjpeg_server.h>

List of all members.

Public Member Functions

void cleanUp ()
 Closes all client threads.
void client (int fd)
 Client thread function Serve a connected TCP-client. This thread function is called for each connect of a HTTP client like a webbrowser. It determines if it is a valid HTTP request and dispatches between the different response options.
void execute ()
 Runs whenever a new goal is sent to the move_base.
 MJPEGServer (ros::NodeHandle &node)
 Constructor.
void spin ()
 Starts the server and spins.
void stop ()
 Stops the server.
virtual ~MJPEGServer ()
 Destructor - Cleans up.

Private Types

typedef std::map< std::string,
ImageBuffer * > 
ImageBufferMap
typedef std::map< std::string,
size_t > 
ImageSubscriberCountMap
typedef std::map< std::string,
image_transport::Subscriber
ImageSubscriberMap
typedef std::map< std::string,
std::string > 
ParameterMap

Private Member Functions

void decodeBase64 (char *data)
 Decodes the data and stores the result to the same buffer. The buffer will be large enough, because base64 requires more space then plain text.
void decodeParameter (const std::string &parameter, ParameterMap &parameter_map)
 Decodes URI parameters in form of ?parameter=value.
void decreaseSubscriberCount (const std::string topic)
 increase the number of the subscribers of the specified topic
void freeRequest (request *req)
 If strings were assigned to the different members free them. This will fail if strings are static, so always use strdup().
ImageBuffergetImageBuffer (const std::string &topic)
int hexCharToInt (char in)
 Convert a hexadecimal ASCII character to integer.
void imageCallback (const sensor_msgs::ImageConstPtr &msg, const std::string &topic)
void increaseSubscriberCount (const std::string topic)
 decrease the number of the subscribers of the specified topic
void initIOBuffer (iobuffer *iobuf)
 Initializes the iobuffer structure properly.
void initRequest (request *req)
 Initializes the request structure properly.
void invertImage (const cv::Mat &input, cv::Mat &output)
 Rotate input image by 180 degrees.
int readLineWithTimeout (int fd, iobuffer *iobuf, char *buffer, size_t len, int timeout)
 Read a single line from the provided fildescriptor. This funtion will return under two conditions:
int readWithTimeout (int fd, iobuffer *iobuf, char *buffer, size_t len, int timeout)
 read with timeout, implemented without using signals tries to read len bytes and returns if enough bytes were read or the timeout was triggered. In case of timeout the return value may differ from the requested bytes "len".
void sendError (int fd, int which, const char *message)
 Send an error message.
void sendSnapshot (int fd, const char *parameter)
 Send a complete HTTP response and a single JPG-frame.
void sendStream (int fd, const char *parameter)
 Send a complete HTTP response and a stream of JPG-frames.
void splitString (const std::string &str, std::vector< std::string > &tokens, const std::string &delimiter=" ")
 Split string into a list of tokens.
int stringToInt (const std::string &str, const int default_value=0)
 Convert a string to an integer.
int unescape (char *string)
 Replaces XX with the character code it represents, URI.
void unregisterSubscriberIfPossible (const std::string topic)
 remove ros::Subscriber if the number of the subscribers of the topic is equal to 0

Private Attributes

std::string header
ImageBufferMap image_buffers_
boost::mutex image_maps_mutex_
ImageSubscriberMap image_subscribers_
ImageSubscriberCountMap image_subscribers_count_
image_transport::ImageTransport image_transport_
ros::NodeHandle node_
int port_
int sd [MAX_NUM_SOCKETS]
int sd_len
bool stop_requested_
char * www_folder_

Detailed Description

Definition at line 101 of file mjpeg_server.h.


Member Typedef Documentation

typedef std::map<std::string, ImageBuffer*> mjpeg_server::MJPEGServer::ImageBufferMap [private]

Definition at line 148 of file mjpeg_server.h.

typedef std::map<std::string, size_t> mjpeg_server::MJPEGServer::ImageSubscriberCountMap [private]

Definition at line 150 of file mjpeg_server.h.

Definition at line 149 of file mjpeg_server.h.

typedef std::map<std::string, std::string> mjpeg_server::MJPEGServer::ParameterMap [private]

Definition at line 151 of file mjpeg_server.h.


Constructor & Destructor Documentation

Constructor.

Returns:

Definition at line 80 of file mjpeg_server.cpp.

Destructor - Cleans up.

Definition at line 91 of file mjpeg_server.cpp.


Member Function Documentation

Closes all client threads.

Definition at line 1043 of file mjpeg_server.cpp.

Client thread function Serve a connected TCP-client. This thread function is called for each connect of a HTTP client like a webbrowser. It determines if it is a valid HTTP request and dispatches between the different response options.

Definition at line 747 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::decodeBase64 ( char *  data) [private]

Decodes the data and stores the result to the same buffer. The buffer will be large enough, because base64 requires more space then plain text.

Parameters:
base64encoded data
Returns:
plain decoded data

Definition at line 236 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::decodeParameter ( const std::string &  parameter,
ParameterMap parameter_map 
) [private]

Decodes URI parameters in form of ?parameter=value.

Parameters:
URIstring
Returns:
a map of parameter/value pairs

Definition at line 402 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::decreaseSubscriberCount ( const std::string  topic) [private]

increase the number of the subscribers of the specified topic

Parameters:
topicname string

Definition at line 1065 of file mjpeg_server.cpp.

Runs whenever a new goal is sent to the move_base.

Parameters:
goalThe goal to pursue
feedbackFeedback that the action gives to a higher-level monitor, in this case, the position of the robot
Returns:
The result of the execution, ie: Success, Preempted, Aborted, etc.

Definition at line 893 of file mjpeg_server.cpp.

If strings were assigned to the different members free them. This will fail if strings are static, so always use strdup().

Parameters:
req,:pointer to request structure

Definition at line 152 of file mjpeg_server.cpp.

ImageBuffer * mjpeg_server::MJPEGServer::getImageBuffer ( const std::string &  topic) [private]

Definition at line 422 of file mjpeg_server.cpp.

int mjpeg_server::MJPEGServer::hexCharToInt ( char  in) [private]

Convert a hexadecimal ASCII character to integer.

Parameters:
ASCIIcharacter
Returns:
corresponding value between 0 and 15, or -1 in case of error

Definition at line 280 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::imageCallback ( const sensor_msgs::ImageConstPtr &  msg,
const std::string &  topic 
) [private]

Definition at line 96 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::increaseSubscriberCount ( const std::string  topic) [private]

decrease the number of the subscribers of the specified topic

Parameters:
topicname string

Definition at line 1086 of file mjpeg_server.cpp.

Initializes the iobuffer structure properly.

Parameters:
Pointerto already allocated iobuffer

Definition at line 137 of file mjpeg_server.cpp.

Initializes the request structure properly.

Parameters:
Pointerto already allocated req

Definition at line 143 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::invertImage ( const cv::Mat &  input,
cv::Mat &  output 
) [private]

Rotate input image by 180 degrees.

Parameters:
inputimage
outputimage

Definition at line 438 of file mjpeg_server.cpp.

int mjpeg_server::MJPEGServer::readLineWithTimeout ( int  fd,
iobuffer iobuf,
char *  buffer,
size_t  len,
int  timeout 
) [private]

Read a single line from the provided fildescriptor. This funtion will return under two conditions:

  • line end was reached
  • timeout occured
    Parameters:
    fd.....,:fildescriptor to read from
    iobuf..,:iobuffer that allows to use this functions from multiple threads because the complete context is the iobuffer.
    buffer.,:The buffer to store values at, will be set to zero before storing values.
    len....,:the length of buffer
    timeout,:seconds to wait for an answer
    Returns:
    buffer.: will become filled with bytes read
    iobuf..: May get altered to save the context for future calls.
    func().: bytes copied to buffer or -1 in case of error

Definition at line 216 of file mjpeg_server.cpp.

int mjpeg_server::MJPEGServer::readWithTimeout ( int  fd,
iobuffer iobuf,
char *  buffer,
size_t  len,
int  timeout 
) [private]

read with timeout, implemented without using signals tries to read len bytes and returns if enough bytes were read or the timeout was triggered. In case of timeout the return value may differ from the requested bytes "len".

Parameters:
fd.....,:fildescriptor to read from
iobuf..,:iobuffer that allows to use this functions from multiple threads because the complete context is the iobuffer.
buffer.,:The buffer to store values at, will be set to zero before storing values.
len....,:the length of buffer
timeout,:seconds to wait for an answer
Returns:
buffer.: will become filled with bytes read
iobuf..: May get altered to save the context for future calls.
func().: bytes copied to buffer or -1 in case of error

Definition at line 162 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::sendError ( int  fd,
int  which,
const char *  message 
) [private]

Send an error message.

Parameters:
fildescriptorfd to send the answer to
errornumber
errormessage

Definition at line 340 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::sendSnapshot ( int  fd,
const char *  parameter 
) [private]

Send a complete HTTP response and a single JPG-frame.

Parameters:
fildescriptorfd to send the answer to
parameterstring

Definition at line 622 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::sendStream ( int  fd,
const char *  parameter 
) [private]

Send a complete HTTP response and a stream of JPG-frames.

Parameters:
fildescriptorfd to send the answer to
parameterstring

Definition at line 454 of file mjpeg_server.cpp.

Starts the server and spins.

Definition at line 1051 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::splitString ( const std::string &  str,
std::vector< std::string > &  tokens,
const std::string &  delimiter = " " 
) [private]

Split string into a list of tokens.

Parameters:
stringto split
Returns:
vector of tokens

Definition at line 107 of file mjpeg_server.cpp.

Stops the server.

Definition at line 1060 of file mjpeg_server.cpp.

int mjpeg_server::MJPEGServer::stringToInt ( const std::string &  str,
const int  default_value = 0 
) [private]

Convert a string to an integer.

Parameters:
string
defaultreturn value
Returns:
corresponding value, default_value in case of error

Definition at line 125 of file mjpeg_server.cpp.

int mjpeg_server::MJPEGServer::unescape ( char *  string) [private]

Replaces XX with the character code it represents, URI.

Parameters:
stringto unescape
Returns:
0 if everything is ok, -1 in case of error

Definition at line 294 of file mjpeg_server.cpp.

void mjpeg_server::MJPEGServer::unregisterSubscriberIfPossible ( const std::string  topic) [private]

remove ros::Subscriber if the number of the subscribers of the topic is equal to 0

Parameters:
topicname string

Definition at line 1100 of file mjpeg_server.cpp.


Member Data Documentation

std::string mjpeg_server::MJPEGServer::header [private]

Definition at line 153 of file mjpeg_server.h.

Definition at line 316 of file mjpeg_server.h.

Definition at line 319 of file mjpeg_server.h.

Definition at line 317 of file mjpeg_server.h.

Definition at line 318 of file mjpeg_server.h.

Definition at line 307 of file mjpeg_server.h.

Definition at line 306 of file mjpeg_server.h.

Definition at line 308 of file mjpeg_server.h.

Definition at line 310 of file mjpeg_server.h.

Definition at line 311 of file mjpeg_server.h.

Definition at line 313 of file mjpeg_server.h.

Definition at line 314 of file mjpeg_server.h.


The documentation for this class was generated from the following files:


mjpeg_server
Author(s): Benjamin Pitzer
autogenerated on Thu Jun 6 2019 20:12:27