vscan2image.cpp 3.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118
  1. /*
  2. * Copyright 2015-2019 Autoware Foundation. All rights reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. */
  16. #include <ros/ros.h>
  17. #include <sensor_msgs/PointCloud2.h>
  18. #include <sensor_msgs/CameraInfo.h>
  19. #include "autoware_msgs/PointsImage.h"
  20. #include "autoware_msgs/ProjectionMatrix.h"
  21. //#include "autoware_msgs/CameraExtrinsic.h"
  22. #include <include/points_image/points_image.hpp>
  23. #define CAMERAEXTRINSICMAT "CameraExtrinsicMat"
  24. #define CAMERAMAT "CameraMat"
  25. #define DISTCOEFF "DistCoeff"
  26. #define IMAGESIZE "ImageSize"
  27. static cv::Mat cameraExtrinsicMat;
  28. static cv::Mat cameraMat;
  29. static cv::Mat distCoeff;
  30. static cv::Size imageSize;
  31. static ros::Publisher pub;
  32. static void projection_callback(const autoware_msgs::ProjectionMatrix& msg)
  33. {
  34. cameraExtrinsicMat = cv::Mat(4, 4, CV_64F);
  35. for (int row = 0; row < 4; row++)
  36. {
  37. for (int col = 0; col < 4; col++)
  38. {
  39. cameraExtrinsicMat.at<double>(row, col) = msg.projection_matrix[row * 4 + col];
  40. }
  41. }
  42. }
  43. static void intrinsic_callback(const sensor_msgs::CameraInfo& msg)
  44. {
  45. imageSize.height = msg.height;
  46. imageSize.width = msg.width;
  47. cameraMat = cv::Mat(3, 3, CV_64F);
  48. for (int row = 0; row < 3; row++)
  49. {
  50. for (int col = 0; col < 3; col++)
  51. {
  52. cameraMat.at<double>(row, col) = msg.K[row * 3 + col];
  53. }
  54. }
  55. distCoeff = cv::Mat(1, 5, CV_64F);
  56. for (int col = 0; col < 5; col++)
  57. {
  58. distCoeff.at<double>(col) = msg.D[col];
  59. }
  60. }
  61. static void callback(const sensor_msgs::PointCloud2ConstPtr& msg)
  62. {
  63. if (cameraExtrinsicMat.empty() || cameraMat.empty() || distCoeff.empty() || imageSize.height == 0 ||
  64. imageSize.width == 0)
  65. {
  66. ROS_INFO("Looks like /camera/camera_info or /projection_matrix are not being published.. Please check that both "
  67. "are running..");
  68. return;
  69. }
  70. autoware_msgs::PointsImage pub_msg = pointcloud2_to_image(msg, cameraExtrinsicMat, cameraMat, distCoeff, imageSize);
  71. pub.publish(pub_msg);
  72. }
  73. int main(int argc, char* argv[])
  74. {
  75. ros::init(argc, argv, "vscan2image");
  76. ros::NodeHandle n;
  77. ros::NodeHandle private_nh("~");
  78. std::string cameraInfo_topic_name;
  79. private_nh.param<std::string>("camera_info_topic", cameraInfo_topic_name, "/camera/camera_info");
  80. std::string projectionMat_topic_name;
  81. private_nh.param<std::string>("projection_matrix_topic", projectionMat_topic_name, "/projection_matrix");
  82. /*if(argc < 2){
  83. std::cout<<"Need calibration filename as the first parameter.";
  84. return 0;
  85. }
  86. cv::FileStorage fs(argv[1], cv::FileStorage::READ);
  87. if(!fs.isOpened()){
  88. std::cout<<"Invalid calibration filename.";
  89. return 0;
  90. }
  91. fs[CAMERAEXTRINSICMAT] >> cameraExtrinsicMat;
  92. fs[CAMERAMAT] >> cameraMat;
  93. fs[DISTCOEFF] >> distCoeff;
  94. fs[IMAGESIZE] >> imageSize;*/
  95. // imageSize.width = IMAGE_WIDTH;
  96. // imageSize.height = IMAGE_HEIGHT;
  97. pub = n.advertise<autoware_msgs::PointsImage>("vscan_image", 10);
  98. ros::Subscriber sub = n.subscribe("vscan_points", 1, callback);
  99. ros::Subscriber projection = n.subscribe(projectionMat_topic_name, 1, projection_callback);
  100. ros::Subscriber intrinsic = n.subscribe(cameraInfo_topic_name, 1, intrinsic_callback);
  101. ros::spin();
  102. return 0;
  103. }