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
a56a153d
Commit
a56a153d
authored
8 years ago
by
Don Gagne
Committed by
GitHub
8 years ago
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #4595 from bluerobotics/temperature
Put temperature readings in vehicle values widget
parents
7911dc29
ec0450ce
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
115 additions
and
4 deletions
+115
-4
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-0
TemperatureFact.json
src/Vehicle/TemperatureFact.json
+23
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+51
-0
Vehicle.h
src/Vehicle/Vehicle.h
+40
-4
No files found.
qgroundcontrol.qrc
View file @
a56a153d
...
...
@@ -187,6 +187,7 @@
<file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file>
<file alias="Survey.FactMetaData.json">src/MissionManager/Survey.FactMetaData.json</file>
<file alias="USBBoardInfo.json">src/comm/USBBoardInfo.json</file>
<file alias="Vehicle/TemperatureFact.json">src/Vehicle/TemperatureFact.json</file>
</qresource>
<qresource prefix="/MockLink">
<file alias="APMArduCopterMockLink.params">src/comm/APMArduCopterMockLink.params</file>
...
...
This diff is collapsed.
Click to expand it.
src/Vehicle/TemperatureFact.json
0 → 100644
View file @
a56a153d
[
{
"name"
:
"temperature1"
,
"shortDescription"
:
"Temperature (1)"
,
"type"
:
"double"
,
"decimalPlaces"
:
2
,
"units"
:
"C"
},
{
"name"
:
"temperature2"
,
"shortDescription"
:
"Temperature (2)"
,
"type"
:
"double"
,
"decimalPlaces"
:
2
,
"units"
:
"C"
},
{
"name"
:
"temperature3"
,
"shortDescription"
:
"Temperature (3)"
,
"type"
:
"double"
,
"decimalPlaces"
:
2
,
"units"
:
"C"
}
]
This diff is collapsed.
Click to expand it.
src/Vehicle/Vehicle.cc
View file @
a56a153d
...
...
@@ -54,6 +54,7 @@ const char* Vehicle::_gpsFactGroupName = "gps";
const
char
*
Vehicle
::
_batteryFactGroupName
=
"battery"
;
const
char
*
Vehicle
::
_windFactGroupName
=
"wind"
;
const
char
*
Vehicle
::
_vibrationFactGroupName
=
"vibration"
;
const
char
*
Vehicle
::
_temperatureFactGroupName
=
"temperature"
;
const
int
Vehicle
::
_lowBatteryAnnounceRepeatMSecs
=
30
*
1000
;
...
...
@@ -149,6 +150,7 @@ Vehicle::Vehicle(LinkInterface* link,
,
_batteryFactGroup
(
this
)
,
_windFactGroup
(
this
)
,
_vibrationFactGroup
(
this
)
,
_temperatureFactGroup
(
this
)
{
_addLink
(
link
);
...
...
@@ -343,6 +345,7 @@ void Vehicle::_commonInit(void)
_addFactGroup
(
&
_batteryFactGroup
,
_batteryFactGroupName
);
_addFactGroup
(
&
_windFactGroup
,
_windFactGroupName
);
_addFactGroup
(
&
_vibrationFactGroup
,
_vibrationFactGroupName
);
_addFactGroup
(
&
_temperatureFactGroup
,
_temperatureFactGroupName
);
}
Vehicle
::~
Vehicle
()
...
...
@@ -561,6 +564,15 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case
MAVLINK_MSG_ID_VFR_HUD
:
_handleVfrHud
(
message
);
break
;
case
MAVLINK_MSG_ID_SCALED_PRESSURE
:
_handleScaledPressure
(
message
);
break
;
case
MAVLINK_MSG_ID_SCALED_PRESSURE2
:
_handleScaledPressure2
(
message
);
break
;
case
MAVLINK_MSG_ID_SCALED_PRESSURE3
:
_handleScaledPressure3
(
message
);
break
;
// Following are ArduPilot dialect messages
...
...
@@ -990,6 +1002,24 @@ void Vehicle::_handleRCChannelsRaw(mavlink_message_t& message)
emit
rcChannelsChanged
(
channelCount
,
pwmValues
);
}
void
Vehicle
::
_handleScaledPressure
(
mavlink_message_t
&
message
)
{
mavlink_scaled_pressure_t
pressure
;
mavlink_msg_scaled_pressure_decode
(
&
message
,
&
pressure
);
_temperatureFactGroup
.
temperature1
()
->
setRawValue
(
pressure
.
temperature
/
100.0
);
}
void
Vehicle
::
_handleScaledPressure2
(
mavlink_message_t
&
message
)
{
mavlink_scaled_pressure2_t
pressure
;
mavlink_msg_scaled_pressure2_decode
(
&
message
,
&
pressure
);
_temperatureFactGroup
.
temperature2
()
->
setRawValue
(
pressure
.
temperature
/
100.0
);
}
void
Vehicle
::
_handleScaledPressure3
(
mavlink_message_t
&
message
)
{
mavlink_scaled_pressure3_t
pressure
;
mavlink_msg_scaled_pressure3_decode
(
&
message
,
&
pressure
);
_temperatureFactGroup
.
temperature3
()
->
setRawValue
(
pressure
.
temperature
/
100.0
);
}
bool
Vehicle
::
_containsLink
(
LinkInterface
*
link
)
{
return
_links
.
contains
(
link
);
...
...
@@ -2394,3 +2424,24 @@ VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent)
_yAxisFact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
_zAxisFact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
}
const
char
*
VehicleTemperatureFactGroup
::
_temperature1FactName
=
"temperature1"
;
const
char
*
VehicleTemperatureFactGroup
::
_temperature2FactName
=
"temperature2"
;
const
char
*
VehicleTemperatureFactGroup
::
_temperature3FactName
=
"temperature3"
;
VehicleTemperatureFactGroup
::
VehicleTemperatureFactGroup
(
QObject
*
parent
)
:
FactGroup
(
1000
,
":/json/Vehicle/TemperatureFact.json"
,
parent
)
,
_temperature1Fact
(
0
,
_temperature1FactName
,
FactMetaData
::
valueTypeDouble
)
,
_temperature2Fact
(
0
,
_temperature2FactName
,
FactMetaData
::
valueTypeDouble
)
,
_temperature3Fact
(
0
,
_temperature3FactName
,
FactMetaData
::
valueTypeDouble
)
{
_addFact
(
&
_temperature1Fact
,
_temperature1FactName
);
_addFact
(
&
_temperature2Fact
,
_temperature2FactName
);
_addFact
(
&
_temperature3Fact
,
_temperature3FactName
);
// Start out as not available "--.--"
_temperature1Fact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
_temperature2Fact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
_temperature3Fact
.
setRawValue
(
std
::
numeric_limits
<
float
>::
quiet_NaN
());
}
This diff is collapsed.
Click to expand it.
src/Vehicle/Vehicle.h
View file @
a56a153d
...
...
@@ -185,6 +185,35 @@ private:
Fact
_cellCountFact
;
};
class
VehicleTemperatureFactGroup
:
public
FactGroup
{
Q_OBJECT
public:
VehicleTemperatureFactGroup
(
QObject
*
parent
=
NULL
);
Q_PROPERTY
(
Fact
*
temperature1
READ
temperature1
CONSTANT
)
Q_PROPERTY
(
Fact
*
temperature2
READ
temperature2
CONSTANT
)
Q_PROPERTY
(
Fact
*
temperature3
READ
temperature3
CONSTANT
)
Fact
*
temperature1
(
void
)
{
return
&
_temperature1Fact
;
}
Fact
*
temperature2
(
void
)
{
return
&
_temperature2Fact
;
}
Fact
*
temperature3
(
void
)
{
return
&
_temperature3Fact
;
}
static
const
char
*
_temperature1FactName
;
static
const
char
*
_temperature2FactName
;
static
const
char
*
_temperature3FactName
;
static
const
char
*
_settingsGroup
;
static
const
double
_temperatureUnavailable
;
private:
Fact
_temperature1Fact
;
Fact
_temperature2Fact
;
Fact
_temperature3Fact
;
};
class
Vehicle
:
public
FactGroup
{
Q_OBJECT
...
...
@@ -306,10 +335,11 @@ public:
Q_PROPERTY
(
Fact
*
altitudeRelative
READ
altitudeRelative
CONSTANT
)
Q_PROPERTY
(
Fact
*
altitudeAMSL
READ
altitudeAMSL
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
gps
READ
gpsFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
battery
READ
batteryFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
wind
READ
windFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
vibration
READ
vibrationFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
gps
READ
gpsFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
battery
READ
batteryFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
wind
READ
windFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
vibration
READ
vibrationFactGroup
CONSTANT
)
Q_PROPERTY
(
FactGroup
*
temperature
READ
temperatureFactGroup
CONSTANT
)
Q_PROPERTY
(
int
firmwareMajorVersion
READ
firmwareMajorVersion
NOTIFY
firmwareMajorVersionChanged
)
Q_PROPERTY
(
int
firmwareMinorVersion
READ
firmwareMinorVersion
NOTIFY
firmwareMinorVersionChanged
)
...
...
@@ -560,6 +590,7 @@ public:
FactGroup
*
batteryFactGroup
(
void
)
{
return
&
_batteryFactGroup
;
}
FactGroup
*
windFactGroup
(
void
)
{
return
&
_windFactGroup
;
}
FactGroup
*
vibrationFactGroup
(
void
)
{
return
&
_vibrationFactGroup
;
}
FactGroup
*
temperatureFactGroup
(
void
)
{
return
&
_temperatureFactGroup
;
}
void
setConnectionLostEnabled
(
bool
connectionLostEnabled
);
...
...
@@ -754,6 +785,9 @@ private:
void
_handleGlobalPositionInt
(
mavlink_message_t
&
message
);
void
_handleAltitude
(
mavlink_message_t
&
message
);
void
_handleVfrHud
(
mavlink_message_t
&
message
);
void
_handleScaledPressure
(
mavlink_message_t
&
message
);
void
_handleScaledPressure2
(
mavlink_message_t
&
message
);
void
_handleScaledPressure3
(
mavlink_message_t
&
message
);
void
_missionManagerError
(
int
errorCode
,
const
QString
&
errorMsg
);
void
_geoFenceManagerError
(
int
errorCode
,
const
QString
&
errorMsg
);
void
_rallyPointManagerError
(
int
errorCode
,
const
QString
&
errorMsg
);
...
...
@@ -924,6 +958,7 @@ private:
VehicleBatteryFactGroup
_batteryFactGroup
;
VehicleWindFactGroup
_windFactGroup
;
VehicleVibrationFactGroup
_vibrationFactGroup
;
VehicleTemperatureFactGroup
_temperatureFactGroup
;
static
const
char
*
_rollFactName
;
static
const
char
*
_pitchFactName
;
...
...
@@ -938,6 +973,7 @@ private:
static
const
char
*
_batteryFactGroupName
;
static
const
char
*
_windFactGroupName
;
static
const
char
*
_vibrationFactGroupName
;
static
const
char
*
_temperatureFactGroupName
;
static
const
int
_vehicleUIUpdateRateMSecs
=
100
;
...
...
This diff is collapsed.
Click to expand it.
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