36 #ifndef CV_BRIDGE_CV_BRIDGE_H
37 #define CV_BRIDGE_CV_BRIDGE_H
39 #include <sensor_msgs/Image.h>
40 #include <sensor_msgs/CompressedImage.h>
43 #include <opencv2/core/core.hpp>
44 #include <opencv2/imgproc/imgproc.hpp>
45 #include <opencv2/imgproc/types_c.h>
50 class Exception :
public std::runtime_error
53 Exception(
const std::string& description) : std::runtime_error(description) {}
92 const cv::Mat&
image = cv::Mat())
163 const std::string& encoding = std::string());
166 const std::string& encoding = std::string());
188 const std::string& encoding = std::string());
191 const std::string& encoding = std::string());
214 const std::string& encoding = std::string());
242 const std::string& encoding = std::string());
248 const std::string& encoding);
297 const std::string& encoding = std::string(),
298 const CvtColorForDisplayOptions options = CvtColorForDisplayOptions());
305 int getCvType(
const std::string& encoding);
321 namespace message_traits {
323 template<>
struct MD5Sum<
cv_bridge::CvImage>
328 static const uint64_t static_value1 = MD5Sum<sensor_msgs::Image>::static_value1;
329 static const uint64_t static_value2 = MD5Sum<sensor_msgs::Image>::static_value2;
332 ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value1 == 0x060021388200f6f0ULL);
333 ROS_STATIC_ASSERT(MD5Sum<sensor_msgs::Image>::static_value2 == 0xf447d0fcd9c64743ULL);
336 template<>
struct DataType<
cv_bridge::CvImage>
342 template<>
struct Definition<
cv_bridge::CvImage>
348 template<>
struct HasHeader<
cv_bridge::CvImage> : TrueType {};
352 namespace serialization {
354 template<>
struct Serializer<
cv_bridge::CvImage>
358 template<
typename Stream>
362 stream.next((uint32_t)m.
image.rows);
363 stream.next((uint32_t)m.
image.cols);
365 uint8_t is_bigendian = 0;
366 stream.next(is_bigendian);
367 stream.next((uint32_t)m.
image.step);
369 stream.next((uint32_t)data_size);
371 memcpy(stream.advance(data_size), m.
image.data, data_size);
374 template<
typename Stream>
378 uint32_t height, width;
382 uint8_t is_bigendian;
383 stream.next(is_bigendian);
384 uint32_t step, data_size;
386 stream.next(data_size);
389 cv::Mat tmp((
int)height, (
int)width, type, stream.advance(data_size), (
size_t)step);
402 namespace message_operations {
404 template<>
struct Printer<
cv_bridge::CvImage>
406 template<
typename Stream>
419 inline std::ostream&
operator<<(std::ostream& s,
const CvImage& m)