NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
ff::RosCompressedImageRapidImage Class Reference

#include <ros_compressed_image_rapid_image.h>

Inheritance diagram for ff::RosCompressedImageRapidImage:
Inheritance graph

Public Member Functions

 RosCompressedImageRapidImage (const std::string &subscribe_topic, const std::string &pub_topic, const ros::NodeHandle &nh, const unsigned int queue_size=10)
 
void CallBack (const sensor_msgs::CompressedImage::ConstPtr &msg)
 

Additional Inherited Members

- Protected Member Functions inherited from ff::RosSubRapidPub
 RosSubRapidPub (const std::string &subscribe_topic, const std::string &pub_topic, const ros::NodeHandle &nh, const unsigned int queue_size)
 
 RosSubRapidPub (const std::string &subscribe_topic, const std::string &pub_topic, const ros::NodeHandle &nh, const unsigned int queue_size)
 
- Protected Attributes inherited from ff::RosSubRapidPub
ros::NodeHandle nh_
 
ros::Subscriber sub_
 
std::string subscribe_topic_
 
std::string publish_topic_
 
unsigned int queue_size_
 

Detailed Description

RosCompressedImageRapidImage will use the ros::Subscriber to subscribe to the compressed image type

Constructor & Destructor Documentation

◆ RosCompressedImageRapidImage()

ff::RosCompressedImageRapidImage::RosCompressedImageRapidImage ( const std::string &  subscribe_topic,
const std::string &  pub_topic,
const ros::NodeHandle &  nh,
const unsigned int  queue_size = 10 
)

Member Function Documentation

◆ CallBack()

void ff::RosCompressedImageRapidImage::CallBack ( const sensor_msgs::CompressedImage::ConstPtr &  msg)

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