Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
L
laser
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Deploy
Releases
Model registry
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
mobile_robotics
wolf_projects
wolf_lib
plugins
laser
Commits
61b37ba2
Commit
61b37ba2
authored
2 years ago
by
Víctor Sainz Ubide
Browse files
Options
Downloads
Patches
Plain Diff
pointer cast changed from std::make_shared to pcl::make_shared
parent
0f68e59b
No related branches found
Branches containing commit
No related tags found
1 merge request
!41
Draft: Resolve "New branch laser 3d"
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
src/processor/processor_odom_icp_3d.cpp
+3
-3
3 additions, 3 deletions
src/processor/processor_odom_icp_3d.cpp
test/gtest_laser3d_tools.cpp
+2
-2
2 additions, 2 deletions
test/gtest_laser3d_tools.cpp
with
5 additions
and
5 deletions
src/processor/processor_odom_icp_3d.cpp
+
3
−
3
View file @
61b37ba2
...
@@ -48,17 +48,17 @@ ProcessorOdomIcp3d::ProcessorOdomIcp3d(ParamsProcessorOdomIcp3dPtr _params)
...
@@ -48,17 +48,17 @@ ProcessorOdomIcp3d::ProcessorOdomIcp3d(ParamsProcessorOdomIcp3dPtr _params)
if
(
std
::
strcmp
(
_params
->
icp_algorithm
.
c_str
(),
"icp_nl"
)
==
0
)
if
(
std
::
strcmp
(
_params
->
icp_algorithm
.
c_str
(),
"icp_nl"
)
==
0
)
{
{
WOLF_INFO
(
"ProcessorOdomIcp3d: Using icp_nl"
);
WOLF_INFO
(
"ProcessorOdomIcp3d: Using icp_nl"
);
registration_solver_
=
std
::
make_shared
<
pcl
::
IterativeClosestPointNonLinear
<
pcl
::
PointXYZ
,
pcl
::
PointXYZ
>>
();
registration_solver_
=
pcl
::
make_shared
<
pcl
::
IterativeClosestPointNonLinear
<
pcl
::
PointXYZ
,
pcl
::
PointXYZ
>>
();
}
}
else
if
(
std
::
strcmp
(
_params
->
icp_algorithm
.
c_str
(),
"icp"
)
==
0
)
else
if
(
std
::
strcmp
(
_params
->
icp_algorithm
.
c_str
(),
"icp"
)
==
0
)
{
{
WOLF_INFO
(
"ProcessorOdomIcp3d: Using icp"
);
WOLF_INFO
(
"ProcessorOdomIcp3d: Using icp"
);
registration_solver_
=
std
::
make_shared
<
pcl
::
IterativeClosestPoint
<
pcl
::
PointXYZ
,
pcl
::
PointXYZ
>>
();
registration_solver_
=
pcl
::
make_shared
<
pcl
::
IterativeClosestPoint
<
pcl
::
PointXYZ
,
pcl
::
PointXYZ
>>
();
}
}
else
if
(
std
::
strcmp
(
_params
->
icp_algorithm
.
c_str
(),
"gicp"
)
==
0
)
else
if
(
std
::
strcmp
(
_params
->
icp_algorithm
.
c_str
(),
"gicp"
)
==
0
)
{
{
WOLF_INFO
(
"ProcessorOdomIcp3d: Using gicp"
);
WOLF_INFO
(
"ProcessorOdomIcp3d: Using gicp"
);
registration_solver_
=
std
::
make_shared
<
pcl
::
GeneralizedIterativeClosestPoint
<
pcl
::
PointXYZ
,
pcl
::
PointXYZ
>>
();
registration_solver_
=
pcl
::
make_shared
<
pcl
::
GeneralizedIterativeClosestPoint
<
pcl
::
PointXYZ
,
pcl
::
PointXYZ
>>
();
}
}
else
else
{
{
...
...
This diff is collapsed.
Click to expand it.
test/gtest_laser3d_tools.cpp
+
2
−
2
View file @
61b37ba2
...
@@ -77,7 +77,7 @@ TEST(pairAlign, identity)
...
@@ -77,7 +77,7 @@ TEST(pairAlign, identity)
// Solver configuration
// Solver configuration
RegistrationPtr
registration_solver
=
RegistrationPtr
registration_solver
=
std
::
make_shared
<
pcl
::
IterativeClosestPointNonLinear
<
pcl
::
PointXYZ
,
pcl
::
PointXYZ
>>
();
pcl
::
make_shared
<
pcl
::
IterativeClosestPointNonLinear
<
pcl
::
PointXYZ
,
pcl
::
PointXYZ
>>
();
registration_solver
->
setTransformationEpsilon
(
1e-6
);
registration_solver
->
setTransformationEpsilon
(
1e-6
);
// Set the maximum distance between two correspondences (src<->tgt) to 10cm
// Set the maximum distance between two correspondences (src<->tgt) to 10cm
// Note: adjust this based on the size of your datasets
// Note: adjust this based on the size of your datasets
...
@@ -123,7 +123,7 @@ TEST(pairAlign, known_transformation)
...
@@ -123,7 +123,7 @@ TEST(pairAlign, known_transformation)
// Solver configuration
// Solver configuration
RegistrationPtr
registration_solver
=
RegistrationPtr
registration_solver
=
std
::
make_shared
<
pcl
::
IterativeClosestPointNonLinear
<
pcl
::
PointXYZ
,
pcl
::
PointXYZ
>>
();
pcl
::
make_shared
<
pcl
::
IterativeClosestPointNonLinear
<
pcl
::
PointXYZ
,
pcl
::
PointXYZ
>>
();
// pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> registration_solver;
// pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> registration_solver;
double
max_trans_epsilon_meters
=
0.001
;
double
max_trans_epsilon_meters
=
0.001
;
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment