Apollo  6.0
Open source self driving car software
Public Member Functions | Public Attributes | List of all members
apollo::perception::lidar::LidarFrame Struct Reference

#include <lidar_frame.h>

Collaboration diagram for apollo::perception::lidar::LidarFrame:
Collaboration graph

Public Member Functions

void Reset ()
 
void FilterPointCloud (base::PointCloud< base::PointF > *filtered_cloud, const std::vector< uint32_t > &indices)
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::shared_ptr< base::AttributePointCloud< base::PointF > > cloud
 
std::shared_ptr< base::AttributePointCloud< base::PointD > > world_cloud
 
double timestamp = 0.0
 
Eigen::Affine3d lidar2world_pose = Eigen::Affine3d::Identity()
 
Eigen::Affine3d novatel2world_pose = Eigen::Affine3d::Identity()
 
std::shared_ptr< base::HdmapStructhdmap_struct = nullptr
 
std::vector< std::shared_ptr< base::Object > > segmented_objects
 
std::vector< std::shared_ptr< base::Object > > tracked_objects
 
base::PointIndices roi_indices
 
base::PointIndices non_ground_indices
 
base::PointIndices secondary_indices
 
base::SensorInfo sensor_info
 
std::string reserve
 

Member Function Documentation

◆ FilterPointCloud()

void apollo::perception::lidar::LidarFrame::FilterPointCloud ( base::PointCloud< base::PointF > *  filtered_cloud,
const std::vector< uint32_t > &  indices 
)
inline

◆ Reset()

void apollo::perception::lidar::LidarFrame::Reset ( )
inline

Member Data Documentation

◆ cloud

EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::shared_ptr<base::AttributePointCloud<base::PointF> > apollo::perception::lidar::LidarFrame::cloud

◆ hdmap_struct

std::shared_ptr<base::HdmapStruct> apollo::perception::lidar::LidarFrame::hdmap_struct = nullptr

◆ lidar2world_pose

Eigen::Affine3d apollo::perception::lidar::LidarFrame::lidar2world_pose = Eigen::Affine3d::Identity()

◆ non_ground_indices

base::PointIndices apollo::perception::lidar::LidarFrame::non_ground_indices

◆ novatel2world_pose

Eigen::Affine3d apollo::perception::lidar::LidarFrame::novatel2world_pose = Eigen::Affine3d::Identity()

◆ reserve

std::string apollo::perception::lidar::LidarFrame::reserve

◆ roi_indices

base::PointIndices apollo::perception::lidar::LidarFrame::roi_indices

◆ secondary_indices

base::PointIndices apollo::perception::lidar::LidarFrame::secondary_indices

◆ segmented_objects

std::vector<std::shared_ptr<base::Object> > apollo::perception::lidar::LidarFrame::segmented_objects

◆ sensor_info

base::SensorInfo apollo::perception::lidar::LidarFrame::sensor_info

◆ timestamp

double apollo::perception::lidar::LidarFrame::timestamp = 0.0

◆ tracked_objects

std::vector<std::shared_ptr<base::Object> > apollo::perception::lidar::LidarFrame::tracked_objects

◆ world_cloud

std::shared_ptr<base::AttributePointCloud<base::PointD> > apollo::perception::lidar::LidarFrame::world_cloud

The documentation for this struct was generated from the following file: