Skip to content
Projects
Groups
Snippets
Help
Loading...
Sign in / Register
Toggle navigation
Y
yiqi-frame-mapping
Project
Project
Details
Activity
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Board
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Packages
Packages
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
wangdawei
yiqi-frame-mapping
Commits
0bf6b9f9
Commit
0bf6b9f9
authored
Apr 01, 2024
by
xiebojie
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
merge files from pcl-1 online code
parent
01ea89a7
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
78 additions
and
49 deletions
+78
-49
libs.zip
libs.zip
+0
-0
pcl_point_type.h
libs/lidar/pcl_point_type.h
+63
-43
pcd_reader.cpp
libs/reader/pcd_reader.cpp
+15
-6
maptask.cpp
libs/task/maptask.cpp
+0
-0
trajectory.cpp
libs/trajectory/trajectory.cpp
+0
-0
No files found.
libs.zip
0 → 100644
View file @
0bf6b9f9
File added
libs/lidar/pcl_point_type.h
View file @
0bf6b9f9
...
...
@@ -3,26 +3,27 @@
#ifndef PCL_POINT_TYPE_H
#define PCL_POINT_TYPE_H
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
namespace
pcl
{
struct
PointInternal
{
PCL_ADD_POINT4D
PCL_ADD_RGB
float
intensity
;
float
ring
;
float
label
=
0
;
float
distance
;
double
timestamp
;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// make sure our new allocators are aligned
PCL_ADD_POINT4D
PCL_ADD_RGB
float
intensity
;
float
ring
;
float
label
=
0
;
float
distance
;
double
timestamp
;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// make sure our new allocators are aligned
}
EIGEN_ALIGN16
;
}
//
end namespace pcl
}
//
end namespace pcl
POINT_CLOUD_REGISTER_POINT_STRUCT
(
pcl
::
PointInternal
,
(
float
,
x
,
x
)(
float
,
y
,
y
)(
float
,
z
,
z
)(
float
,
rgb
,
rgb
)
(
float
,
intensity
,
intensity
)(
float
,
ring
,
ring
)(
float
,
label
,
label
)
(
float
,
distance
,
distance
)(
double
,
timestamp
,
timestamp
))
pcl
::
PointInternal
,
(
float
,
x
,
x
)(
float
,
y
,
y
)(
float
,
z
,
z
)(
float
,
rgb
,
rgb
)(
float
,
intensity
,
intensity
)(
float
,
ring
,
ring
)(
float
,
label
,
label
)(
float
,
distance
,
distance
)(
double
,
timestamp
,
timestamp
))
typedef
pcl
::
PointInternal
Point
;
typedef
pcl
::
PointCloud
<
Point
>
PointCloud
;
...
...
@@ -32,19 +33,19 @@ typedef pcl::PointCloud<Point> PointCloud;
///
namespace
pcl
{
struct
PointRos
{
PCL_ADD_POINT4D
float
intensity
;
float
ring
;
float
label
=
0
;
float
timestamp
;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// make sure our new allocators are aligned
PCL_ADD_POINT4D
float
intensity
;
float
ring
;
float
label
=
0
;
float
timestamp
;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// make sure our new allocators are aligned
}
EIGEN_ALIGN32
;
}
//
end namespace pcl
}
//
end namespace pcl
POINT_CLOUD_REGISTER_POINT_STRUCT
(
pcl
::
PointRos
,
(
float
,
x
,
x
)(
float
,
y
,
y
)(
float
,
z
,
z
)
(
float
,
intensity
,
intensity
)(
float
,
ring
,
ring
)(
float
,
label
,
label
)
(
float
,
timestamp
,
timestamp
))
pcl
::
PointRos
,
(
float
,
x
,
x
)(
float
,
y
,
y
)(
float
,
z
,
z
)(
float
,
intensity
,
intensity
)(
float
,
ring
,
ring
)(
float
,
label
,
label
)
(
float
,
timestamp
,
timestamp
))
typedef
pcl
::
PointRos
PointRos
;
typedef
pcl
::
PointCloud
<
PointRos
>
PointCloudRos
;
...
...
@@ -54,18 +55,19 @@ typedef pcl::PointCloud<PointRos> PointCloudRos;
///
namespace
pcl
{
struct
PointExport
{
PCL_ADD_POINT4D
PCL_ADD_RGB
float
intensity
=
0
;
float
label
=
0
;
float
info
=
0
;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// make sure our new allocators are aligned
PCL_ADD_POINT4D
PCL_ADD_RGB
float
intensity
=
0
;
float
label
=
0
;
float
info
=
0
;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// make sure our new allocators are aligned
}
EIGEN_ALIGN16
;
}
//
end namespace pcl
}
//
end namespace pcl
POINT_CLOUD_REGISTER_POINT_STRUCT
(
pcl
::
PointExport
,
(
float
,
x
,
x
)(
float
,
y
,
y
)(
float
,
z
,
z
)(
float
,
rgb
,
rgb
)
(
float
,
intensity
,
intensity
)(
float
,
label
,
label
)(
float
,
info
,
info
))
pcl
::
PointExport
,
(
float
,
x
,
x
)(
float
,
y
,
y
)(
float
,
z
,
z
)(
float
,
rgb
,
rgb
)(
float
,
intensity
,
intensity
)(
float
,
label
,
label
)(
float
,
info
,
info
))
typedef
pcl
::
PointExport
PointExport
;
typedef
pcl
::
PointCloud
<
PointExport
>
PointCloudExport
;
...
...
@@ -73,21 +75,39 @@ typedef pcl::PointCloud<PointExport> PointCloudExport;
/////////////////////////////////////////////////////////////
namespace
pcl
{
struct
PointTemp1
{
PCL_ADD_POINT4D
float
intensity
;
float
ring
;
float
label
=
0
;
float
time
;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// make sure our new allocators are aligned
PCL_ADD_POINT4D
float
intensity
;
float
ring
;
float
label
=
0
;
float
time
;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// make sure our new allocators are aligned
}
EIGEN_ALIGN16
;
}
//
end namespace pcl
}
//
end namespace pcl
POINT_CLOUD_REGISTER_POINT_STRUCT
(
pcl
::
PointTemp1
,
(
float
,
x
,
x
)(
float
,
y
,
y
)(
float
,
z
,
z
)
(
float
,
intensity
,
intensity
)(
float
,
ring
,
ring
)(
float
,
label
,
label
)
(
float
,
time
,
time
))
pcl
::
PointTemp1
,
(
float
,
x
,
x
)(
float
,
y
,
y
)(
float
,
z
,
z
)(
float
,
intensity
,
intensity
)(
float
,
ring
,
ring
)(
float
,
label
,
label
)
(
float
,
time
,
time
))
typedef
pcl
::
PointTemp1
PointTemp1
;
/////////////////////////////////////////////////////////////
namespace
pcl
{
struct
PointI
{
PCL_ADD_POINT4D
float
intensity
;
float
stamp_offset
;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
// make sure our new allocators are aligned
}
EIGEN_ALIGN16
;
}
// end namespace pcl
POINT_CLOUD_REGISTER_POINT_STRUCT
(
pcl
::
PointI
,
(
float
,
x
,
x
)(
float
,
y
,
y
)(
float
,
z
,
z
)(
float
,
intensity
,
intensity
)(
float
,
stamp_offset
,
stamp_offset
))
typedef
pcl
::
PointI
PointI
;
typedef
pcl
::
PointCloud
<
PointI
>
PointCloudI
;
#endif // PCL_POINT_TYPE_H
#endif
// PCL_POINT_TYPE_H
libs/reader/pcd_reader.cpp
View file @
0bf6b9f9
...
...
@@ -49,7 +49,8 @@ bool PcdReader::loadFile() {
bool
PcdReader
::
getNextFrame
(
PointCloud
*&
frame
)
{
if
(
pcdIndex_
>=
pcdPathVec_
.
size
())
return
false
;
bool
suceess
=
false
;
PointCloud
tempFrame
;
PointCloudI
tempFrame
;
double
time
;
while
(
!
suceess
)
{
string
pcdPath
=
pcdPathVec_
.
at
(
pcdIndex_
);
pcdIndex_
++
;
...
...
@@ -60,17 +61,25 @@ bool PcdReader::getNextFrame(PointCloud*& frame) {
if
(
iter
==
frameTimeMap_
.
end
())
{
continue
;
}
double
time
=
iter
->
second
;
time
=
iter
->
second
;
int8_t
ret
=
checkTime
(
time
,
durations_
);
if
(
ret
!=
1
)
{
continue
;
}
for
(
auto
&
point
:
tempFrame
)
{
point
.
timestamp
=
time
;
}
// LOG(INFO) << setprecision(15) << "frameId: " << frameId
// << " time: " << time;
suceess
=
true
;
}
frame
=
new
PointCloud
;
*
frame
=
tempFrame
;
for
(
auto
&
pointI
:
tempFrame
)
{
Point
point
;
point
.
x
=
pointI
.
x
;
point
.
y
=
pointI
.
y
;
point
.
z
=
pointI
.
z
;
point
.
timestamp
=
time
+
pointI
.
stamp_offset
*
0.001
;
point
.
intensity
=
pointI
.
intensity
;
point
.
distance
=
sqrt
(
pow
(
point
.
x
,
2
)
+
pow
(
point
.
y
,
2
)
+
pow
(
point
.
z
,
2
));
frame
->
push_back
(
point
);
}
return
true
;
}
libs/task/maptask.cpp
View file @
0bf6b9f9
This diff is collapsed.
Click to expand it.
libs/trajectory/trajectory.cpp
View file @
0bf6b9f9
This diff is collapsed.
Click to expand it.
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment