Classes | Functions
ground_surface_utilities Namespace Reference

Classes

struct  SplineDrawParameters
 Struct containing parameters for drawing a pointcloud representation of a B-Spline model. More...
 

Functions

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. More...
 
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. More...
 
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-bounds -> blue, obstacle -> red, free-space -> green) More...
 

Function Documentation

◆ convertSplineToPointcloud()

std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > ground_surface_utilities::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.

Parameters
controlGridControl points grid used to determine interpolated spline values
splineDrawParamsParameters for drawing a pointcloud representation of a B-Spline model
pointcloudMaxRangeMax range to draw spline model to from camera frame
xzCellOriginX,Z cell origin of the spline fitting algorithm in meters
xzCellSizeSize of the X,Z plane containing the spline fit in meters
minMaxAzimuthAngleMin and max limit to the spline fitting angle in radians, for visualization purposes
extrinsicsExtrinsic transform for stereo pointcloud used during B-Spline modelling
quadraticParamsparameters for the quadratic data transformation prior to spline fitting
baselineStereo camera baseline in meters
Returns
Eigen representation of spline pointcloud at regularly sample x/z intervals

Definition at line 200 of file ground_surface_utilities.cpp.

◆ eigenToPointcloud()

sensor_msgs::PointCloud2 ground_surface_utilities::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.

Parameters
inputPointcloud to convert between eigen and sensor_msg format
frame_idBase frame ID for resulting sensor_msg
Returns
Pointcloud in sensor_msg format

Definition at line 181 of file ground_surface_utilities.cpp.

◆ groundSurfaceClassToPixelColor()

Eigen::Matrix< uint8_t, 3, 1 > ground_surface_utilities::groundSurfaceClassToPixelColor ( const uint8_t  value)

Look up table to convert a ground surface class value into into a color for visualization (out-of-bounds -> blue, obstacle -> red, free-space -> green)

Parameters
valueRaw pixel value resulting from ground surface modeling operation on camera
Returns
RGB value corresponding to the class of the value argument

Definition at line 168 of file ground_surface_utilities.cpp.



multisense_ros
Author(s):
autogenerated on Thu Apr 17 2025 02:49:25