Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
e4f8eea2
Commit
e4f8eea2
authored
Nov 01, 2015
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
QGC: Fix excessive noise terms
parent
9ebd2baf
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
10 additions
and
10 deletions
+10
-10
UAS.cc
src/uas/UAS.cc
+10
-10
No files found.
src/uas/UAS.cc
View file @
e4f8eea2
...
...
@@ -1765,7 +1765,7 @@ void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObj
simulation
=
new
QGCFlightGearLink
(
_vehicle
,
options
);
}
float
noise_scaler
=
0.00
2
f
;
float
noise_scaler
=
0.00
01
f
;
xacc_var
=
noise_scaler
*
0.2914
f
;
yacc_var
=
noise_scaler
*
0.2914
f
;
zacc_var
=
noise_scaler
*
0.9577
f
;
...
...
@@ -1775,10 +1775,10 @@ void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObj
xmag_var
=
noise_scaler
*
0.0786
f
;
ymag_var
=
noise_scaler
*
0.0566
f
;
zmag_var
=
noise_scaler
*
0.0333
f
;
abs_pressure_var
=
noise_scaler
*
1.1
604
f
;
diff_pressure_var
=
noise_scaler
*
0.
3
604
f
;
pressure_alt_var
=
noise_scaler
*
1.1
604
f
;
temperature_var
=
noise_scaler
*
2.4
290
f
;
abs_pressure_var
=
noise_scaler
*
0.5
604
f
;
diff_pressure_var
=
noise_scaler
*
0.
2
604
f
;
pressure_alt_var
=
noise_scaler
*
0.5
604
f
;
temperature_var
=
noise_scaler
*
0.7
290
f
;
// Connect Flight Gear Link
link
=
dynamic_cast
<
QGCFlightGearLink
*>
(
simulation
);
...
...
@@ -1840,7 +1840,7 @@ void UAS::enableHilXPlane(bool enable)
}
simulation
=
new
QGCXPlaneLink
(
_vehicle
);
float
noise_scaler
=
0.000
2
f
;
float
noise_scaler
=
0.000
1
f
;
xacc_var
=
noise_scaler
*
0.2914
f
;
yacc_var
=
noise_scaler
*
0.2914
f
;
zacc_var
=
noise_scaler
*
0.9577
f
;
...
...
@@ -1850,10 +1850,10 @@ void UAS::enableHilXPlane(bool enable)
xmag_var
=
noise_scaler
*
0.0786
f
;
ymag_var
=
noise_scaler
*
0.0566
f
;
zmag_var
=
noise_scaler
*
0.0333
f
;
abs_pressure_var
=
noise_scaler
*
1.1
604
f
;
diff_pressure_var
=
noise_scaler
*
0.
3
604
f
;
pressure_alt_var
=
noise_scaler
*
1.1
604
f
;
temperature_var
=
noise_scaler
*
2.4
290
f
;
abs_pressure_var
=
noise_scaler
*
0.5
604
f
;
diff_pressure_var
=
noise_scaler
*
0.
2
604
f
;
pressure_alt_var
=
noise_scaler
*
0.5
604
f
;
temperature_var
=
noise_scaler
*
0.7
290
f
;
}
// Connect X-Plane Link
if
(
enable
)
...
...
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