NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
image_sampler.h
Go to the documentation of this file.
1 // Copyright 2016 Intelligent RObotics Group, NASA ARC
2 
3 #ifndef IMAGE_SAMPLER_IMAGE_SAMPLER_H_
4 #define IMAGE_SAMPLER_IMAGE_SAMPLER_H_
5 
6 #include <pluginlib/class_list_macros.h>
7 
8 #include <image_transport/image_transport.h>
9 #include <ros/publisher.h>
10 #include <ros/subscriber.h>
11 
12 #include <ff_util/ff_nodelet.h>
13 #include <ff_msgs/ConfigureCamera.h>
14 #include <ff_msgs/EnableCamera.h>
15 #include <ff_msgs/CameraState.h>
16 
17 #include <string>
18 
19 #define NUM_CAMERAS 4
20 #define NAV_CAM_ID 0
21 #define DOCK_CAM_ID 1
22 #define HAZ_CAM_ID 2
23 #define PERCH_CAM_ID 3
24 
25 namespace image_sampler {
26 
28  public:
29  ImageSampler();
30  ~ImageSampler();
31 
32  protected:
33  virtual void Initialize(ros::NodeHandle *nh);
34  bool ConfigureService(ff_msgs::ConfigureCamera::Request& req, ff_msgs::ConfigureCamera::Response& res, int camera); // NOLINT
35  bool ConfigureServiceNavCam(ff_msgs::ConfigureCamera::Request& req, ff_msgs::ConfigureCamera::Response& res); // NOLINT
36  bool ConfigureServiceDockCam(ff_msgs::ConfigureCamera::Request& req, ff_msgs::ConfigureCamera::Response& res); // NOLINT
37  bool ConfigureServiceHazCam(ff_msgs::ConfigureCamera::Request& req, ff_msgs::ConfigureCamera::Response& res); // NOLINT
38  bool ConfigureServicePerchCam(ff_msgs::ConfigureCamera::Request& req, ff_msgs::ConfigureCamera::Response& res); // NOLINT
39  bool EnableService(ff_msgs::EnableCamera::Request& req, ff_msgs::EnableCamera::Response& res, // NOLINT
40  int camera, std::string topic, void (ImageSampler::*callback)(const sensor_msgs::ImageConstPtr &));
41  bool EnableServiceNavCam(ff_msgs::EnableCamera::Request& req, ff_msgs::EnableCamera::Response& res); // NOLINT
42  bool EnableServiceDockCam(ff_msgs::EnableCamera::Request& req, ff_msgs::EnableCamera::Response& res); // NOLINT
43  bool EnableServiceHazCam(ff_msgs::EnableCamera::Request& req, ff_msgs::EnableCamera::Response& res); // NOLINT
44  bool EnableServicePerchCam(ff_msgs::EnableCamera::Request& req, ff_msgs::EnableCamera::Response& res); // NOLINT
45  void NavCamCallback(const sensor_msgs::ImageConstPtr & msg);
46  void DockCamCallback(const sensor_msgs::ImageConstPtr & msg);
47  void HazCamCallback(const sensor_msgs::ImageConstPtr & msg);
48  void PerchCamCallback(const sensor_msgs::ImageConstPtr & msg);
49  void ImageCallback(const sensor_msgs::ImageConstPtr & msg, int camera);
50  void UpdateState(int camera, bool streaming, int width, int height, float rate);
51 
52  private:
53  image_transport::Subscriber image_sub_[NUM_CAMERAS];
54  image_transport::CameraPublisher record_image_pub_[NUM_CAMERAS];
55  image_transport::CameraPublisher stream_image_pub_[NUM_CAMERAS];
56  ros::ServiceServer configure_srv_[NUM_CAMERAS];
57  ros::ServiceServer enable_srv_[NUM_CAMERAS];
58  ros::Publisher camera_state_pub_;
59 
60  std::string camera_topics_[NUM_CAMERAS];
61  int record_output_width_[NUM_CAMERAS], record_output_height_[NUM_CAMERAS];
62  int stream_output_width_[NUM_CAMERAS], stream_output_height_[NUM_CAMERAS];
63  ros::Duration record_publication_interval_[NUM_CAMERAS];
64  ros::Duration stream_publication_interval_[NUM_CAMERAS];
65  ros::Time record_last_publish_time_[NUM_CAMERAS];
66  ros::Time stream_last_publish_time_[NUM_CAMERAS];
67 
68  ff_msgs::CameraState camera_states_[2 * NUM_CAMERAS];
69 };
70 
71 } // namespace image_sampler
72 
73 #endif // IMAGE_SAMPLER_IMAGE_SAMPLER_H_
image_sampler::ImageSampler::HazCamCallback
void HazCamCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: image_sampler.cc:228
image_sampler::ImageSampler::Initialize
virtual void Initialize(ros::NodeHandle *nh)
Definition: image_sampler.cc:37
camera
Definition: camera_model.h:26
image_sampler::ImageSampler::EnableServiceNavCam
bool EnableServiceNavCam(ff_msgs::EnableCamera::Request &req, ff_msgs::EnableCamera::Response &res)
Definition: image_sampler.cc:165
image_sampler::ImageSampler::NavCamCallback
void NavCamCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: image_sampler.cc:220
image_sampler::ImageSampler::DockCamCallback
void DockCamCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: image_sampler.cc:224
image_sampler::ImageSampler::ImageSampler
ImageSampler()
Definition: image_sampler.cc:30
image_sampler::ImageSampler::ConfigureServiceNavCam
bool ConfigureServiceNavCam(ff_msgs::ConfigureCamera::Request &req, ff_msgs::ConfigureCamera::Response &res)
Definition: image_sampler.cc:113
image_sampler::ImageSampler
Definition: image_sampler.h:27
ff_nodelet.h
image_sampler::ImageSampler::ConfigureServiceHazCam
bool ConfigureServiceHazCam(ff_msgs::ConfigureCamera::Request &req, ff_msgs::ConfigureCamera::Response &res)
Definition: image_sampler.cc:123
image_sampler::ImageSampler::ConfigureService
bool ConfigureService(ff_msgs::ConfigureCamera::Request &req, ff_msgs::ConfigureCamera::Response &res, int camera)
Definition: image_sampler.cc:133
image_sampler::ImageSampler::EnableServiceHazCam
bool EnableServiceHazCam(ff_msgs::EnableCamera::Request &req, ff_msgs::EnableCamera::Response &res)
Definition: image_sampler.cc:175
image_sampler::ImageSampler::ConfigureServiceDockCam
bool ConfigureServiceDockCam(ff_msgs::ConfigureCamera::Request &req, ff_msgs::ConfigureCamera::Response &res)
Definition: image_sampler.cc:118
image_sampler::ImageSampler::EnableServicePerchCam
bool EnableServicePerchCam(ff_msgs::EnableCamera::Request &req, ff_msgs::EnableCamera::Response &res)
Definition: image_sampler.cc:183
ff_util::FreeFlyerNodelet
Definition: ff_nodelet.h:57
image_sampler::ImageSampler::~ImageSampler
~ImageSampler()
Definition: image_sampler.cc:34
image_sampler::ImageSampler::ImageCallback
void ImageCallback(const sensor_msgs::ImageConstPtr &msg, int camera)
Definition: image_sampler.cc:236
image_sampler::ImageSampler::EnableService
bool EnableService(ff_msgs::EnableCamera::Request &req, ff_msgs::EnableCamera::Response &res, int camera, std::string topic, void(ImageSampler::*callback)(const sensor_msgs::ImageConstPtr &))
Definition: image_sampler.cc:191
NUM_CAMERAS
#define NUM_CAMERAS
Definition: image_sampler.h:19
image_sampler
Definition: image_sampler.h:25
image_sampler::ImageSampler::UpdateState
void UpdateState(int camera, bool streaming, int width, int height, float rate)
Definition: image_sampler.cc:96
localization_common::Time
double Time
Definition: time.h:23
image_sampler::ImageSampler::ConfigureServicePerchCam
bool ConfigureServicePerchCam(ff_msgs::ConfigureCamera::Request &req, ff_msgs::ConfigureCamera::Response &res)
Definition: image_sampler.cc:128
image_sampler::ImageSampler::PerchCamCallback
void PerchCamCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: image_sampler.cc:232
image_sampler::ImageSampler::EnableServiceDockCam
bool EnableServiceDockCam(ff_msgs::EnableCamera::Request &req, ff_msgs::EnableCamera::Response &res)
Definition: image_sampler.cc:170