3 #ifndef CV_CAMERA_CAPTURE_H 4 #define CV_CAMERA_CAPTURE_H 12 #include <sensor_msgs/CameraInfo.h> 14 #include <opencv2/highgui/highgui.hpp> 40 const std::string &topic_name,
42 const std::string &frame_id,
43 const std::string &camera_name);
52 void open(int32_t device_id);
60 void open(
const std::string &device_path);
81 void openFile(
const std::string &file_path);
104 inline const sensor_msgs::CameraInfo &
getInfo()
const 139 return cap_.set(cv::CAP_PROP_FRAME_WIDTH, width);
148 return cap_.set(cv::CAP_PROP_FRAME_HEIGHT, height);
227 #endif // CV_CAMERA_CAPTURE_H image_transport::ImageTransport it_
ROS image transport utility.
bool setHeight(int32_t height)
try capture image height
bool capture()
capture an image and store.
const cv::Mat & getCvImage() const
accessor of cv::Mat
void open()
Open default camera device.
ros::NodeHandle node_
node handle for advertise.
void publish()
Publish the image that is already captured by capture().
image_transport::CameraPublisher pub_
image publisher created by image_transport::ImageTransport.
void loadCameraInfo()
Load camera info from file.
captures by cv::VideoCapture and publishes to ROS topic.
int32_t buffer_size_
size of publisher buffer
bool setWidth(int32_t width)
try capture image width
camera_info_manager::CameraInfoManager info_manager_
camera info manager
namespace of this package
cv_bridge::CvImage bridge_
this stores last captured image.
void openFile(const std::string &file_path)
open video file instead of capture device.
std::string topic_name_
name of topic without namespace (usually "image_raw").
cv::VideoCapture cap_
capture device.
bool setPropertyFromParam(int property_id, const std::string ¶m_name)
set CV_PROP_*
ros::Duration capture_delay_
capture_delay param value
std::string frame_id_
header.frame_id for publishing images.
void rescaleCameraInfo(int width, int height)
rescale camera calibration to another resolution
Capture(ros::NodeHandle &node, const std::string &topic_name, int32_t buffer_size, const std::string &frame_id, const std::string &camera_name)
costruct with ros node and topic settings
const sensor_msgs::CameraInfo & getInfo() const
accessor of CameraInfo.
const sensor_msgs::ImagePtr getImageMsgPtr() const
accessor of ROS Image message.
sensor_msgs::CameraInfo info_
this stores last captured image info.
sensor_msgs::ImagePtr toImageMsg() const
bool rescale_camera_info_
rescale_camera_info param value