Skip to content
体验新版
项目
组织
正在加载...
登录
切换导航
打开侧边栏
Pinoxchio
apollo
提交
60c21539
A
apollo
项目概览
Pinoxchio
/
apollo
与 Fork 源项目一致
从无法访问的项目Fork
通知
2
Star
0
Fork
0
代码
文件
提交
分支
Tags
贡献者
分支图
Diff
Issue
0
列表
看板
标记
里程碑
合并请求
0
Wiki
0
Wiki
分析
仓库
DevOps
项目成员
Pages
A
apollo
项目概览
项目概览
详情
发布
仓库
仓库
文件
提交
分支
标签
贡献者
分支图
比较
Issue
0
Issue
0
列表
看板
标记
里程碑
合并请求
0
合并请求
0
Pages
分析
分析
仓库分析
DevOps
Wiki
0
Wiki
成员
成员
收起侧边栏
关闭侧边栏
动态
分支图
创建新Issue
提交
Issue看板
体验新版 GitCode,发现更多精彩内容 >>
提交
60c21539
编写于
7月 02, 2020
作者:
S
storypku
提交者:
Liu Jiaming
7月 02, 2020
浏览文件
操作
浏览文件
下载
电子邮件补丁
差异文件
Build: fix deprecated warnings on localization
上级
3fa087a7
变更
2
隐藏空白更改
内联
并排
Showing
2 changed file
with
14 addition
and
12 deletion
+14
-12
modules/localization/msf/common/io/pcl_point_types.h
modules/localization/msf/common/io/pcl_point_types.h
+7
-6
modules/localization/msf/common/util/voxel_grid_covariance_hdmap.h
...ocalization/msf/common/util/voxel_grid_covariance_hdmap.h
+7
-6
未找到文件。
modules/localization/msf/common/io/pcl_point_types.h
浏览文件 @
60c21539
...
...
@@ -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
))
modules/localization/msf/common/util/voxel_grid_covariance_hdmap.h
浏览文件 @
60c21539
...
...
@@ -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.
先完成此消息的编辑!
取消
想要评论请
注册
或
登录