|
Apollo
v5.5.0
Open source self driving car software
|
#include <limits>#include <memory>#include <utility>#include <vector>#include "Eigen/Dense"#include "modules/perception/base/point.h"#include "modules/perception/base/point_cloud.h"
Go to the source code of this file.
Classes | |
| struct | apollo::perception::base::BoundingCube |
Namespaces | |
| apollo | |
| apollo::perception | |
| apollo::perception::base | |
Functions | |
| bool | apollo::perception::base::GetPointCloudMinareaBbox (const base::PointFCloud &pc, BoundingCube *box, const int &min_num_points=5, const bool &verbose=false) |
| void | apollo::perception::base::CloudDemean (base::PointFCloudPtr cloud) |
| void | apollo::perception::base::GetPointCloudCentroid (base::PointFCloudConstPtr cloud, PointF *centroid) |
| double | apollo::perception::base::OrientCloud (const PointFCloud &pc, PointFCloud *pc_out, bool demean) |
1.8.13