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
017e564a
Commit
017e564a
authored
Feb 11, 2014
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fix double->float truncations
parent
96fd7a03
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
34 additions
and
34 deletions
+34
-34
QGCFlightGearLink.cc
src/comm/QGCFlightGearLink.cc
+2
-2
QGCXPlaneLink.cc
src/comm/QGCXPlaneLink.cc
+6
-6
UAS.cc
src/uas/UAS.cc
+1
-1
PrimaryFlightDisplay.cc
src/ui/PrimaryFlightDisplay.cc
+9
-9
BatteryMonitorConfig.cc
src/ui/configuration/BatteryMonitorConfig.cc
+16
-16
No files found.
src/comm/QGCFlightGearLink.cc
View file @
017e564a
...
@@ -353,8 +353,8 @@ void QGCFlightGearLink::readBytes()
...
@@ -353,8 +353,8 @@ void QGCFlightGearLink::readBytes()
// qDebug() << "sensorHilRawImuChanged " << xacc << yacc << zacc << rollspeed << pitchspeed << yawspeed << xmag << ymag << zmag << abs_pressure << diff_pressure << pressure_alt << temperature;
// qDebug() << "sensorHilRawImuChanged " << xacc << yacc << zacc << rollspeed << pitchspeed << yawspeed << xmag << ymag << zmag << abs_pressure << diff_pressure << pressure_alt << temperature;
int
gps_fix_type
=
3
;
int
gps_fix_type
=
3
;
float
eph
=
0.3
;
float
eph
=
0.3
f
;
float
epv
=
0.6
;
float
epv
=
0.6
f
;
float
vel
=
sqrt
(
vx
*
vx
+
vy
*
vy
+
vz
*
vz
);
float
vel
=
sqrt
(
vx
*
vx
+
vy
*
vy
+
vz
*
vz
);
float
cog
=
yaw
;
float
cog
=
yaw
;
int
satellites
=
8
;
int
satellites
=
8
;
...
...
src/comm/QGCXPlaneLink.cc
View file @
017e564a
...
@@ -518,19 +518,19 @@ void QGCXPlaneLink::readBytes()
...
@@ -518,19 +518,19 @@ void QGCXPlaneLink::readBytes()
// X-Plane expresses yaw as 0..2 PI
// X-Plane expresses yaw as 0..2 PI
if
(
yaw
>
M_PI
)
{
if
(
yaw
>
M_PI
)
{
yaw
-=
2.0
*
M_PI
;
yaw
-=
2.0
f
*
static_cast
<
float
>
(
M_PI
)
;
}
}
if
(
yaw
<
-
M_PI
)
{
if
(
yaw
<
-
M_PI
)
{
yaw
+=
2.0
*
M_PI
;
yaw
+=
2.0
f
*
static_cast
<
float
>
(
M_PI
)
;
}
}
float
yawmag
=
p
.
f
[
3
]
/
180.0
f
*
M_PI
;
float
yawmag
=
p
.
f
[
3
]
/
180.0
f
*
M_PI
;
if
(
yawmag
>
M_PI
)
{
if
(
yawmag
>
M_PI
)
{
yawmag
-=
2.0
*
M_PI
;
yawmag
-=
2.0
f
*
static_cast
<
float
>
(
M_PI
)
;
}
}
if
(
yawmag
<
-
M_PI
)
{
if
(
yawmag
<
-
M_PI
)
{
yawmag
+=
2.0
*
M_PI
;
yawmag
+=
2.0
f
*
static_cast
<
float
>
(
M_PI
)
;
}
}
// Normal rotation matrix, but since we rotate the
// Normal rotation matrix, but since we rotate the
...
@@ -689,8 +689,8 @@ void QGCXPlaneLink::readBytes()
...
@@ -689,8 +689,8 @@ void QGCXPlaneLink::readBytes()
// XXX make these GUI-configurable and add randomness
// XXX make these GUI-configurable and add randomness
int
gps_fix_type
=
3
;
int
gps_fix_type
=
3
;
float
eph
=
0.3
;
float
eph
=
0.3
f
;
float
epv
=
0.6
;
float
epv
=
0.6
f
;
float
vel
=
sqrt
(
vx
*
vx
+
vy
*
vy
+
vz
*
vz
);
float
vel
=
sqrt
(
vx
*
vx
+
vy
*
vy
+
vz
*
vz
);
float
cog
=
atan2
(
vy
,
vx
);
float
cog
=
atan2
(
vy
,
vx
);
int
satellites
=
8
;
int
satellites
=
8
;
...
...
src/uas/UAS.cc
View file @
017e564a
...
@@ -3198,7 +3198,7 @@ void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fi
...
@@ -3198,7 +3198,7 @@ void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fi
float
course
=
cog
;
float
course
=
cog
;
// map to 0..2pi
// map to 0..2pi
if
(
course
<
0
)
if
(
course
<
0
)
course
+=
2.0
f
*
M_PI
;
course
+=
2.0
f
*
static_cast
<
float
>
(
M_PI
)
;
// scale from radians to degrees
// scale from radians to degrees
course
=
(
course
/
M_PI
)
*
180.0
f
;
course
=
(
course
/
M_PI
)
*
180.0
f
;
...
...
src/ui/PrimaryFlightDisplay.cc
View file @
017e564a
...
@@ -33,7 +33,7 @@ static const float PITCHTRANSLATION = 65;
...
@@ -33,7 +33,7 @@ static const float PITCHTRANSLATION = 65;
// 5 degrees for each line
// 5 degrees for each line
static
const
int
PITCH_SCALE_RESOLUTION
=
5
;
static
const
int
PITCH_SCALE_RESOLUTION
=
5
;
static
const
float
PITCH_SCALE_MAJORWIDTH
=
0.1
f
;
static
const
float
PITCH_SCALE_MAJORWIDTH
=
0.1
f
;
static
const
float
PITCH_SCALE_MINORWIDTH
=
0.066
;
static
const
float
PITCH_SCALE_MINORWIDTH
=
0.066
f
;
// Beginning from PITCH_SCALE_WIDTHREDUCTION_FROM degrees of +/- pitch, the
// Beginning from PITCH_SCALE_WIDTHREDUCTION_FROM degrees of +/- pitch, the
// width of the lines is reduced, down to PITCH_SCALE_WIDTHREDUCTION times
// width of the lines is reduced, down to PITCH_SCALE_WIDTHREDUCTION times
...
@@ -49,18 +49,18 @@ static const int PITCH_SCALE_HALFRANGE = 15;
...
@@ -49,18 +49,18 @@ static const int PITCH_SCALE_HALFRANGE = 15;
static
const
int
COMPASS_DISK_MAJORTICK
=
10
;
static
const
int
COMPASS_DISK_MAJORTICK
=
10
;
static
const
int
COMPASS_DISK_ARROWTICK
=
45
;
static
const
int
COMPASS_DISK_ARROWTICK
=
45
;
static
const
float
COMPASS_DISK_MAJORLINEWIDTH
=
0.006
;
static
const
float
COMPASS_DISK_MAJORLINEWIDTH
=
0.006
f
;
static
const
float
COMPASS_DISK_MINORLINEWIDTH
=
0.004
;
static
const
float
COMPASS_DISK_MINORLINEWIDTH
=
0.004
f
;
static
const
int
COMPASS_DISK_RESOLUTION
=
10
;
static
const
int
COMPASS_DISK_RESOLUTION
=
10
;
static
const
float
COMPASS_SEPARATE_DISK_RESOLUTION
=
5
;
static
const
float
COMPASS_SEPARATE_DISK_RESOLUTION
=
5
.0
f
;
static
const
float
COMPASS_DISK_MARKERWIDTH
=
0.2
;
static
const
float
COMPASS_DISK_MARKERWIDTH
=
0.2
f
;
static
const
float
COMPASS_DISK_MARKERHEIGHT
=
0.133
;
static
const
float
COMPASS_DISK_MARKERHEIGHT
=
0.133
f
;
static
const
int
CROSSTRACK_MAX
=
1000
;
static
const
int
CROSSTRACK_MAX
=
1000
;
static
const
float
CROSSTRACK_RADIUS
=
0.6
;
static
const
float
CROSSTRACK_RADIUS
=
0.6
f
;
static
const
float
TAPE_GAUGES_TICKWIDTH_MAJOR
=
0.25
;
static
const
float
TAPE_GAUGES_TICKWIDTH_MAJOR
=
0.25
f
;
static
const
float
TAPE_GAUGES_TICKWIDTH_MINOR
=
0.15
;
static
const
float
TAPE_GAUGES_TICKWIDTH_MINOR
=
0.15
f
;
// The altitude difference between top and bottom of scale
// The altitude difference between top and bottom of scale
static
const
int
ALTIMETER_LINEAR_SPAN
=
50
;
static
const
int
ALTIMETER_LINEAR_SPAN
=
50
;
...
...
src/ui/configuration/BatteryMonitorConfig.cc
View file @
017e564a
...
@@ -149,39 +149,39 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
...
@@ -149,39 +149,39 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
}
}
void
BatteryMonitorConfig
::
sensorCurrentIndexChanged
(
int
index
)
void
BatteryMonitorConfig
::
sensorCurrentIndexChanged
(
int
index
)
{
{
float
maxvolt
=
0.0
;
float
maxvolt
=
0.0
f
;
float
maxamps
=
0.0
;
float
maxamps
=
0.0
f
;
float
mvpervolt
=
0.0
;
float
mvpervolt
=
0.0
f
;
float
mvperamp
=
0.0
;
float
mvperamp
=
0.0
f
;
float
topvolt
=
0.0
;
float
topvolt
=
0.0
f
;
float
topamps
=
0.0
;
float
topamps
=
0.0
f
;
if
(
index
==
1
)
if
(
index
==
1
)
{
{
//atto 45 see https://www.sparkfun.com/products/10643
//atto 45 see https://www.sparkfun.com/products/10643
maxvolt
=
13.6
;
maxvolt
=
13.6
f
;
maxamps
=
44.7
;
maxamps
=
44.7
f
;
}
}
else
if
(
index
==
2
)
else
if
(
index
==
2
)
{
{
//atto 90 see https://www.sparkfun.com/products/9028
//atto 90 see https://www.sparkfun.com/products/9028
maxvolt
=
51.8
;
maxvolt
=
51.8
f
;
maxamps
=
89.4
;
maxamps
=
89.4
f
;
}
}
else
if
(
index
==
3
)
else
if
(
index
==
3
)
{
{
//atto 180 see https://www.sparkfun.com/products/10644
//atto 180 see https://www.sparkfun.com/products/10644
maxvolt
=
51.8
;
maxvolt
=
51.8
f
;
maxamps
=
178.8
;
maxamps
=
178.8
f
;
}
}
else
if
(
index
==
4
)
else
if
(
index
==
4
)
{
{
//3dr
//3dr
maxvolt
=
50.0
;
maxvolt
=
50.0
f
;
maxamps
=
90.0
;
maxamps
=
90.0
f
;
}
}
mvpervolt
=
calculatemVPerVolt
(
3.3
,
maxvolt
);
mvpervolt
=
calculatemVPerVolt
(
3.3
f
,
maxvolt
);
mvperamp
=
calculatemVPerAmp
(
3.3
,
maxamps
);
mvperamp
=
calculatemVPerAmp
(
3.3
f
,
maxamps
);
if
(
index
==
0
)
if
(
index
==
0
)
{
{
//Other
//Other
...
...
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