|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
3 #ifndef IMAGE_SAMPLER_IMAGE_SAMPLER_H_
4 #define IMAGE_SAMPLER_IMAGE_SAMPLER_H_
6 #include <pluginlib/class_list_macros.h>
8 #include <image_transport/image_transport.h>
9 #include <ros/publisher.h>
10 #include <ros/subscriber.h>
13 #include <ff_msgs/ConfigureCamera.h>
14 #include <ff_msgs/EnableCamera.h>
15 #include <ff_msgs/CameraState.h>
23 #define PERCH_CAM_ID 3
34 bool ConfigureService(ff_msgs::ConfigureCamera::Request& req, ff_msgs::ConfigureCamera::Response& res,
int camera);
35 bool ConfigureServiceNavCam(ff_msgs::ConfigureCamera::Request& req, ff_msgs::ConfigureCamera::Response& res);
37 bool ConfigureServiceHazCam(ff_msgs::ConfigureCamera::Request& req, ff_msgs::ConfigureCamera::Response& res);
39 bool EnableService(ff_msgs::EnableCamera::Request& req, ff_msgs::EnableCamera::Response& res,
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);
42 bool EnableServiceDockCam(ff_msgs::EnableCamera::Request& req, ff_msgs::EnableCamera::Response& res);
43 bool EnableServiceHazCam(ff_msgs::EnableCamera::Request& req, ff_msgs::EnableCamera::Response& res);
44 bool EnableServicePerchCam(ff_msgs::EnableCamera::Request& req, ff_msgs::EnableCamera::Response& res);
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];
58 ros::Publisher camera_state_pub_;
63 ros::Duration record_publication_interval_[
NUM_CAMERAS];
64 ros::Duration stream_publication_interval_[
NUM_CAMERAS];
68 ff_msgs::CameraState camera_states_[2 *
NUM_CAMERAS];
73 #endif // IMAGE_SAMPLER_IMAGE_SAMPLER_H_
void HazCamCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: image_sampler.cc:228
virtual void Initialize(ros::NodeHandle *nh)
Definition: image_sampler.cc:37
Definition: camera_model.h:26
bool EnableServiceNavCam(ff_msgs::EnableCamera::Request &req, ff_msgs::EnableCamera::Response &res)
Definition: image_sampler.cc:165
void NavCamCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: image_sampler.cc:220
void DockCamCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: image_sampler.cc:224
ImageSampler()
Definition: image_sampler.cc:30
bool ConfigureServiceNavCam(ff_msgs::ConfigureCamera::Request &req, ff_msgs::ConfigureCamera::Response &res)
Definition: image_sampler.cc:113
Definition: image_sampler.h:27
bool ConfigureServiceHazCam(ff_msgs::ConfigureCamera::Request &req, ff_msgs::ConfigureCamera::Response &res)
Definition: image_sampler.cc:123
bool ConfigureService(ff_msgs::ConfigureCamera::Request &req, ff_msgs::ConfigureCamera::Response &res, int camera)
Definition: image_sampler.cc:133
bool EnableServiceHazCam(ff_msgs::EnableCamera::Request &req, ff_msgs::EnableCamera::Response &res)
Definition: image_sampler.cc:175
bool ConfigureServiceDockCam(ff_msgs::ConfigureCamera::Request &req, ff_msgs::ConfigureCamera::Response &res)
Definition: image_sampler.cc:118
bool EnableServicePerchCam(ff_msgs::EnableCamera::Request &req, ff_msgs::EnableCamera::Response &res)
Definition: image_sampler.cc:183
Definition: ff_nodelet.h:57
~ImageSampler()
Definition: image_sampler.cc:34
void ImageCallback(const sensor_msgs::ImageConstPtr &msg, int camera)
Definition: image_sampler.cc:236
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
#define NUM_CAMERAS
Definition: image_sampler.h:19
Definition: image_sampler.h:25
void UpdateState(int camera, bool streaming, int width, int height, float rate)
Definition: image_sampler.cc:96
double Time
Definition: time.h:23
bool ConfigureServicePerchCam(ff_msgs::ConfigureCamera::Request &req, ff_msgs::ConfigureCamera::Response &res)
Definition: image_sampler.cc:128
void PerchCamCallback(const sensor_msgs::ImageConstPtr &msg)
Definition: image_sampler.cc:232
bool EnableServiceDockCam(ff_msgs::EnableCamera::Request &req, ff_msgs::EnableCamera::Response &res)
Definition: image_sampler.cc:170