Skip to content
GitLab
Projects
Groups
Snippets
Help
Loading...
Help
What's new
4
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Switch to GitLab Next
Sign in / Register
Toggle navigation
eskf_odometry_ros
Project overview
Project overview
Details
Activity
Releases
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Locked Files
Issues
0
Issues
0
List
Boards
Labels
Service Desk
Milestones
Iterations
Merge Requests
0
Merge Requests
0
Requirements
Requirements
List
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Test Cases
Security & Compliance
Security & Compliance
Dependency List
License Compliance
Operations
Operations
Incidents
Environments
Packages & Registries
Packages & Registries
Package Registry
Container Registry
Analytics
Analytics
CI / CD
Code Review
Insights
Issue
Repository
Value Stream
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Angel Santamaria-Navarro
C
code
S
state_estimation
eskf_odometry
eskf_odometry_ros
Commits
0e8133fb
Commit
0e8133fb
authored
Feb 15, 2016
by
asantamaria
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
typos and sensor var names matched
parent
c4530fe8
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
3 additions
and
9 deletions
+3
-9
launch/params.yaml
launch/params.yaml
+0
-3
src/eskf_odom_alg_node.cpp
src/eskf_odom_alg_node.cpp
+3
-6
No files found.
launch/params.yaml
View file @
0e8133fb
...
...
@@ -22,14 +22,11 @@ imu_method: discrete #Sets the data time nature (continous: simulated IMU or dis
px4_std_outsidebounds
:
[
10.0
,
10.0
,
10.0
]
px4_std_insidebounds
:
[
0.01
,
0.15
,
0.15
]
# Range STD values
range_std_landed
:
0.1
range_std_outsidebounds
:
10.0
range_std_insidebounds
:
0.01
# Flow2d STD values
flow2d_std_landed
:
[
0.001
,
0.001
]
flow2d_std_outsidebounds
:
[
10.0
,
10.0
]
flow2d_std_insidebounds
:
[
0.15
,
0.15
]
flow2d_focal_length
:
0.016
...
...
src/eskf_odom_alg_node.cpp
View file @
0e8133fb
...
...
@@ -100,21 +100,18 @@ void EskfOdomAlgNode::read_and_set_ini_params(void)
// Range STD values
Sensor
::
range_params
range_params
;
double
std_landed
,
std_outsidebounds
,
std_insidebounds
;
this
->
public_node_handle_
.
param
<
double
>
(
"range_std_landed"
,
std_landed
,
0.1
);
double
std_outsidebounds
,
std_insidebounds
;
this
->
public_node_handle_
.
param
<
double
>
(
"range_std_outsidebounds"
,
std_outsidebounds
,
10.0
);
this
->
public_node_handle_
.
param
<
double
>
(
"range_std_insidebounds"
,
std_insidebounds
,
0.01
);
range_params
.
std_landed
=
static_cast
<
float
>
(
std_landed
);
range_params
.
std_outsidebounds
=
static_cast
<
float
>
(
std_outsidebounds
);
range_params
.
std_insidebounds
=
static_cast
<
float
>
(
std_insidebounds
);
range_params
.
std
=
range_params
.
std_
landed
;
// Considering initially landed
range_params
.
std
=
range_params
.
std_
outsidebounds
;
// Considering initially landed
// Flow2d STD values
Sensor
::
flow2d_params
flow2d_params
;
flow2d_params
.
std_landed
=
read_vec
(
"flow2d_std_landed"
,
2
);
flow2d_params
.
std_outsidebounds
=
read_vec
(
"flow2d_std_outsidebounds"
,
2
);
flow2d_params
.
std_insidebounds
=
read_vec
(
"flow2d_std_insidebounds"
,
2
);
flow2d_params
.
std
=
flow2d_params
.
std_
landed
;
// Considering initially landed
flow2d_params
.
std
=
flow2d_params
.
std_
outsidebounds
;
// Considering initially landed
double
focal_length
;
this
->
public_node_handle_
.
param
<
double
>
(
"flow2d_focal_length"
,
focal_length
,
0.016
);
flow2d_params
.
focal_length
=
static_cast
<
float
>
(
focal_length
);
...
...
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