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
af85cb3a
Commit
af85cb3a
authored
Apr 07, 2016
by
asantamaria
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
From hummingbird. tunning.
parent
c2241887
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
63 additions
and
1 deletion
+63
-1
launch/params_kinton.yaml
launch/params_kinton.yaml
+62
-0
src/eskf_odom_alg_node.cpp
src/eskf_odom_alg_node.cpp
+1
-1
No files found.
launch/params_kinton.yaml
0 → 100644
View file @
af85cb3a
# Frame names
odom_frame_id
:
odom
robot_frame_id
:
base_link
# Initial STD of Error-State values (filter)
dp0_std
:
[
0.0
,
0.0
,
0.05
]
dv0_std
:
[
0.0
,
0.0
,
0.0
]
dtheta0_std
:
[
0.05
,
0.05
,
0.0
]
dab0_std
:
[
0.0196
,
0.0196
,
0.0196
]
dwb0_std
:
[
0.0037
,
0.0040
,
0.0
]
dg0_std
:
[
0.0
,
0.0
,
0.0
]
dpo0_std
:
[
0.0
,
0.0
,
0.0
]
dthetao0_std
:
[
0.0
,
0.0
,
0.0
]
dpr0_std
:
[
0.0
,
0.0
,
0.0
]
dthetar0_std
:
[
0.0
,
0.0
,
0.0
]
frame
:
global
# Frame r.t. orientation derivation is computed (global or local)
#IMU pose`
imu_z_up
:
true
#IMU STD values
imu_a_std
:
[
0.2
,
0.2
,
0.2
]
imu_w_std
:
[
0.005
,
0.005
,
0.005
]
imu_ab_std
:
[
0.0
,
0.0
,
0.0
]
imu_wb_std
:
[
0.0
,
0.0
,
0.0
]
imu_method
:
discrete
#Sets the data time nature (continous: simulated IMU or discrete: IMU sensor).
# Position STD values
position_std_outsidebounds
:
[
10.0
,
10.0
,
10.0
]
position_std_insidebounds
:
[
0.01
,
0.01
,
0.01
]
# Orientation STD values
orientation_std_outsidebounds
:
[
10.0
,
10.0
,
10.0
]
orientation_std_insidebounds
:
[
0.01
,
0.01
,
0.01
]
# Linear velocity STD values
linvel_std_outsidebounds
:
[
10.0
,
10.0
,
10.0
]
linvel_std_insidebounds
:
[
0.01
,
0.01
,
0.01
]
# Range STD values
range_std_outsidebounds
:
10.0
range_std_insidebounds
:
0.01
range_min
:
0.31
range_max
:
4.0
using_laser_range
:
true
# PX4 STD values
px4_std_outsidebounds
:
[
10.0
,
10.0
,
10.0
]
px4_std_insidebounds
:
[
0.01
,
0.15
,
0.15
]
using_laser_px4
:
true
# Flow2d STD values
flow2d_std_outsidebounds
:
[
10.0
,
10.0
]
flow2d_std_insidebounds
:
[
0.15
,
0.15
]
# focal_length in pixels
flow2d_focal_length
:
73
# Initial Nominal-State vector (p,v,q,ab,wb,g)
xstate0
:
[
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
1.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
-0.0005
,
-0.0026
,
-0.0004
,
0.0
,
0.0
,
-9.803057
,
0.0
,
0.0
,
0.0
,
1.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
1.0
,
0.0
,
0.0
,
0.0
]
# Initial Error-State vector (dp,dv,dtheta,dab,dwb,dg)
dxstate0
:
[
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
]
src/eskf_odom_alg_node.cpp
View file @
af85cb3a
...
...
@@ -529,7 +529,7 @@ void EskfOdomAlgNode::set_px4_reading(const px_comm::OpticalFlow::ConstPtr& msg,
// // this->alg_.set_px4_params(px4_params);
// // }
//
this->alg_.set_px4_reading(msg_time, val, flow); // Set values into filter object
//this->alg_.set_px4_reading(msg_time, val, flow); // Set values into filter object
//*****************************
// USING RANGE AND RAW FLOW
...
...
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