transformation.h 1.1 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758
  1. #ifndef TRANSFORMATION_H
  2. #define TRANSFORMATION_H
  3. #include "eigen3/Eigen/Dense"
  4. //#include "objectarray.pb.h"
  5. #include "radarobjectarray.pb.h"
  6. #include "fusionobjectarray.pb.h"
  7. #include <opencv2/opencv.hpp>
  8. struct Point{
  9. double x;
  10. double y;
  11. double z;
  12. double i; //强度信息
  13. double r;
  14. double g;
  15. double b;
  16. };
  17. struct Vel_Struct{
  18. double vx;
  19. double vy;
  20. };
  21. struct match_index
  22. {
  23. int nlidar;
  24. int nradar;
  25. };
  26. namespace iv {
  27. namespace fusion {
  28. class Transformation{
  29. public:
  30. Transformation(){};
  31. ~Transformation(){};
  32. static Point RadarToCamera(Point radarInfo);
  33. // static Point CameraToWorld(Point CameraInfo);
  34. static void RadarPross(iv::radar::radarobjectarray& radar_object);
  35. static float ComputelonDistance(double x, double y);
  36. static float ComputeRadarSpeed(double vx, double vy);
  37. static Vel_Struct lidarVelTra(float yaw, float LineVel);
  38. static Eigen::Matrix<float,3,1> RadarToLidar(Eigen::Matrix<float,3,1> radar_in_radar);
  39. static Eigen::Matrix<float,3,1> LidarToRadar(Eigen::Matrix<float,3,1> lidar_in_lidar);
  40. };
  41. }
  42. }
  43. #endif // TRANSFORMATION_H