36 #ifndef USB_CAM_USB_CAM_H 37 #define USB_CAM_USB_CAM_H 43 #include <sensor_msgs/Image.h> 46 #include <std_srvs/Empty.h> 47 #include <std_srvs/Trigger.h> 83 std_srvs::Empty::Response& response);
88 std_srvs::Empty::Response& response);
92 std_srvs::Trigger::Response& response);
96 std_srvs::Trigger::Response& response);
ros::ServiceServer _service_supported_formats
static image_transport::ImageTransport * image_transport
static bool service_supported_controls_callback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
ros::ServiceServer _service_supported_controls
ros::ServiceServer _service_stop
static ros::ServiceServer * service_supported_controls
static ros::ServiceServer * service_stop
UsbCam operator=(const UsbCam &root)=delete
std::string _service_stop_name
image_transport::CameraPublisher _image_pub
ros::ServiceServer _service_start
static sensor_msgs::Image * img_msg
static ros::ServiceServer * service_start
static camera_info_manager::CameraInfoManager * camera_info
static bool service_start_callback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
static void frame_timer_callback(const ros::TimerEvent &event)
static std::string camera_info_url
static bool service_supported_formats_callback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
static bool create_suspended
sensor_msgs::Image _img_msg
static ros::Timer * frame_timer
image_transport::ImageTransport _image_transport
static std::string camera_transport_suffix
std::string _service_start_name
static std::string camera_name
static UsbCam & Instance()
static image_transport::CameraPublisher * image_pub
static std::string camera_frame_id
static ros::ServiceServer * service_supported_formats
static bool service_stop_callback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)