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
10840b7c
Commit
10840b7c
authored
Jun 03, 2013
by
dongfang
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Multiple altitudes and speeds signals. Simplified PFD
parent
13dcbfae
Changes
7
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
368 additions
and
167 deletions
+368
-167
UAS.cc
src/uas/UAS.cc
+84
-43
UAS.h
src/uas/UAS.h
+88
-51
UASInterface.h
src/uas/UASInterface.h
+46
-3
senseSoarMAV.cpp
src/uas/senseSoarMAV.cpp
+3
-3
PrimaryFlightDisplay.cpp
src/ui/PrimaryFlightDisplay.cpp
+97
-50
PrimaryFlightDisplay.h
src/ui/PrimaryFlightDisplay.h
+38
-17
UASQuickView.cc
src/ui/uas/UASQuickView.cc
+12
-0
No files found.
src/uas/UAS.cc
View file @
10840b7c
This diff is collapsed.
Click to expand it.
src/uas/UAS.h
View file @
10840b7c
This diff is collapsed.
Click to expand it.
src/uas/UASInterface.h
View file @
10840b7c
...
...
@@ -51,6 +51,40 @@ This file is part of the QGROUNDCONTROL project
#endif
#endif
enum
BatteryType
{
NICD
=
0
,
NIMH
=
1
,
LIION
=
2
,
LIPOLY
=
3
,
LIFE
=
4
,
AGZN
=
5
};
///< The type of battery used
enum
SpeedMeasurementSource
{
PRIMARY_SPEED
=
0
,
// ArduPlane: Measured airspeed or estimated airspeed. ArduCopter: Ground (XY) speed.
GROUNDSPEED_BY_UAV
=
1
,
// Ground speed as reported by UAS
GROUNDSPEED_BY_GPS
=
2
,
// Ground speed as calculated from received GPS velocity data
LOCAL_SPEED
=
3
};
///< For velocity data, the data source
enum
AltitudeMeasurementSource
{
PRIMARY_ALTITUDE
=
0
,
// ArduPlane: air and ground speed mix. This is the altitude used for navigastion.
BAROMETRIC_ALTITUDE
=
1
,
// Altitude is pressure altitude. Ardupilot reports no altitude purely by barometer,
// however when ALT_MIX==1, mix-altitude is purely barometric.
GPS_ALTITUDE
=
2
// GPS ASL altitude
};
///< For altitude data, the data source
// TODO!!! The different frames are probably represented elsewhere. There should really only
// be one set of frames. We also need to keep track of the home alt. somehow.
enum
AltitudeMeasurementFrame
{
ABSOLUTE
=
0
,
// Altitude is pressure altitude
ABOVE_HOME_POSITION
=
1
};
///< For altitude data, a reference frame
/**
* @brief Interface for all robots.
*
...
...
@@ -477,7 +511,7 @@ signals:
void
heartbeat
(
UASInterface
*
uas
);
void
attitudeChanged
(
UASInterface
*
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
usec
);
void
attitudeChanged
(
UASInterface
*
,
int
component
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
usec
);
void
attitude
SpeedChanged
(
int
uas
,
double
rollspeed
,
double
pitchspeed
,
double
yawspeed
,
quint64
usec
);
void
attitude
RotationRatesChanged
(
int
uas
,
double
rollrate
,
double
pitchrate
,
double
yawrate
,
quint64
usec
);
void
attitudeThrustSetPointChanged
(
UASInterface
*
,
double
rollDesired
,
double
pitchDesired
,
double
yawDesired
,
double
thrustDesired
,
quint64
usec
);
/** @brief The MAV set a new setpoint in the local (not body) NED X, Y, Z frame */
void
positionSetPointsChanged
(
int
uasid
,
float
xDesired
,
float
yDesired
,
float
zDesired
,
float
yawDesired
,
quint64
usec
);
...
...
@@ -486,10 +520,19 @@ signals:
void
localPositionChanged
(
UASInterface
*
,
double
x
,
double
y
,
double
z
,
quint64
usec
);
void
localPositionChanged
(
UASInterface
*
,
int
component
,
double
x
,
double
y
,
double
z
,
quint64
usec
);
void
globalPositionChanged
(
UASInterface
*
,
double
lat
,
double
lon
,
double
alt
,
quint64
usec
);
void
altitudeChanged
(
int
uasid
,
double
altitude
);
void
altitudeChanged
(
UASInterface
*
,
AltitudeMeasurementSource
source
,
double
altitude
,
quint64
usec
);
/** @brief Update the status of one satellite used for localization */
void
gpsSatelliteStatusChanged
(
int
uasid
,
int
satid
,
float
azimuth
,
float
direction
,
float
snr
,
bool
used
);
void
speedChanged
(
UASInterface
*
,
double
x
,
double
y
,
double
z
,
quint64
usec
);
// The horizontal speed (a scalar)
void
speedChanged
(
UASInterface
*
,
SpeedMeasurementSource
source
,
double
speed
,
quint64
usec
);
// The vertical speed (a scalar)
void
climbRateChanged
(
UASInterface
*
,
AltitudeMeasurementSource
source
,
double
speed
,
quint64
usec
);
// Consider adding a MAV_FRAME parameter to this; could help specifying what the 3 scalars are.
void
velocityChanged
(
UASInterface
*
,
MAV_FRAME
frame
,
double
vx
,
double
vy
,
double
vz
,
quint64
usec
);
void
navigationControllerErrorsChanged
(
UASInterface
*
,
double
altitudeError
,
double
speedError
,
double
xtrackError
);
void
imageStarted
(
int
imgid
,
int
width
,
int
height
,
int
depth
,
int
channels
);
void
imageDataReceived
(
int
imgid
,
const
unsigned
char
*
imageData
,
int
length
,
int
startIndex
);
/** @brief Emit the new system type */
...
...
src/uas/senseSoarMAV.cpp
View file @
10840b7c
...
...
@@ -41,7 +41,7 @@ void senseSoarMAV::receiveMessage(LinkInterface *link, mavlink_message_t message
emit
valueChanged
(
uasId
,
"rollspeed"
,
"rad/s"
,
this
->
m_rotVel
[
0
],
time
);
emit
valueChanged
(
uasId
,
"pitchspeed"
,
"rad/s"
,
this
->
m_rotVel
[
1
],
time
);
emit
valueChanged
(
uasId
,
"yawspeed"
,
"rad/s"
,
this
->
m_rotVel
[
2
],
time
);
emit
attitudeSpeed
Changed
(
uasId
,
this
->
m_rotVel
[
0
],
this
->
m_rotVel
[
1
],
this
->
m_rotVel
[
2
],
time
);
emit
attitudeRotationRates
Changed
(
uasId
,
this
->
m_rotVel
[
0
],
this
->
m_rotVel
[
1
],
this
->
m_rotVel
[
2
],
time
);
break
;
}
case
MAVLINK_MSG_ID_LLC_OUT
:
// low level controller output
...
...
@@ -62,7 +62,7 @@ void senseSoarMAV::receiveMessage(LinkInterface *link, mavlink_message_t message
mavlink_obs_air_temp_t
airTMsg
;
mavlink_msg_obs_air_temp_decode
(
&
message
,
&
airTMsg
);
quint64
time
=
getUnixTime
();
emit
valueChanged
(
uasId
,
"Air Temp"
,
""
,
airTMsg
.
airT
,
time
);
emit
valueChanged
(
uasId
,
"Air Temp"
,
"
°
"
,
airTMsg
.
airT
,
time
);
break
;
}
case
MAVLINK_MSG_ID_OBS_AIR_VELOCITY
:
...
...
@@ -211,4 +211,4 @@ void senseSoarMAV::quat2euler(const double *quat, double &roll, double &pitch, d
pitch
=
std
::
asin
(
qMax
(
-
1.0
,
qMin
(
1.0
,
2
*
(
quat
[
0
]
*
quat
[
2
]
-
quat
[
1
]
*
quat
[
3
]))));
yaw
=
std
::
atan2
(
2
*
(
quat
[
1
]
*
quat
[
2
]
+
quat
[
0
]
*
quat
[
3
]),
quat
[
0
]
*
quat
[
0
]
+
quat
[
1
]
*
quat
[
1
]
-
quat
[
2
]
*
quat
[
2
]
-
quat
[
3
]
*
quat
[
3
]);
return
;
}
\ No newline at end of file
}
src/ui/PrimaryFlightDisplay.cpp
View file @
10840b7c
This diff is collapsed.
Click to expand it.
src/ui/PrimaryFlightDisplay.h
View file @
10840b7c
...
...
@@ -106,8 +106,12 @@ public slots:
void
updateAttitude
(
UASInterface
*
uas
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
timestamp
);
/** @brief Attitude from one specific component / redundant autopilot */
void
updateAttitude
(
UASInterface
*
uas
,
int
component
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
timestamp
);
// void updateAttitudeThrustSetPoint(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec);
void
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
);
void
updateSpeed
(
UASInterface
*
uas
,
SpeedMeasurementSource
source
,
double
speed
,
quint64
timstamp
);
void
updateClimbRate
(
UASInterface
*
uas
,
AltitudeMeasurementSource
source
,
double
altitude
,
quint64
timestamp
);
void
updateAltitude
(
UASInterface
*
uas
,
AltitudeMeasurementSource
source
,
double
altitude
,
quint64
timestamp
);
/** @brief Set the currently monitored UAS */
virtual
void
setActiveUAS
(
UASInterface
*
uas
);
protected:
enum
Layout
{
...
...
@@ -136,23 +140,34 @@ protected:
// dongfang: We have no context menu. Viewonly.
// void contextMenuEvent (QContextMenuEvent* event);
protected:
// dongfang: What is that?
// dongfang: OK it's for UI interaction. Presently, there is none.
void
createActions
();
public
slots
:
/** @brief Set the currently monitored UAS */
virtual
void
setActiveUAS
(
UASInterface
*
uas
);
protected
slots
:
signals:
void
visibilityChanged
(
bool
visible
);
private:
//void prepareTransform(QPainter& painter, qreal width, qreal height);
//void transformToGlobalSystem(QPainter& painter, qreal width, qreal height, float roll, float pitch);
enum
AltimeterMode
{
PRIMARY_MAIN_GPS_SUB
,
// Show the primary alt. on tape and GPS as extra info
GPS_MAIN
// Show GPS on tape and no extra info
};
enum
AltimeterFrame
{
ASL
,
// Show ASL altitudes (plane pilots' normal preference)
RELATIVE_TO_HOME
// Show relative-to-home altitude (copter pilots)
};
enum
SpeedMode
{
PRIMARY_MAIN_GROUND_SUB
,
// Show primary speed (often airspeed) on tape and groundspeed as extra
GROUND_MAIN
// Show groundspeed on tape and no extra info
};
/*
* There are at least these differences between airplane and copter PDF view:
* - Airplane show absolute altutude in altimeter, copter shows relative to home
*/
bool
isAirplane
();
void
drawTextCenter
(
QPainter
&
painter
,
QString
text
,
float
fontSize
,
float
x
,
float
y
);
void
drawTextLeftCenter
(
QPainter
&
painter
,
QString
text
,
float
fontSize
,
float
x
,
float
y
);
...
...
@@ -167,8 +182,8 @@ private:
void
drawAICompassDisk
(
QPainter
&
painter
,
QRectF
area
,
float
halfspan
);
void
drawSeparateCompassDisk
(
QPainter
&
painter
,
QRectF
area
);
void
drawAltimeter
(
QPainter
&
painter
,
QRectF
area
,
float
altitude
,
float
max
Altitude
,
float
vv
);
void
drawVelocityMeter
(
QPainter
&
painter
,
QRectF
area
);
void
drawAltimeter
(
QPainter
&
painter
,
QRectF
area
,
float
altitude
,
float
secondary
Altitude
,
float
vv
);
void
drawVelocityMeter
(
QPainter
&
painter
,
QRectF
area
,
float
speed
,
float
secondarySpeed
);
void
fillInstrumentBackground
(
QPainter
&
painter
,
QRectF
edge
);
void
fillInstrumentOpagueBackground
(
QPainter
&
painter
,
QRectF
edge
);
void
drawInstrumentBackground
(
QPainter
&
painter
,
QRectF
edge
);
...
...
@@ -184,21 +199,27 @@ private:
UASInterface
*
uas
;
///< The uas currently monitored
AltimeterMode
altimeterMode
;
AltimeterFrame
altimeterFrame
;
SpeedMode
speedMode
;
bool
didReceivePrimaryAltitude
;
bool
didReceivePrimarySpeed
;
float
roll
;
float
pitch
;
float
heading
;
// APM: GPS and baro mix. From the GLOBAL_POSITION_INT or VFR_HUD messages.
float
aboveASLAltitude
;
float
primaryAltitude
;
float
GPSAltitude
;
// APM: GPS and baro mix above home (GPS) altitude. This value comes from the GLOBAL_POSITION_INT message.
// Do !!!NOT!!! ever do altitude calculations at the ground station. There are enough pitfalls already.
//
The MP "set home altitude" button will not be repeated here if it did that
.
//
If the MP "set home altitude" button is migrated to here, it must set the UAS home altitude, not a GS-local one
.
float
aboveHomeAltitude
;
float
primarySpeed
;
float
groundspeed
;
float
airspeed
;
float
verticalVelocity
;
Layout
layout
;
// The display layout.
...
...
src/ui/uas/UASQuickView.cc
View file @
10840b7c
...
...
@@ -73,6 +73,18 @@ UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent)
uasPropertyToLabelMap
[
"distToWaypoint"
]
=
item
;
}
{
QAction
*
action
=
new
QAction
(
"bearingToWaypoint"
,
this
);
action
->
setCheckable
(
true
);
action
->
setChecked
(
true
);
connect
(
action
,
SIGNAL
(
toggled
(
bool
)),
this
,
SLOT
(
actionTriggered
(
bool
)));
this
->
addAction
(
action
);
UASQuickViewItem
*
item
=
new
UASQuickViewItem
(
this
);
item
->
setTitle
(
"bearingToWaypoint"
);
ui
.
verticalLayout
->
addWidget
(
item
);
uasPropertyToLabelMap
[
"bearingToWaypoint"
]
=
item
;
}
updateTimer
=
new
QTimer
(
this
);
connect
(
updateTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
updateTimerTick
()));
updateTimer
->
start
(
1000
);
...
...
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