12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758 |
- #ifndef TRANSFORMATION_H
- #define TRANSFORMATION_H
- #include "eigen3/Eigen/Dense"
- //#include "objectarray.pb.h"
- #include "radarobjectarray.pb.h"
- #include "fusionobjectarray.pb.h"
- #include <opencv2/opencv.hpp>
- struct Point{
- double x;
- double y;
- double z;
- double i; //强度信息
- double r;
- double g;
- double b;
- };
- struct Vel_Struct{
- double vx;
- double vy;
- };
- struct match_index
- {
- int nlidar;
- int nradar;
- };
- namespace iv {
- namespace fusion {
- class Transformation{
- public:
- Transformation(){};
- ~Transformation(){};
- static Point RadarToCamera(Point radarInfo);
- // static Point CameraToWorld(Point CameraInfo);
- static void RadarPross(iv::radar::radarobjectarray& radar_object);
- static float ComputelonDistance(double x, double y);
- static float ComputeRadarSpeed(double vx, double vy);
- static Vel_Struct lidarVelTra(float yaw, float LineVel);
- static Eigen::Matrix<float,3,1> RadarToLidar(Eigen::Matrix<float,3,1> radar_in_radar);
- static Eigen::Matrix<float,3,1> LidarToRadar(Eigen::Matrix<float,3,1> lidar_in_lidar);
- };
- }
- }
- #endif // TRANSFORMATION_H
|