#include <compressed_subscriber.h>
|
| CompressedSubscriber () |
|
virtual std::string | getTransportName () const |
|
virtual void | shutdown () |
|
virtual | ~CompressedSubscriber () |
|
virtual uint32_t | getNumPublishers () const |
|
virtual std::string | getTopic () const |
|
virtual | ~SimpleSubscriberPlugin () |
|
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 () |
|
|
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) |
|
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::NodeHandle & | nh () const |
|
|
typedef boost::function< void(const sensor_msgs::ImageConstPtr &)> | Callback |
|
static std::string | getLookupName (const std::string &transport_type) |
|
Definition at line 44 of file compressed_subscriber.h.
◆ Config
◆ ReconfigureServer
◆ CompressedSubscriber()
compressed_image_transport::CompressedSubscriber::CompressedSubscriber |
( |
| ) |
|
◆ ~CompressedSubscriber()
compressed_image_transport::CompressedSubscriber::~CompressedSubscriber |
( |
| ) |
|
|
virtual |
◆ configCb()
void compressed_image_transport::CompressedSubscriber::configCb |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protected |
◆ 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 |
◆ getTransportName()
virtual std::string compressed_image_transport::CompressedSubscriber::getTransportName |
( |
| ) |
const |
|
inlinevirtual |
◆ internalCallback()
void compressed_image_transport::CompressedSubscriber::internalCallback |
( |
const sensor_msgs::CompressedImageConstPtr & |
message, |
|
|
const Callback & |
user_cb |
|
) |
| |
|
protectedvirtual |
◆ shutdown()
void compressed_image_transport::CompressedSubscriber::shutdown |
( |
| ) |
|
|
virtual |
◆ subscribeImpl()
◆ config_
Config compressed_image_transport::CompressedSubscriber::config_ |
|
protected |
◆ imdecode_flag_
int compressed_image_transport::CompressedSubscriber::imdecode_flag_ |
|
protected |
◆ reconfigure_server_
◆ tj_
tjhandle compressed_image_transport::CompressedSubscriber::tj_ |
|
protected |
The documentation for this class was generated from the following files: