34 #ifndef MULTISENSE_ROS_GROUND_SURFACE_UTILITIES_H 35 #define MULTISENSE_ROS_GROUND_SURFACE_UTILITIES_H 40 #include <Eigen/Geometry> 41 #include <Eigen/StdVector> 62 const std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f>> &input,
63 const std::string &frame_id);
100 const Eigen::Matrix<float, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> &controlGrid,
102 const double pointcloudMaxRange,
103 const float* xzCellOrigin,
104 const float* xzCellSize,
105 const float* minMaxAzimuthAngle,
106 const float* extrinsics,
107 const float* quadraticParams,
108 const float baseline);
double max_z_m
The max range (along the z dimension / optical axis) to draw the B-spline model.
double max_x_m
The max width (along the x dimension) to draw the B-spline model.
Struct containing parameters for drawing a pointcloud representation of a B-Spline model...
sensor_msgs::PointCloud2 eigenToPointcloud(const std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f >> &input, const std::string &frame_id)
Convert an eigen representation of a pointcloud to a ROS sensor_msgs::PointCloud2 format...
Eigen::Matrix< uint8_t, 3, 1 > groundSurfaceClassToPixelColor(const uint8_t value)
Look up table to convert a ground surface class value into into a color for visualization (out-of-bou...
double min_x_m
The min width (along the x dimension) to draw the B-spline model.
double resolution
The resolution to sample the B-Spline model for drawing.
double min_z_m
The min range (along the z dimension / optical axis) to draw the B-spline model.
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > convertSplineToPointcloud(const Eigen::Matrix< float, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > &controlGrid, const SplineDrawParameters &splineDrawParams, const double pointcloudMaxRange, const float *xzCellOrigin, const float *xzCellSize, const float *minMaxAzimuthAngle, const float *extrinsics, const float *quadraticParams, const float baseline)
Generate a pointcloud representation of a b-spline ground surface model for visualization.