Protected Member Functions | Protected Attributes | List of all members
video_stream_opencv::VideoStreamNodelet Class Reference
Inheritance diagram for video_stream_opencv::VideoStreamNodelet:
Inheritance graph
[legend]

Protected Member Functions

virtual void configCallback (VideoStreamConfig &new_config, uint32_t level)
 
virtual void connectionCallback (const image_transport::SingleSubscriberPublisher &)
 
virtual void connectionCallbackImpl ()
 
virtual void disconnectionCallback (const image_transport::SingleSubscriberPublisher &)
 
virtual void disconnectionCallbackImpl ()
 
virtual void do_capture ()
 
virtual void do_publish (const ros::TimerEvent &event)
 
virtual sensor_msgs::CameraInfo get_default_camera_info_from_image (sensor_msgs::ImagePtr img)
 
virtual void infoConnectionCallback (const ros::SingleSubscriberPublisher &)
 
virtual void infoDisconnectionCallback (const ros::SingleSubscriberPublisher &)
 
virtual void onInit ()
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 
virtual ~VideoStreamNodelet ()
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Protected Attributes

std::mutex c_mutex
 
sensor_msgs::CameraInfo cam_info_msg
 
boost::shared_ptr< cv::VideoCapture > cap
 
boost::thread capture_thread
 
bool capture_thread_running
 
VideoStreamConfig config
 
boost::shared_ptr< dynamic_reconfigure::Server< VideoStreamConfig > > dyn_srv
 
cv::Mat frame
 
std::queue< cv::Mat > framesQueue
 
boost::shared_ptr< ros::NodeHandlenh
 
std::mutex p_mutex
 
boost::shared_ptr< ros::NodeHandlepnh
 
image_transport::CameraPublisher pub
 
ros::Timer publish_timer
 
std::mutex q_mutex
 
std::mutex s_mutex
 
int subscriber_num
 
std::string video_stream_provider
 
std::string video_stream_provider_type
 

Additional Inherited Members

- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Detailed Description

Definition at line 58 of file video_stream.cpp.

Constructor & Destructor Documentation

virtual video_stream_opencv::VideoStreamNodelet::~VideoStreamNodelet ( )
inlineprotectedvirtual

Definition at line 463 of file video_stream.cpp.

Member Function Documentation

virtual void video_stream_opencv::VideoStreamNodelet::configCallback ( VideoStreamConfig &  new_config,
uint32_t  level 
)
inlineprotectedvirtual

Definition at line 360 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::connectionCallback ( const image_transport::SingleSubscriberPublisher )
inlineprotectedvirtual

Definition at line 344 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::connectionCallbackImpl ( )
inlineprotectedvirtual

Definition at line 322 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::disconnectionCallback ( const image_transport::SingleSubscriberPublisher )
inlineprotectedvirtual

Definition at line 352 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::disconnectionCallbackImpl ( )
inlineprotectedvirtual

Definition at line 330 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::do_capture ( )
inlineprotectedvirtual

Definition at line 106 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::do_publish ( const ros::TimerEvent event)
inlineprotectedvirtual

Definition at line 168 of file video_stream.cpp.

virtual sensor_msgs::CameraInfo video_stream_opencv::VideoStreamNodelet::get_default_camera_info_from_image ( sensor_msgs::ImagePtr  img)
inlineprotectedvirtual

Definition at line 78 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::infoConnectionCallback ( const ros::SingleSubscriberPublisher )
inlineprotectedvirtual

Definition at line 348 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::infoDisconnectionCallback ( const ros::SingleSubscriberPublisher )
inlineprotectedvirtual

Definition at line 356 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::onInit ( )
inlineprotectedvirtual

Implements nodelet::Nodelet.

Definition at line 404 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::subscribe ( )
inlineprotectedvirtual

Definition at line 223 of file video_stream.cpp.

virtual void video_stream_opencv::VideoStreamNodelet::unsubscribe ( )
inlineprotectedvirtual

Definition at line 314 of file video_stream.cpp.

Member Data Documentation

std::mutex video_stream_opencv::VideoStreamNodelet::c_mutex
protected

Definition at line 64 of file video_stream.cpp.

sensor_msgs::CameraInfo video_stream_opencv::VideoStreamNodelet::cam_info_msg
protected

Definition at line 74 of file video_stream.cpp.

boost::shared_ptr<cv::VideoCapture> video_stream_opencv::VideoStreamNodelet::cap
protected

Definition at line 67 of file video_stream.cpp.

boost::thread video_stream_opencv::VideoStreamNodelet::capture_thread
protected

Definition at line 72 of file video_stream.cpp.

bool video_stream_opencv::VideoStreamNodelet::capture_thread_running
protected

Definition at line 71 of file video_stream.cpp.

VideoStreamConfig video_stream_opencv::VideoStreamNodelet::config
protected

Definition at line 63 of file video_stream.cpp.

boost::shared_ptr<dynamic_reconfigure::Server<VideoStreamConfig> > video_stream_opencv::VideoStreamNodelet::dyn_srv
protected

Definition at line 62 of file video_stream.cpp.

cv::Mat video_stream_opencv::VideoStreamNodelet::frame
protected

Definition at line 66 of file video_stream.cpp.

std::queue<cv::Mat> video_stream_opencv::VideoStreamNodelet::framesQueue
protected

Definition at line 65 of file video_stream.cpp.

boost::shared_ptr<ros::NodeHandle> video_stream_opencv::VideoStreamNodelet::nh
protected

Definition at line 60 of file video_stream.cpp.

std::mutex video_stream_opencv::VideoStreamNodelet::p_mutex
protected

Definition at line 64 of file video_stream.cpp.

boost::shared_ptr<ros::NodeHandle> video_stream_opencv::VideoStreamNodelet::pnh
protected

Definition at line 60 of file video_stream.cpp.

image_transport::CameraPublisher video_stream_opencv::VideoStreamNodelet::pub
protected

Definition at line 61 of file video_stream.cpp.

ros::Timer video_stream_opencv::VideoStreamNodelet::publish_timer
protected

Definition at line 73 of file video_stream.cpp.

std::mutex video_stream_opencv::VideoStreamNodelet::q_mutex
protected

Definition at line 64 of file video_stream.cpp.

std::mutex video_stream_opencv::VideoStreamNodelet::s_mutex
protected

Definition at line 64 of file video_stream.cpp.

int video_stream_opencv::VideoStreamNodelet::subscriber_num
protected

Definition at line 70 of file video_stream.cpp.

std::string video_stream_opencv::VideoStreamNodelet::video_stream_provider
protected

Definition at line 68 of file video_stream.cpp.

std::string video_stream_opencv::VideoStreamNodelet::video_stream_provider_type
protected

Definition at line 69 of file video_stream.cpp.


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


video_stream_opencv
Author(s): Sammy Pfeiffer
autogenerated on Wed Apr 14 2021 02:45:12