35 #include <opencv2/highgui/highgui.hpp>
38 #include <sensor_msgs/Image.h>
42 #include <boost/thread.hpp>
43 #include <boost/format.hpp>
62 CvVideoWriter* video_writer;
72 std::string format_string;
73 local_nh.
param(
"filename_format", format_string, std::string(
"frame%04i.jpg"));
92 void image_cb(
const sensor_msgs::ImageConstPtr& msg)
101 if (msg->encoding.find(
"bayer") != std::string::npos)
102 boost::const_pointer_cast<sensor_msgs::Image>(msg)->encoding =
"mono8";
110 ROS_ERROR(
"Unable to convert %s image to bgr8", msg->encoding.c_str());
118 if (!image.empty()) {
124 if (
filename.length() >= 4 && file_extension ==
".raw")
126 std::ofstream raw_file;
128 if (raw_file.is_open() ==
false)
134 raw_file.write((
char*)(msg->data.data()), msg->data.size());
140 if (cv::imwrite(
filename, image) ==
false)
148 video_writer = cvCreateVideoWriter(
"video.avi", CV_FOURCC(
'M',
'J',
'P',
'G'),
152 cvWriteFrame(video_writer, image);
158 ROS_WARN(
"Couldn't save image, no data!");
164 int main(
int argc,
char **argv)
169 ROS_WARN(
"extract_images: image has not been remapped! Typical command-line usage:\n"
170 "\t$ ./extract_images image:=<image topic> [transport]");