| 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... | |
| 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.
| controlGrid | Control points grid used to determine interpolated spline values | 
| splineDrawParams | Parameters for drawing a pointcloud representation of a B-Spline model | 
| pointcloudMaxRange | Max range to draw spline model to from camera frame | 
| xzCellOrigin | X,Z cell origin of the spline fitting algorithm in meters | 
| xzCellSize | Size of the X,Z plane containing the spline fit in meters | 
| minMaxAzimuthAngle | Min and max limit to the spline fitting angle in radians, for visualization purposes | 
| extrinsics | Extrinsic transform for stereo pointcloud used during B-Spline modelling | 
| quadraticParams | parameters for the quadratic data transformation prior to spline fitting | 
| baseline | Stereo camera baseline in meters | 
Definition at line 206 of file ground_surface_utilities.cpp.
| 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.
| input | Pointcloud to convert between eigen and sensor_msg format | 
| frame_id | Base frame ID for resulting sensor_msg | 
Definition at line 180 of file ground_surface_utilities.cpp.
| 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)
| value | Raw pixel value resulting from ground surface modeling operation on camera | 
Definition at line 167 of file ground_surface_utilities.cpp.