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
69c389ba
Commit
69c389ba
authored
3 years ago
by
Joan Vallvé Navarro
Browse files
Options
Downloads
Patches
Plain Diff
Resolve "New processor loop closure"
parent
3fbe0236
No related branches found
No related tags found
3 merge requests
!30
Release after RAL
,
!29
After 2nd RAL submission
,
!24
Resolve "New processor loop closure"
Changes
2
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
include/laser/processor/processor_loop_closure_icp.h
+38
-42
38 additions, 42 deletions
include/laser/processor/processor_loop_closure_icp.h
src/processor/processor_loop_closure_icp.cpp
+124
-194
124 additions, 194 deletions
src/processor/processor_loop_closure_icp.cpp
with
162 additions
and
236 deletions
include/laser/processor/processor_loop_closure_icp.h
+
38
−
42
View file @
69c389ba
...
@@ -5,7 +5,7 @@
...
@@ -5,7 +5,7 @@
* WOLF includes *
* WOLF includes *
**************************/
**************************/
#include
"core/common/wolf.h"
#include
"core/common/wolf.h"
#include
<core/processor/processor_
bas
e.h>
#include
<core/processor/processor_
loop_closur
e.h>
#include
<laser/capture/capture_laser_2d.h>
#include
<laser/capture/capture_laser_2d.h>
#include
<core/factor/factor_relative_pose_2d_with_extrinsics.h>
#include
<core/factor/factor_relative_pose_2d_with_extrinsics.h>
...
@@ -22,10 +22,10 @@ namespace wolf
...
@@ -22,10 +22,10 @@ namespace wolf
WOLF_PTR_TYPEDEFS
(
ProcessorLoopClosureIcp
);
WOLF_PTR_TYPEDEFS
(
ProcessorLoopClosureIcp
);
WOLF_STRUCT_PTR_TYPEDEFS
(
ParamsProcessorLoopClosureIcp
);
WOLF_STRUCT_PTR_TYPEDEFS
(
ParamsProcessorLoopClosureIcp
);
struct
ParamsProcessorLoopClosureIcp
:
public
ParamsProcessor
Bas
e
struct
ParamsProcessorLoopClosureIcp
:
public
ParamsProcessor
LoopClosur
e
{
{
int
recent_
key_
frames_ignored
;
int
recent_frames_ignored
;
int
key_
frames_to_wait
;
int
frames_to_wait
;
double
max_error_threshold
;
double
max_error_threshold
;
double
min_points_percent
;
double
min_points_percent
;
...
@@ -34,14 +34,14 @@ struct ParamsProcessorLoopClosureIcp : public ParamsProcessorBase
...
@@ -34,14 +34,14 @@ struct ParamsProcessorLoopClosureIcp : public ParamsProcessorBase
ParamsProcessorLoopClosureIcp
()
=
default
;
ParamsProcessorLoopClosureIcp
()
=
default
;
ParamsProcessorLoopClosureIcp
(
std
::
string
_unique_name
,
const
ParamsServer
&
_server
)
:
ParamsProcessorLoopClosureIcp
(
std
::
string
_unique_name
,
const
ParamsServer
&
_server
)
:
ParamsProcessor
Bas
e
(
_unique_name
,
_server
)
ParamsProcessor
LoopClosur
e
(
_unique_name
,
_server
)
{
{
recent_
key_
frames_ignored
=
_server
.
getParam
<
int
>
(
prefix
+
_unique_name
+
"/recent_
key_
frames_ignored"
);
recent_frames_ignored
=
_server
.
getParam
<
int
>
(
prefix
+
_unique_name
+
"/recent_frames_ignored"
);
key_
frames_to_wait
=
_server
.
getParam
<
int
>
(
prefix
+
_unique_name
+
"/
key_
frames_to_wait"
);
frames_to_wait
=
_server
.
getParam
<
int
>
(
prefix
+
_unique_name
+
"/frames_to_wait"
);
max_error_threshold
=
_server
.
getParam
<
double
>
(
prefix
+
_unique_name
+
"/max_error_threshold"
);
max_error_threshold
=
_server
.
getParam
<
double
>
(
prefix
+
_unique_name
+
"/max_error_threshold"
);
min_points_percent
=
_server
.
getParam
<
double
>
(
prefix
+
_unique_name
+
"/min_points_percent"
);
min_points_percent
=
_server
.
getParam
<
double
>
(
prefix
+
_unique_name
+
"/min_points_percent"
);
icp_params
.
use_point_to_line_distance
=
_server
.
getParam
<
double
>
(
prefix
+
_unique_name
+
"/cov_factor"
);
icp_params
.
cov_factor
=
_server
.
getParam
<
double
>
(
prefix
+
_unique_name
+
"/cov_factor"
);
icp_params
.
use_point_to_line_distance
=
_server
.
getParam
<
int
>
(
prefix
+
_unique_name
+
"/use_point_to_line_distance"
);
icp_params
.
use_point_to_line_distance
=
_server
.
getParam
<
int
>
(
prefix
+
_unique_name
+
"/use_point_to_line_distance"
);
icp_params
.
max_correspondence_dist
=
_server
.
getParam
<
double
>
(
prefix
+
_unique_name
+
"/max_correspondence_dist"
);
icp_params
.
max_correspondence_dist
=
_server
.
getParam
<
double
>
(
prefix
+
_unique_name
+
"/max_correspondence_dist"
);
...
@@ -79,22 +79,21 @@ struct ParamsProcessorLoopClosureIcp : public ParamsProcessorBase
...
@@ -79,22 +79,21 @@ struct ParamsProcessorLoopClosureIcp : public ParamsProcessorBase
}
}
std
::
string
print
()
const
override
std
::
string
print
()
const
override
{
{
return
"
\n
"
+
ParamsProcessor
Bas
e
::
print
()
return
"
\n
"
+
ParamsProcessor
LoopClosur
e
::
print
()
+
"recent_
key_
frames_ignored: "
+
std
::
to_string
(
recent_
key_
frames_ignored
)
+
"
\n
"
+
"recent_frames_ignored: "
+
std
::
to_string
(
recent_frames_ignored
)
+
"
\n
"
+
"
key_
frames_to_wait: "
+
std
::
to_string
(
key_
frames_to_wait
)
+
"
\n
"
+
"frames_to_wait: "
+
std
::
to_string
(
frames_to_wait
)
+
"
\n
"
+
"max_error_threshold: "
+
std
::
to_string
(
max_error_threshold
)
+
"
\n
"
+
"max_error_threshold: "
+
std
::
to_string
(
max_error_threshold
)
+
"
\n
"
+
"min_points_percent: "
+
std
::
to_string
(
min_points_percent
)
+
"
\n
"
;
+
"min_points_percent: "
+
std
::
to_string
(
min_points_percent
)
+
"
\n
"
;
}
}
};
};
struct
CapturesAligned
{
CaptureBasePtr
capture_own
;
CaptureBasePtr
capture_other
;
laserscanutils
::
icpOutput
align_result
;
};
WOLF_STRUCT_PTR_TYPEDEFS
(
MatchLoopClosureIcp
);
struct
MatchLoopClosureIcp
:
public
MatchLoopClosure
{
laserscanutils
::
icpOutput
align_result_
;
};
class
ProcessorLoopClosureIcp
:
public
Processor
Bas
e
class
ProcessorLoopClosureIcp
:
public
Processor
LoopClosur
e
{
{
protected:
protected:
// Useful sensor stuff
// Useful sensor stuff
...
@@ -103,7 +102,7 @@ class ProcessorLoopClosureIcp : public ProcessorBase
...
@@ -103,7 +102,7 @@ class ProcessorLoopClosureIcp : public ProcessorBase
//Closeloop parameters
//Closeloop parameters
ParamsProcessorLoopClosureIcpPtr
params_loop_closure_icp_
;
ParamsProcessorLoopClosureIcpPtr
params_loop_closure_icp_
;
int
key_
frames_skipped_
;
int
frames_skipped_
;
// ICP algorithm
// ICP algorithm
std
::
shared_ptr
<
laserscanutils
::
ICP
>
icp_tools_ptr_
;
std
::
shared_ptr
<
laserscanutils
::
ICP
>
icp_tools_ptr_
;
...
@@ -115,32 +114,29 @@ class ProcessorLoopClosureIcp : public ProcessorBase
...
@@ -115,32 +114,29 @@ class ProcessorLoopClosureIcp : public ProcessorBase
void
configure
(
SensorBasePtr
_sensor
)
override
;
void
configure
(
SensorBasePtr
_sensor
)
override
;
protected:
protected:
void
processCapture
(
CaptureBasePtr
)
override
;
void
processKeyFrame
(
FrameBasePtr
_keyframe_ptr
,
const
double
&
_time_tolerance
)
override
;
bool
triggerInCapture
(
CaptureBasePtr
)
const
override
;
bool
triggerInKeyFrame
(
FrameBasePtr
_keyframe_ptr
,
const
double
&
_time_tolerance
)
const
override
;
bool
storeKeyFrame
(
FrameBasePtr
)
override
;
bool
storeCapture
(
CaptureBasePtr
)
override
;
bool
voteForKeyFrame
()
const
override
;
FrameBasePtrList
selectCandidates
(
FrameBasePtr
_keyframe_ptr
,
/** \brief Returns if findLoopClosures() has to be called for the given capture
const
double
&
_time_tolerance
);
* Since there is no enough information in the capture to decide if a loop can be closed, try always.
*/
bool
voteFindLoopClosures
(
CaptureBasePtr
cap
)
override
;
std
::
map
<
double
,
CapturesAligned
>
evaluateCandidates
(
FrameBasePtr
_keyframe_own
,
/** \brief detects and emplaces all features of the given capture
FrameBasePtrList
&
_keyframe_candidates
);
* Since the loop closures of this processor are not based on any features, it is empty
*/
void
emplaceFeatures
(
CaptureBasePtr
cap
)
override
{};
CapturesAligned
bestCandidate
(
std
::
map
<
double
,
CapturesAligned
>&
_capture_candidates
);
/** \brief Find captures that correspond to loop closures with the given capture
*/
std
::
map
<
double
,
MatchLoopClosurePtr
>
findLoopClosures
(
CaptureBasePtr
_capture
)
override
;
FactorBasePtr
emplaceFeatureAndFactor
(
CapturesAligned
&
_captures_aligned
);
/** \brief validates a loop closure
* Loops are validated just after calling ICP
*/
bool
validateLoopClosure
(
MatchLoopClosurePtr
)
override
{
return
true
;};
/** \brief emplaces the factor(s) corresponding to a Loop Closure between two captures
*/
void
emplaceFactors
(
MatchLoopClosurePtr
)
override
;
};
};
}
}
...
...
This diff is collapsed.
Click to expand it.
src/processor/processor_loop_closure_icp.cpp
+
124
−
194
View file @
69c389ba
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