19 #include "cartographer/sensor/proto/sensor.pb.h" 28 result.reserve(point_cloud.size());
29 for (
const Eigen::Vector3f& point : point_cloud) {
30 result.emplace_back(transform * point);
38 result.reserve(point_cloud.size());
39 for (
const Eigen::Vector4f& point : point_cloud) {
40 Eigen::Vector4f result_point;
41 result_point.head<3>() = transform * point.head<3>();
42 result_point[3] = point[3];
43 result.emplace_back(result_point);
51 for (
const Eigen::Vector3f& point : point_cloud) {
52 if (min_z <= point.z() && point.z() <=
max_z) {
53 cropped_point_cloud.push_back(point);
56 return cropped_point_cloud;
62 for (
const Eigen::Vector4f& point : point_cloud) {
63 if (min_z <= point.z() && point.z() <=
max_z) {
64 cropped_point_cloud.push_back(point);
67 return cropped_point_cloud;
PointCloud TransformPointCloud(const PointCloud &point_cloud, const transform::Rigid3f &transform)
TimedPointCloud TransformTimedPointCloud(const TimedPointCloud &point_cloud, const transform::Rigid3f &transform)
PointCloud CropPointCloud(const PointCloud &point_cloud, const float min_z, const float max_z)
std::vector< Eigen::Vector3f > PointCloud
std::vector< Eigen::Vector4f > TimedPointCloud
TimedPointCloud CropTimedPointCloud(const TimedPointCloud &point_cloud, const float min_z, const float max_z)