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
61a50ca6
Commit
61a50ca6
authored
May 20, 2018
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
comit
parent
65ebabe4
Changes
4
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
196 additions
and
156 deletions
+196
-156
APMAirframeComponent.qml
src/AutoPilotPlugins/APM/APMAirframeComponent.qml
+3
-4
APMPowerComponent.qml
src/AutoPilotPlugins/APM/APMPowerComponent.qml
+162
-129
Vehicle.cc
src/Vehicle/Vehicle.cc
+23
-19
Vehicle.h
src/Vehicle/Vehicle.h
+8
-4
No files found.
src/AutoPilotPlugins/APM/APMAirframeComponent.qml
View file @
61a50ca6
...
...
@@ -83,10 +83,9 @@ SetupPage {
id
:
newFramePageComponent
Grid
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margins
columns
:
2
width
:
availableWidth
spacing
:
_margins
columns
:
2
QGCLabel
{
text
:
qsTr
(
"
Frame Class:
"
)
...
...
src/AutoPilotPlugins/APM/APMPowerComponent.qml
View file @
61a50ca6
This diff is collapsed.
Click to expand it.
src/Vehicle/Vehicle.cc
View file @
61a50ca6
...
...
@@ -69,7 +69,8 @@ const char* Vehicle::_distanceToHomeFactName = "distanceToHome";
const
char
*
Vehicle
::
_hobbsFactName
=
"hobbs"
;
const
char
*
Vehicle
::
_gpsFactGroupName
=
"gps"
;
const
char
*
Vehicle
::
_batteryFactGroupName
=
"battery"
;
const
char
*
Vehicle
::
_battery1FactGroupName
=
"battery"
;
const
char
*
Vehicle
::
_battery2FactGroupName
=
"battery2"
;
const
char
*
Vehicle
::
_windFactGroupName
=
"wind"
;
const
char
*
Vehicle
::
_vibrationFactGroupName
=
"vibration"
;
const
char
*
Vehicle
::
_temperatureFactGroupName
=
"temperature"
;
...
...
@@ -185,7 +186,8 @@ Vehicle::Vehicle(LinkInterface* link,
,
_distanceToHomeFact
(
0
,
_distanceToHomeFactName
,
FactMetaData
::
valueTypeDouble
)
,
_hobbsFact
(
0
,
_hobbsFactName
,
FactMetaData
::
valueTypeString
)
,
_gpsFactGroup
(
this
)
,
_batteryFactGroup
(
this
)
,
_battery1FactGroup
(
this
)
,
_battery2FactGroup
(
this
)
,
_windFactGroup
(
this
)
,
_vibrationFactGroup
(
this
)
,
_temperatureFactGroup
(
this
)
...
...
@@ -370,7 +372,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
,
_distanceToHomeFact
(
0
,
_distanceToHomeFactName
,
FactMetaData
::
valueTypeDouble
)
,
_hobbsFact
(
0
,
_hobbsFactName
,
FactMetaData
::
valueTypeString
)
,
_gpsFactGroup
(
this
)
,
_batteryFactGroup
(
this
)
,
_battery1FactGroup
(
this
)
,
_battery2FactGroup
(
this
)
,
_windFactGroup
(
this
)
,
_vibrationFactGroup
(
this
)
,
_clockFactGroup
(
this
)
...
...
@@ -440,7 +443,8 @@ void Vehicle::_commonInit(void)
_addFact
(
&
_hobbsFact
,
_hobbsFactName
);
_addFactGroup
(
&
_gpsFactGroup
,
_gpsFactGroupName
);
_addFactGroup
(
&
_batteryFactGroup
,
_batteryFactGroupName
);
_addFactGroup
(
&
_battery1FactGroup
,
_battery1FactGroupName
);
_addFactGroup
(
&
_battery2FactGroup
,
_battery2FactGroupName
);
_addFactGroup
(
&
_windFactGroup
,
_windFactGroupName
);
_addFactGroup
(
&
_vibrationFactGroup
,
_vibrationFactGroupName
);
_addFactGroup
(
&
_temperatureFactGroup
,
_temperatureFactGroupName
);
...
...
@@ -940,7 +944,7 @@ void Vehicle::_handleHighLatency2(mavlink_message_t& message)
_windFactGroup
.
direction
()
->
setRawValue
((
double
)
highLatency2
.
wind_heading
*
2.0
);
_windFactGroup
.
speed
()
->
setRawValue
((
double
)
highLatency2
.
windspeed
/
5.0
);
_batteryFactGroup
.
percentRemaining
()
->
setRawValue
(
highLatency2
.
battery
);
_battery
1
FactGroup
.
percentRemaining
()
->
setRawValue
(
highLatency2
.
battery
);
_temperatureFactGroup
.
temperature1
()
->
setRawValue
(
highLatency2
.
temperature_air
);
...
...
@@ -1245,19 +1249,19 @@ void Vehicle::_handleSysStatus(mavlink_message_t& message)
mavlink_msg_sys_status_decode
(
&
message
,
&
sysStatus
);
if
(
sysStatus
.
current_battery
==
-
1
)
{
_batteryFactGroup
.
current
()
->
setRawValue
(
VehicleBatteryFactGroup
::
_currentUnavailable
);
_battery
1
FactGroup
.
current
()
->
setRawValue
(
VehicleBatteryFactGroup
::
_currentUnavailable
);
}
else
{
// Current is in Amps, current_battery is 10 * milliamperes (1 = 10 milliampere)
_batteryFactGroup
.
current
()
->
setRawValue
((
float
)
sysStatus
.
current_battery
/
100.0
f
);
_battery
1
FactGroup
.
current
()
->
setRawValue
((
float
)
sysStatus
.
current_battery
/
100.0
f
);
}
if
(
sysStatus
.
voltage_battery
==
UINT16_MAX
)
{
_batteryFactGroup
.
voltage
()
->
setRawValue
(
VehicleBatteryFactGroup
::
_voltageUnavailable
);
_battery
1
FactGroup
.
voltage
()
->
setRawValue
(
VehicleBatteryFactGroup
::
_voltageUnavailable
);
}
else
{
_batteryFactGroup
.
voltage
()
->
setRawValue
((
double
)
sysStatus
.
voltage_battery
/
1000.0
);
_battery
1
FactGroup
.
voltage
()
->
setRawValue
((
double
)
sysStatus
.
voltage_battery
/
1000.0
);
// current_battery is 10 mA and voltage_battery is 1mV. (10/1e3 times 1/1e3 = 1/1e5)
_batteryFactGroup
.
instantPower
()
->
setRawValue
((
float
)(
sysStatus
.
current_battery
*
sysStatus
.
voltage_battery
)
/
(
100000.0
));
_battery
1
FactGroup
.
instantPower
()
->
setRawValue
((
float
)(
sysStatus
.
current_battery
*
sysStatus
.
voltage_battery
)
/
(
100000.0
));
}
_batteryFactGroup
.
percentRemaining
()
->
setRawValue
(
sysStatus
.
battery_remaining
);
_battery
1
FactGroup
.
percentRemaining
()
->
setRawValue
(
sysStatus
.
battery_remaining
);
if
(
sysStatus
.
battery_remaining
>
0
)
{
if
(
sysStatus
.
battery_remaining
<
_settingsManager
->
appSettings
()
->
batteryPercentRemainingAnnounce
()
->
rawValue
().
toInt
()
&&
...
...
@@ -1301,14 +1305,14 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
mavlink_msg_battery_status_decode
(
&
message
,
&
bat_status
);
if
(
bat_status
.
temperature
==
INT16_MAX
)
{
_batteryFactGroup
.
temperature
()
->
setRawValue
(
VehicleBatteryFactGroup
::
_temperatureUnavailable
);
_battery
1
FactGroup
.
temperature
()
->
setRawValue
(
VehicleBatteryFactGroup
::
_temperatureUnavailable
);
}
else
{
_batteryFactGroup
.
temperature
()
->
setRawValue
((
double
)
bat_status
.
temperature
/
100.0
);
_battery
1
FactGroup
.
temperature
()
->
setRawValue
((
double
)
bat_status
.
temperature
/
100.0
);
}
if
(
bat_status
.
current_consumed
==
-
1
)
{
_batteryFactGroup
.
mahConsumed
()
->
setRawValue
(
VehicleBatteryFactGroup
::
_mahConsumedUnavailable
);
_battery
1
FactGroup
.
mahConsumed
()
->
setRawValue
(
VehicleBatteryFactGroup
::
_mahConsumedUnavailable
);
}
else
{
_batteryFactGroup
.
mahConsumed
()
->
setRawValue
(
bat_status
.
current_consumed
);
_battery
1
FactGroup
.
mahConsumed
()
->
setRawValue
(
bat_status
.
current_consumed
);
}
int
cellCount
=
0
;
...
...
@@ -1321,15 +1325,15 @@ void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
cellCount
=
-
1
;
}
_batteryFactGroup
.
cellCount
()
->
setRawValue
(
cellCount
);
_battery
1
FactGroup
.
cellCount
()
->
setRawValue
(
cellCount
);
//-- Time remaining in seconds (0 means not supported)
_batteryFactGroup
.
timeRemaining
()
->
setRawValue
(
bat_status
.
time_remaining
);
_battery
1
FactGroup
.
timeRemaining
()
->
setRawValue
(
bat_status
.
time_remaining
);
//-- Battery charge state (0 means not supported)
if
(
bat_status
.
charge_state
<=
MAV_BATTERY_CHARGE_STATE_UNHEALTHY
)
{
_batteryFactGroup
.
chargeState
()
->
setRawValue
(
bat_status
.
charge_state
);
_battery
1
FactGroup
.
chargeState
()
->
setRawValue
(
bat_status
.
charge_state
);
}
else
{
_batteryFactGroup
.
chargeState
()
->
setRawValue
(
0
);
_battery
1
FactGroup
.
chargeState
()
->
setRawValue
(
0
);
}
//-- TODO: Somewhere, actions would be taken based on this chargeState:
// MAV_BATTERY_CHARGE_STATE_CRITICAL: Battery state is critical, return / abort immediately
...
...
src/Vehicle/Vehicle.h
View file @
61a50ca6
...
...
@@ -526,7 +526,8 @@ public:
Q_PROPERTY
(
Fact
*
hobbs
READ
hobbs
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
gps
READ
gpsFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
battery
READ
batteryFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
battery
READ
battery1FactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
battery2
READ
battery2FactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
wind
READ
windFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
vibration
READ
vibrationFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
temperature
READ
temperatureFactGroup
CONSTANT
)
...
...
@@ -816,7 +817,8 @@ public:
Fact
*
hobbs
(
void
)
{
return
&
_hobbsFact
;
}
FactGroup
*
gpsFactGroup
(
void
)
{
return
&
_gpsFactGroup
;
}
FactGroup
*
batteryFactGroup
(
void
)
{
return
&
_batteryFactGroup
;
}
FactGroup
*
battery1FactGroup
(
void
)
{
return
&
_battery1FactGroup
;
}
FactGroup
*
battery2FactGroup
(
void
)
{
return
&
_battery2FactGroup
;
}
FactGroup
*
windFactGroup
(
void
)
{
return
&
_windFactGroup
;
}
FactGroup
*
vibrationFactGroup
(
void
)
{
return
&
_vibrationFactGroup
;
}
FactGroup
*
temperatureFactGroup
(
void
)
{
return
&
_temperatureFactGroup
;
}
...
...
@@ -1294,7 +1296,8 @@ private:
Fact
_hobbsFact
;
VehicleGPSFactGroup
_gpsFactGroup
;
VehicleBatteryFactGroup
_batteryFactGroup
;
VehicleBatteryFactGroup
_battery1FactGroup
;
VehicleBatteryFactGroup
_battery2FactGroup
;
VehicleWindFactGroup
_windFactGroup
;
VehicleVibrationFactGroup
_vibrationFactGroup
;
VehicleTemperatureFactGroup
_temperatureFactGroup
;
...
...
@@ -1319,7 +1322,8 @@ private:
static
const
char
*
_hobbsFactName
;
static
const
char
*
_gpsFactGroupName
;
static
const
char
*
_batteryFactGroupName
;
static
const
char
*
_battery1FactGroupName
;
static
const
char
*
_battery2FactGroupName
;
static
const
char
*
_windFactGroupName
;
static
const
char
*
_vibrationFactGroupName
;
static
const
char
*
_temperatureFactGroupName
;
...
...
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