Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
compressed_image_transport::CompressedSubscriber Class Reference

#include <compressed_subscriber.h>

Inheritance diagram for compressed_image_transport::CompressedSubscriber:
Inheritance graph
[legend]

Public Member Functions

 CompressedSubscriber ()
 
virtual std::string getTransportName () const
 
virtual void shutdown ()
 
virtual ~CompressedSubscriber ()
 
- Public Member Functions inherited from image_transport::SimpleSubscriberPlugin< sensor_msgs::CompressedImage >
virtual uint32_t getNumPublishers () const
 
virtual std::string getTopic () const
 
virtual ~SimpleSubscriberPlugin ()
 
- Public Member Functions inherited from image_transport::SubscriberPlugin
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints())
 
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
 
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &), const TransportHints &transport_hints=TransportHints())
 
virtual ~SubscriberPlugin ()
 

Protected Types

typedef compressed_image_transport::CompressedSubscriberConfig Config
 
typedef dynamic_reconfigure::Server< ConfigReconfigureServer
 

Protected Member Functions

void configCb (Config &config, uint32_t level)
 
sensor_msgs::ImagePtr decompressJPEG (const std::vector< uint8_t > &data, const std::string &source_encoding, const std_msgs::Header &header)
 
virtual void internalCallback (const sensor_msgs::CompressedImageConstPtr &message, const Callback &user_cb)
 
virtual void subscribeImpl (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object, const image_transport::TransportHints &transport_hints)
 
- Protected Member Functions inherited from image_transport::SimpleSubscriberPlugin< sensor_msgs::CompressedImage >
virtual std::string getTopicToSubscribe (const std::string &base_topic) const
 
virtual void internalCallback (const typename sensor_msgs::CompressedImage ::ConstPtr &message, const Callback &user_cb)=0
 
const ros::NodeHandlenh () const
 

Protected Attributes

Config config_
 
int imdecode_flag_
 
boost::shared_ptr< ReconfigureServerreconfigure_server_
 
tjhandle tj_
 

Additional Inherited Members

- Public Types inherited from image_transport::SubscriberPlugin
typedef boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
 
- Static Public Member Functions inherited from image_transport::SubscriberPlugin
static std::string getLookupName (const std::string &transport_type)
 

Detailed Description

Definition at line 44 of file compressed_subscriber.h.

Member Typedef Documentation

◆ Config

typedef compressed_image_transport::CompressedSubscriberConfig compressed_image_transport::CompressedSubscriber::Config
protected

Definition at line 69 of file compressed_subscriber.h.

◆ ReconfigureServer

typedef dynamic_reconfigure::Server<Config> compressed_image_transport::CompressedSubscriber::ReconfigureServer
protected

Definition at line 70 of file compressed_subscriber.h.

Constructor & Destructor Documentation

◆ CompressedSubscriber()

compressed_image_transport::CompressedSubscriber::CompressedSubscriber ( )

Definition at line 55 of file compressed_subscriber.cpp.

◆ ~CompressedSubscriber()

compressed_image_transport::CompressedSubscriber::~CompressedSubscriber ( )
virtual

Definition at line 59 of file compressed_subscriber.cpp.

Member Function Documentation

◆ configCb()

void compressed_image_transport::CompressedSubscriber::configCb ( Config config,
uint32_t  level 
)
protected

Definition at line 79 of file compressed_subscriber.cpp.

◆ decompressJPEG()

sensor_msgs::ImagePtr compressed_image_transport::CompressedSubscriber::decompressJPEG ( const std::vector< uint8_t > &  data,
const std::string &  source_encoding,
const std_msgs::Header header 
)
protected

Definition at line 97 of file compressed_subscriber.cpp.

◆ getTransportName()

virtual std::string compressed_image_transport::CompressedSubscriber::getTransportName ( ) const
inlinevirtual

Implements image_transport::SubscriberPlugin.

Definition at line 50 of file compressed_subscriber.h.

◆ internalCallback()

void compressed_image_transport::CompressedSubscriber::internalCallback ( const sensor_msgs::CompressedImageConstPtr &  message,
const Callback user_cb 
)
protectedvirtual

Definition at line 183 of file compressed_subscriber.cpp.

◆ shutdown()

void compressed_image_transport::CompressedSubscriber::shutdown ( )
virtual

◆ subscribeImpl()

void compressed_image_transport::CompressedSubscriber::subscribeImpl ( ros::NodeHandle nh,
const std::string &  base_topic,
uint32_t  queue_size,
const Callback callback,
const ros::VoidPtr tracked_object,
const image_transport::TransportHints transport_hints 
)
protectedvirtual

Member Data Documentation

◆ config_

Config compressed_image_transport::CompressedSubscriber::config_
protected

Definition at line 72 of file compressed_subscriber.h.

◆ imdecode_flag_

int compressed_image_transport::CompressedSubscriber::imdecode_flag_
protected

Definition at line 73 of file compressed_subscriber.h.

◆ reconfigure_server_

boost::shared_ptr<ReconfigureServer> compressed_image_transport::CompressedSubscriber::reconfigure_server_
protected

Definition at line 71 of file compressed_subscriber.h.

◆ tj_

tjhandle compressed_image_transport::CompressedSubscriber::tj_
protected

Definition at line 74 of file compressed_subscriber.h.


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


compressed_image_transport
Author(s): Patrick Mihelich, Julius Kammerl, David Gossow
autogenerated on Fri Feb 10 2023 03:31:21