提交 60c21539 编写于 作者: S storypku 提交者: Liu Jiaming

Build: fix deprecated warnings on localization

上级 3fa087a7
......@@ -73,22 +73,23 @@ struct PointXYZITd {
POINT_CLOUD_REGISTER_POINT_STRUCT(
apollo::localization::msf::velodyne::PointXYZIT,
(float, x, x)(float, y, y)(float, z, z)(uint8_t, intensity,
(float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity,
intensity)(double, timestamp,
timestamp))
POINT_CLOUD_REGISTER_POINT_STRUCT(
apollo::localization::msf::velodyne::PointXYZIRT,
(float, x, x)(float, y, y)(float, z, z)(uint8_t, intensity, intensity)(
uint8_t, ring, ring)(double, timestamp, timestamp))
(float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)(
std::uint8_t, ring, ring)(double, timestamp, timestamp))
POINT_CLOUD_REGISTER_POINT_STRUCT(
apollo::localization::msf::velodyne::PointXYZITd,
(double, x, x)(double, y, y)(double, z, z)(uint8_t, intensity,
(double, x, x)(double, y, y)(double, z, z)(std::uint8_t, intensity,
intensity)(double, timestamp,
timestamp))
POINT_CLOUD_REGISTER_POINT_STRUCT(
apollo::localization::msf::velodyne::PointXYZIRTd,
(double, x, x)(double, y, y)(double, z, z)(uint8_t, intensity, intensity)(
uint8_t, ring, ring)(double, timestamp, timestamp))
(double, x, x)(double, y, y)(double, z, z)(
std::uint8_t, intensity, intensity)(std::uint8_t, ring,
ring)(double, timestamp, timestamp))
......@@ -56,6 +56,7 @@
#pragma once
#include <cmath> // for std::isfinite
#include <limits>
#include <map>
#include <vector>
......@@ -369,9 +370,9 @@ class VoxelGridCovariance : public pcl::VoxelGrid<PointT> {
for (size_t cp = 0; cp < input_->points.size(); ++cp) {
if (!input_->is_dense) {
// Check if the point is invalid
if (!pcl_isfinite(input_->points[cp].x) ||
!pcl_isfinite(input_->points[cp].y) ||
!pcl_isfinite(input_->points[cp].z)) {
if (!std::isfinite(input_->points[cp].x) ||
!std::isfinite(input_->points[cp].y) ||
!std::isfinite(input_->points[cp].z)) {
continue;
}
}
......@@ -455,9 +456,9 @@ class VoxelGridCovariance : public pcl::VoxelGrid<PointT> {
for (size_t cp = 0; cp < input_->points.size(); ++cp) {
if (!input_->is_dense) {
// Check if the point is invalid
if (!pcl_isfinite(input_->points[cp].x) ||
!pcl_isfinite(input_->points[cp].y) ||
!pcl_isfinite(input_->points[cp].z)) {
if (!std::isfinite(input_->points[cp].x) ||
!std::isfinite(input_->points[cp].y) ||
!std::isfinite(input_->points[cp].z)) {
continue;
}
}
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册