cv_connection.cpp 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176
  1. #include "cv_connection.hpp"
  2. #include <opencv2/opencv.hpp>
  3. #include <vector>
  4. #include <string>
  5. #include <thread>
  6. #include <cstdio>
  7. #include <iostream>
  8. #include <memory>
  9. #include <stdexcept>
  10. #include <array>
  11. #include <cv_bridge/cv_bridge.h>
  12. #include <opencv2/imgproc/imgproc.hpp>
  13. #include <opencv2/opencv.hpp>
  14. #include <sensor_msgs/Image.h>
  15. #include <sensor_msgs/image_encodings.h>
  16. #include <sensor_msgs/CompressedImage.h>
  17. #include <camera_info_manager/camera_info_manager.h>
  18. OpenCVConnector::OpenCVConnector(std::string topic_name,size_t csiPort,uint32_t cameraIdx,std::string calib_file_path , std::string camera_type_name, bool rectif_flag ) :
  19. it(nh), counter(0),
  20. csiPort(csiPort),
  21. cameraIdx(cameraIdx),
  22. info_manager_( ros::NodeHandle( topic_name ) , camera_type_name ),
  23. do_rectify(rectif_flag) {
  24. pub = it.advertise(topic_name + std::string("/image_raw"), 1);
  25. pub_comp = nh.advertise<sensor_msgs::CompressedImage>(topic_name + std::string("/image_raw") + std::string("/compressed"), 1);
  26. // Camera Info
  27. //info_manager_.setCameraName(topic_name);
  28. if ( info_manager_.validateURL(calib_file_path) ) {
  29. info_manager_.loadCameraInfo(calib_file_path);
  30. camera_info = info_manager_.getCameraInfo();
  31. }
  32. else {
  33. // URL not valid, use the old one
  34. std::cerr<<"Calibration URL not valid @ "+topic_name+" : "+calib_file_path<<std::endl;
  35. }
  36. pubCamInfo = nh.advertise<sensor_msgs::CameraInfo>(topic_name + std::string("/camera_info"), 1);
  37. }
  38. void OpenCVConnector::WriteToOpenCV(unsigned char* buffer, int width, int height) {
  39. sensor_msgs::ImagePtr ptr = boost::make_shared<sensor_msgs::Image>();
  40. sensor_msgs::Image &img_msg = *ptr; // >> message to be sent
  41. std_msgs::Header header; // empty header
  42. header.seq = counter; // user defined counter
  43. header.stamp = ros::Time::now(); // time
  44. // Formatting directly the message no OpenCV
  45. img_msg.header = header;
  46. img_msg.height = height;
  47. img_msg.width = width;
  48. img_msg.encoding = sensor_msgs::image_encodings::RGBA8;
  49. img_msg.step = width * 4; // 1 Byte per 4 Channels of the RGBA format
  50. size_t size = img_msg.step * height;
  51. img_msg.data.resize(size);
  52. memcpy((char *)( &img_msg.data[0] ) , buffer , size);
  53. pub.publish( ptr );
  54. camera_info = info_manager_.getCameraInfo();
  55. camera_info.header = header;
  56. camera_info.roi.do_rectify = do_rectify;
  57. pubCamInfo.publish( camera_info );
  58. //counter ++;
  59. }
  60. void OpenCVConnector::WriteToOpenCV_reduced(unsigned char* buffer, int width, int height,int downsample_width , int downsample_height) {
  61. cv::Mat mat_img(cv::Size(width, height), CV_8UC4, buffer);
  62. cv::resize(mat_img, mat_img, cv::Size(downsample_width ,downsample_height), 0, 0, CV_INTER_LINEAR); //
  63. cv::cvtColor( mat_img ,mat_img,cv::COLOR_RGBA2RGB); //=COLOR_BGRA2RGB
  64. std_msgs::Header header; // empty header
  65. header.seq = counter; // user defined counter
  66. header.stamp = ros::Time::now(); // time
  67. //sensor_msgs::ImagePtr img_msg = cv_bridge::CvImage(mat_img).toImageMsg();
  68. pub.publish( cv_bridge::CvImage(header, sensor_msgs::image_encodings::RGB8 , mat_img).toImageMsg() );
  69. camera_info = info_manager_.getCameraInfo();
  70. camera_info.header = header;
  71. camera_info.roi.do_rectify = do_rectify;
  72. pubCamInfo.publish( camera_info );
  73. //counter ++;
  74. }
  75. void OpenCVConnector::PublishJpeg(uint8_t* image_compressed, uint32_t image_compressed_size) {
  76. sensor_msgs::CompressedImage c_img_msg;
  77. c_img_msg.data.resize( image_compressed_size );
  78. memcpy(&c_img_msg.data[0], image_compressed, image_compressed_size);
  79. std_msgs::Header header; // empty header
  80. c_img_msg.header = header;
  81. //c_img_msg.header.seq = counter; // user defined counter
  82. c_img_msg.header.stamp = ros::Time::now(); // time
  83. c_img_msg.format = "jpeg";
  84. pub_comp.publish( c_img_msg );
  85. /* camera_info.roi.do_rectify=true;
  86. pubCamInfo.publish( camera_info ); */
  87. }
  88. /* void OpenCVConnector::WriteToRosPng(unsigned char* buffer, int width, int height) {
  89. //sensor_msgs::Image img_msg; // >> message to be sent
  90. sensor_msgs::CompressedImage c_img_msg; // std::vector< uint8_t >
  91. std_msgs::Header header; // empty header
  92. header.seq = counter; // user defined counter
  93. header.stamp = ros::Time::now(); // time
  94. c_img_msg.header = header;
  95. c_img_msg.format = "png";
  96. // Using: lodepng. See references:
  97. // https://raw.githubusercontent.com/lvandeve/lodepng/master/examples/example_encode.cpp
  98. // http://docs.ros.org/indigo/api/libfovis/html/lodepng_8h_source.html
  99. // https://lodev.org/lodepng/
  100. std::vector<unsigned char> png; // = c_img_msg.data
  101. unsigned bitdepth = 8;
  102. LodePNGColorType colortype = LCT_RGBA;
  103. unsigned error = lodepng::encode( c_img_msg.data, buffer, width, height, colortype , bitdepth );
  104. if(error) std::cout << "encoder error " << error << ": "<< lodepng_error_text(error) << std::endl;
  105. std::cout << " Publishing compressed image"<<std::endl;
  106. pub_comp.publish( c_img_msg );
  107. }
  108. */
  109. void OpenCVConnector::WriteToOpenCVJpeg(unsigned char* buffer, int width, int height) { // JPEG encoding with OpenCV
  110. cv::Mat mat_img(cv::Size(width, height), CV_8UC4 , buffer);
  111. cv::cvtColor( mat_img ,mat_img,cv::COLOR_BGRA2RGB); //=COLOR_BGRA2RGB
  112. sensor_msgs::CompressedImage c_img_msg;
  113. c_img_msg.data.resize( mat_img.rows*mat_img.cols );
  114. std::vector<int> params = { cv::IMWRITE_JPEG_QUALITY, 95 };
  115. cv::imencode(".jpg", mat_img, c_img_msg.data, params );
  116. std_msgs::Header header; // empty header
  117. c_img_msg.header = header;
  118. //c_img_msg.header.seq = counter; // user defined counter
  119. c_img_msg.header.stamp = ros::Time::now(); // time
  120. c_img_msg.format = "jpeg";
  121. pub_comp.publish( c_img_msg );
  122. }