Public Member Functions | Private Member Functions | Private Attributes | List of all members
JPEGStreamer Class Reference

Public Member Functions

void add_connection (struct mg_connection *con, boost::condition_variable *cond, boost::mutex *single_mutex)
 
 JPEGStreamer ()
 

Private Member Functions

void image_callback (const sensor_msgs::CompressedImage::ConstPtr &msg)
 

Private Attributes

boost::mutex con_mutex
 
list< boost::tuple< struct mg_connection *, boost::condition_variable *, boost::mutex * > > connections
 
boost::mutex data_mutex
 
ros::Subscriber image_sub
 
ros::NodeHandle node
 
int skip
 
int skipped
 
mg_contextweb_context
 

Detailed Description

Definition at line 14 of file jpeg_streamer.cpp.

Constructor & Destructor Documentation

JPEGStreamer::JPEGStreamer ( )

Definition at line 43 of file jpeg_streamer.cpp.

Member Function Documentation

void JPEGStreamer::add_connection ( struct mg_connection con,
boost::condition_variable cond,
boost::mutex *  single_mutex 
)

Definition at line 78 of file jpeg_streamer.cpp.

void JPEGStreamer::image_callback ( const sensor_msgs::CompressedImage::ConstPtr &  msg)
private

Definition at line 88 of file jpeg_streamer.cpp.

Member Data Documentation

boost::mutex JPEGStreamer::con_mutex
private

Definition at line 23 of file jpeg_streamer.cpp.

list<boost::tuple<struct mg_connection*, boost::condition_variable*, boost::mutex*> > JPEGStreamer::connections
private

Definition at line 25 of file jpeg_streamer.cpp.

boost::mutex JPEGStreamer::data_mutex
private

Definition at line 24 of file jpeg_streamer.cpp.

ros::Subscriber JPEGStreamer::image_sub
private

Definition at line 21 of file jpeg_streamer.cpp.

ros::NodeHandle JPEGStreamer::node
private

Definition at line 20 of file jpeg_streamer.cpp.

int JPEGStreamer::skip
private

Definition at line 29 of file jpeg_streamer.cpp.

int JPEGStreamer::skipped
private

Definition at line 29 of file jpeg_streamer.cpp.

mg_context* JPEGStreamer::web_context
private

Definition at line 22 of file jpeg_streamer.cpp.


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


jpeg_streamer
Author(s): Ken Tossell
autogenerated on Mon Jun 10 2019 12:51:47