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
7cb7efae
Commit
7cb7efae
authored
Jun 09, 2013
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'master' of github.com:dongfang/qgroundcontrol into hud
parents
e79b49fd
c6a96bf7
Changes
10
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
138 additions
and
67 deletions
+138
-67
UAS.cc
src/uas/UAS.cc
+12
-14
UAS.h
src/uas/UAS.h
+3
-4
UASInterface.h
src/uas/UASInterface.h
+8
-4
HSIDisplay.cc
src/ui/HSIDisplay.cc
+2
-2
HUD.cc
src/ui/HUD.cc
+2
-2
PrimaryFlightDisplay.cpp
src/ui/PrimaryFlightDisplay.cpp
+92
-35
PrimaryFlightDisplay.h
src/ui/PrimaryFlightDisplay.h
+16
-3
SlugsDataSensorView.cc
src/ui/SlugsDataSensorView.cc
+1
-1
UASControlParameters.cpp
src/ui/uas/UASControlParameters.cpp
+1
-1
UASView.cc
src/ui/uas/UASView.cc
+1
-1
No files found.
src/uas/UAS.cc
View file @
7cb7efae
...
@@ -711,14 +711,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -711,14 +711,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
attitudeChanged
(
this
,
getRoll
(),
getPitch
(),
getYaw
(),
time
);
emit
attitudeChanged
(
this
,
getRoll
(),
getPitch
(),
getYaw
(),
time
);
}
}
// dongfang: For APM, this altitude is the mix altitude[m]
// The primary altitude is the one that the UAV uses for navigation.
emit
altitudeChanged
(
this
,
PRIMARY_ALTITUDE
,
hud
.
alt
,
time
);
// We assume! that the HUD message reports that as altitude.
emit
primaryAltitudeChanged
(
this
,
hud
.
alt
,
time
);
// This makes the lateral velocity zero when it might really not be, problematic.
emit
primarySpeedChanged
(
this
,
hud
.
airspeed
,
time
);
// emit speedChanged(this, PRIMARY_SPEED, hud.airspeed, 0.0f, hud.climb, time);
emit
gpsSpeedChanged
(
this
,
hud
.
groundspeed
,
time
);
emit
speedChanged
(
this
,
PRIMARY_SPEED
,
hud
.
airspeed
,
time
);
emit
climbRateChanged
(
this
,
hud
.
climb
,
time
);
emit
speedChanged
(
this
,
GROUNDSPEED_BY_UAV
,
hud
.
groundspeed
,
time
);
emit
climbRateChanged
(
this
,
BAROMETRIC_ALTITUDE
,
hud
.
groundspeed
,
time
);
}
}
break
;
break
;
case
MAVLINK_MSG_ID_LOCAL_POSITION_NED
:
case
MAVLINK_MSG_ID_LOCAL_POSITION_NED
:
...
@@ -739,9 +738,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -739,9 +738,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
localZ
=
pos
.
z
;
localZ
=
pos
.
z
;
// Emit
// Emit
emit
localPositionChanged
(
this
,
pos
.
x
,
pos
.
y
,
pos
.
z
,
time
);
emit
localPositionChanged
(
this
,
pos
.
x
,
pos
.
y
,
pos
.
z
,
time
);
emit
velocityChanged
(
this
,
MAV_FRAME_LOCAL_NED
,
pos
.
vx
,
pos
.
vy
,
pos
.
vz
,
time
);
emit
velocityChanged
_NED
(
this
,
pos
.
vx
,
pos
.
vy
,
pos
.
vz
,
time
);
// Set internal state
// Set internal state
if
(
!
positionLock
)
{
if
(
!
positionLock
)
{
...
@@ -786,12 +784,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -786,12 +784,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
globalPositionChanged
(
this
,
getLatitude
(),
getLongitude
(),
getAltitude
(),
time
);
emit
globalPositionChanged
(
this
,
getLatitude
(),
getLongitude
(),
getAltitude
(),
time
);
// dongfang: The altitude is GPS altitude. Bugger. It needs to be changed to primary.
// dongfang: The altitude is GPS altitude. Bugger. It needs to be changed to primary.
emit
altitudeChanged
(
this
,
GPS_ALTITUDE
,
getAltitude
(),
time
);
emit
gpsAltitudeChanged
(
this
,
getAltitude
(),
time
);
// We had some frame mess here, global and local axes were mixed.
// We had some frame mess here, global and local axes were mixed.
emit
velocityChanged
(
this
,
MAV_FRAME_GLOBAL
,
speedX
,
speedY
,
speedZ
,
time
);
emit
velocityChanged
_NED
(
this
,
speedX
,
speedY
,
speedZ
,
time
);
double
groundspeed
=
qSqrt
(
speedX
*
speedX
+
speedY
*
speedY
);
double
groundspeed
=
qSqrt
(
speedX
*
speedX
+
speedY
*
speedY
);
emit
speedChanged
(
this
,
GROUNDSPEED_BY_GPS
,
groundspeed
,
time
);
emit
gpsSpeedChanged
(
this
,
groundspeed
,
time
);
// Set internal state
// Set internal state
if
(
!
positionLock
)
if
(
!
positionLock
)
...
@@ -838,7 +836,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -838,7 +836,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
setLongitude
(
longitude_gps
);
setLongitude
(
longitude_gps
);
setAltitude
(
altitude_gps
);
setAltitude
(
altitude_gps
);
emit
globalPositionChanged
(
this
,
getLatitude
(),
getLongitude
(),
getAltitude
(),
time
);
emit
globalPositionChanged
(
this
,
getLatitude
(),
getLongitude
(),
getAltitude
(),
time
);
emit
altitudeChanged
(
this
,
GPS_ALTITUDE
,
getAltitude
(),
time
);
emit
gpsAltitudeChanged
(
this
,
getAltitude
(),
time
);
}
}
positionLock
=
true
;
positionLock
=
true
;
...
@@ -853,7 +851,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -853,7 +851,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if
((
vel
<
1000000
)
&&
!
isnan
(
vel
)
&&
!
isinf
(
vel
))
if
((
vel
<
1000000
)
&&
!
isnan
(
vel
)
&&
!
isinf
(
vel
))
{
{
// TODO: Other sources also? Actually this condition does not quite belong here.
// TODO: Other sources also? Actually this condition does not quite belong here.
emit
speedChanged
(
this
,
GROUNDSPEED_BY_GPS
,
vel
,
time
);
emit
gpsSpeedChanged
(
this
,
vel
,
time
);
}
}
else
else
{
{
...
...
src/uas/UAS.h
View file @
7cb7efae
...
@@ -852,10 +852,9 @@ signals:
...
@@ -852,10 +852,9 @@ signals:
void
distToWaypointChanged
(
double
val
,
QString
name
);
void
distToWaypointChanged
(
double
val
,
QString
name
);
void
bearingToWaypointChanged
(
double
val
,
QString
name
);
void
bearingToWaypointChanged
(
double
val
,
QString
name
);
void
altitudeChanged
(
UASInterface
*
,
AltitudeMeasurementSource
source
,
double
altitude
,
quint64
usec
);
//void primaryAltitudeChanged(UASInterface*, double altitude, quint64 usec);
//void speedChanged(UASInterface*, SpeedMeasurementSource source, double speed, quint64 usec);
//void gpsAltitudeChanged(UASInterface*, double altitude, quint64 usec);
//void climbRateChanged(UASInterface*, AltitudeMeasurementSource source, double speed, quint64 usec);
//void velocityChanged_NED(UASInterface*, double vx, double vy, double vz, quint64 usec);
void
velocityChanged
(
UASInterface
*
,
MAV_FRAME
,
double
vx
,
double
vy
,
double
vz
,
quint64
usec
);
protected:
protected:
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
/** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
quint64
getUnixTime
(
quint64
time
=
0
);
quint64
getUnixTime
(
quint64
time
=
0
);
...
...
src/uas/UASInterface.h
View file @
7cb7efae
...
@@ -61,6 +61,7 @@ enum BatteryType
...
@@ -61,6 +61,7 @@ enum BatteryType
AGZN
=
5
AGZN
=
5
};
///< The type of battery used
};
///< The type of battery used
/*
enum SpeedMeasurementSource
enum SpeedMeasurementSource
{
{
PRIMARY_SPEED = 0, // ArduPlane: Measured airspeed or estimated airspeed. ArduCopter: Ground (XY) speed.
PRIMARY_SPEED = 0, // ArduPlane: Measured airspeed or estimated airspeed. ArduCopter: Ground (XY) speed.
...
@@ -84,6 +85,7 @@ enum AltitudeMeasurementFrame
...
@@ -84,6 +85,7 @@ enum AltitudeMeasurementFrame
ABSOLUTE = 0, // Altitude is pressure altitude
ABSOLUTE = 0, // Altitude is pressure altitude
ABOVE_HOME_POSITION = 1
ABOVE_HOME_POSITION = 1
}; ///< For altitude data, a reference frame
}; ///< For altitude data, a reference frame
*/
/**
/**
* @brief Interface for all robots.
* @brief Interface for all robots.
...
@@ -520,16 +522,18 @@ signals:
...
@@ -520,16 +522,18 @@ signals:
void
localPositionChanged
(
UASInterface
*
,
double
x
,
double
y
,
double
z
,
quint64
usec
);
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
localPositionChanged
(
UASInterface
*
,
int
component
,
double
x
,
double
y
,
double
z
,
quint64
usec
);
void
globalPositionChanged
(
UASInterface
*
,
double
lat
,
double
lon
,
double
alt
,
quint64
usec
);
void
globalPositionChanged
(
UASInterface
*
,
double
lat
,
double
lon
,
double
alt
,
quint64
usec
);
void
altitudeChanged
(
UASInterface
*
,
AltitudeMeasurementSource
source
,
double
altitude
,
quint64
usec
);
void
primaryAltitudeChanged
(
UASInterface
*
,
double
altitude
,
quint64
usec
);
void
gpsAltitudeChanged
(
UASInterface
*
,
double
altitude
,
quint64
usec
);
/** @brief Update the status of one satellite used for localization */
/** @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
gpsSatelliteStatusChanged
(
int
uasid
,
int
satid
,
float
azimuth
,
float
direction
,
float
snr
,
bool
used
);
// The horizontal speed (a scalar)
// The horizontal speed (a scalar)
void
speedChanged
(
UASInterface
*
,
SpeedMeasurementSource
source
,
double
speed
,
quint64
usec
);
void
primarySpeedChanged
(
UASInterface
*
,
double
speed
,
quint64
usec
);
void
gpsSpeedChanged
(
UASInterface
*
,
double
speed
,
quint64
usec
);
// The vertical speed (a scalar)
// The vertical speed (a scalar)
void
climbRateChanged
(
UASInterface
*
,
AltitudeMeasurementSource
source
,
double
speed
,
quint64
usec
);
void
climbRateChanged
(
UASInterface
*
,
double
climb
,
quint64
usec
);
// Consider adding a MAV_FRAME parameter to this; could help specifying what the 3 scalars are.
// 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
velocityChanged
_NED
(
UASInterface
*
,
double
vx
,
double
vy
,
double
vz
,
quint64
usec
);
void
navigationControllerErrorsChanged
(
UASInterface
*
,
double
altitudeError
,
double
speedError
,
double
xtrackError
);
void
navigationControllerErrorsChanged
(
UASInterface
*
,
double
altitudeError
,
double
speedError
,
double
xtrackError
);
...
...
src/ui/HSIDisplay.cc
View file @
7cb7efae
...
@@ -867,7 +867,7 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
...
@@ -867,7 +867,7 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
disconnect
(
this
->
uas
,
SIGNAL
(
attitudeThrustSetPointChanged
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitudeSetpoints
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
attitudeThrustSetPointChanged
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitudeSetpoints
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
positionSetPointsChanged
(
int
,
float
,
float
,
float
,
float
,
quint64
)),
this
,
SLOT
(
updatePositionSetpoints
(
int
,
float
,
float
,
float
,
float
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
positionSetPointsChanged
(
int
,
float
,
float
,
float
,
float
,
quint64
)),
this
,
SLOT
(
updatePositionSetpoints
(
int
,
float
,
float
,
float
,
float
,
quint64
)));
disconnect
(
uas
,
SIGNAL
(
userPositionSetPointsChanged
(
int
,
float
,
float
,
float
,
float
)),
this
,
SLOT
(
updateUserPositionSetpoints
(
int
,
float
,
float
,
float
,
float
)));
disconnect
(
uas
,
SIGNAL
(
userPositionSetPointsChanged
(
int
,
float
,
float
,
float
,
float
)),
this
,
SLOT
(
updateUserPositionSetpoints
(
int
,
float
,
float
,
float
,
float
)));
disconnect
(
this
->
uas
,
SIGNAL
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
velocityChanged_NED
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitude
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitude
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
attitudeControlEnabled
(
bool
)),
this
,
SLOT
(
updateAttitudeControllerEnabled
(
bool
)));
disconnect
(
this
->
uas
,
SIGNAL
(
attitudeControlEnabled
(
bool
)),
this
,
SLOT
(
updateAttitudeControllerEnabled
(
bool
)));
...
@@ -898,7 +898,7 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
...
@@ -898,7 +898,7 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
connect
(
uas
,
SIGNAL
(
attitudeThrustSetPointChanged
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitudeSetpoints
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
attitudeThrustSetPointChanged
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitudeSetpoints
(
UASInterface
*
,
double
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
positionSetPointsChanged
(
int
,
float
,
float
,
float
,
float
,
quint64
)),
this
,
SLOT
(
updatePositionSetpoints
(
int
,
float
,
float
,
float
,
float
,
quint64
)));
connect
(
uas
,
SIGNAL
(
positionSetPointsChanged
(
int
,
float
,
float
,
float
,
float
,
quint64
)),
this
,
SLOT
(
updatePositionSetpoints
(
int
,
float
,
float
,
float
,
float
,
quint64
)));
connect
(
uas
,
SIGNAL
(
userPositionSetPointsChanged
(
int
,
float
,
float
,
float
,
float
)),
this
,
SLOT
(
updateUserPositionSetpoints
(
int
,
float
,
float
,
float
,
float
)));
connect
(
uas
,
SIGNAL
(
userPositionSetPointsChanged
(
int
,
float
,
float
,
float
,
float
)),
this
,
SLOT
(
updateUserPositionSetpoints
(
int
,
float
,
float
,
float
,
float
)));
connect
(
uas
,
SIGNAL
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
velocityChanged_NED
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitude
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitude
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
attitudeControlEnabled
(
bool
)),
this
,
SLOT
(
updateAttitudeControllerEnabled
(
bool
)));
connect
(
uas
,
SIGNAL
(
attitudeControlEnabled
(
bool
)),
this
,
SLOT
(
updateAttitudeControllerEnabled
(
bool
)));
...
...
src/ui/HUD.cc
View file @
7cb7efae
...
@@ -270,7 +270,7 @@ void HUD::setActiveUAS(UASInterface* uas)
...
@@ -270,7 +270,7 @@ void HUD::setActiveUAS(UASInterface* uas)
disconnect
(
this
->
uas
,
SIGNAL
(
localPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateLocalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
localPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateLocalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
velocityChanged_NED
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
waypointSelected
(
int
,
int
)),
this
,
SLOT
(
selectWaypoint
(
int
,
int
)));
disconnect
(
this
->
uas
,
SIGNAL
(
waypointSelected
(
int
,
int
)),
this
,
SLOT
(
selectWaypoint
(
int
,
int
)));
// Try to disconnect the image link
// Try to disconnect the image link
...
@@ -293,7 +293,7 @@ void HUD::setActiveUAS(UASInterface* uas)
...
@@ -293,7 +293,7 @@ void HUD::setActiveUAS(UASInterface* uas)
connect
(
uas
,
SIGNAL
(
localPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateLocalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
localPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateLocalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
velocityChanged_NED
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
waypointSelected
(
int
,
int
)),
this
,
SLOT
(
selectWaypoint
(
int
,
int
)));
connect
(
uas
,
SIGNAL
(
waypointSelected
(
int
,
int
)),
this
,
SLOT
(
selectWaypoint
(
int
,
int
)));
// Try to connect the image link
// Try to connect the image link
...
...
src/ui/PrimaryFlightDisplay.cpp
View file @
7cb7efae
This diff is collapsed.
Click to expand it.
src/ui/PrimaryFlightDisplay.h
View file @
7cb7efae
...
@@ -58,6 +58,9 @@
...
@@ -58,6 +58,9 @@
#define COMPASS_DISK_MARKERWIDTH 0.2
#define COMPASS_DISK_MARKERWIDTH 0.2
#define COMPASS_DISK_MARKERHEIGHT 0.133
#define COMPASS_DISK_MARKERHEIGHT 0.133
#define CROSSTRACK_MAX 1000
#define CROSSTRACK_RADIUS 0.6
#define TAPE_GAUGES_TICKWIDTH_MAJOR 0.25
#define TAPE_GAUGES_TICKWIDTH_MAJOR 0.25
#define TAPE_GAUGES_TICKWIDTH_MINOR 0.15
#define TAPE_GAUGES_TICKWIDTH_MINOR 0.15
...
@@ -107,9 +110,13 @@ public slots:
...
@@ -107,9 +110,13 @@ public slots:
/** @brief Attitude from one specific component / redundant autopilot */
/** @brief Attitude from one specific component / redundant autopilot */
void
updateAttitude
(
UASInterface
*
uas
,
int
component
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
timestamp
);
void
updateAttitude
(
UASInterface
*
uas
,
int
component
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
timestamp
);
void
updateSpeed
(
UASInterface
*
uas
,
SpeedMeasurementSource
source
,
double
speed
,
quint64
timstamp
);
void
updatePrimarySpeed
(
UASInterface
*
uas
,
double
speed
,
quint64
timstamp
);
void
updateClimbRate
(
UASInterface
*
uas
,
AltitudeMeasurementSource
source
,
double
altitude
,
quint64
timestamp
);
void
updateGPSSpeed
(
UASInterface
*
uas
,
double
speed
,
quint64
timstamp
);
void
updateAltitude
(
UASInterface
*
uas
,
AltitudeMeasurementSource
source
,
double
altitude
,
quint64
timestamp
);
void
updateClimbRate
(
UASInterface
*
uas
,
double
altitude
,
quint64
timestamp
);
void
updatePrimaryAltitude
(
UASInterface
*
uas
,
double
altitude
,
quint64
timestamp
);
void
updateGPSAltitude
(
UASInterface
*
uas
,
double
altitude
,
quint64
timestamp
);
void
updateNavigationControllerErrors
(
UASInterface
*
uas
,
double
altitudeError
,
double
speedError
,
double
xtrackError
);
/** @brief Set the currently monitored UAS */
/** @brief Set the currently monitored UAS */
virtual
void
setActiveUAS
(
UASInterface
*
uas
);
virtual
void
setActiveUAS
(
UASInterface
*
uas
);
...
@@ -168,6 +175,7 @@ private:
...
@@ -168,6 +175,7 @@ private:
* - Airplane show absolute altutude in altimeter, copter shows relative to home
* - Airplane show absolute altutude in altimeter, copter shows relative to home
*/
*/
bool
isAirplane
();
bool
isAirplane
();
bool
shouldDisplayNavigationData
();
void
drawTextCenter
(
QPainter
&
painter
,
QString
text
,
float
fontSize
,
float
x
,
float
y
);
void
drawTextCenter
(
QPainter
&
painter
,
QString
text
,
float
fontSize
,
float
x
,
float
y
);
void
drawTextLeftCenter
(
QPainter
&
painter
,
QString
text
,
float
fontSize
,
float
x
,
float
y
);
void
drawTextLeftCenter
(
QPainter
&
painter
,
QString
text
,
float
fontSize
,
float
x
,
float
y
);
...
@@ -222,6 +230,11 @@ private:
...
@@ -222,6 +230,11 @@ private:
float
groundspeed
;
float
groundspeed
;
float
verticalVelocity
;
float
verticalVelocity
;
float
navigationAltitudeError
;
float
navigationSpeedError
;
float
navigationCrosstrackError
;
float
navigationTargetBearing
;
Layout
layout
;
// The display layout.
Layout
layout
;
// The display layout.
Style
style
;
// The AI style (tapes translusent or opague)
Style
style
;
// The AI style (tapes translusent or opague)
...
...
src/ui/SlugsDataSensorView.cc
View file @
7cb7efae
...
@@ -38,7 +38,7 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
...
@@ -38,7 +38,7 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
//connect standar messages
//connect standar messages
connect
(
slugsMav
,
SIGNAL
(
localPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugLocalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
localPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugLocalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugSpeedLocalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
velocityChanged_NED
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugSpeedLocalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugAttitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugAttitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugsGlobalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugsGlobalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
slugsGPSCogSog
(
int
,
double
,
double
)),
this
,
SLOT
(
slugsGPSCogSog
(
int
,
double
,
double
)));
connect
(
slugsMav
,
SIGNAL
(
slugsGPSCogSog
(
int
,
double
,
double
)),
this
,
SLOT
(
slugsGPSCogSog
(
int
,
double
,
double
)));
...
...
src/ui/uas/UASControlParameters.cpp
View file @
7cb7efae
...
@@ -93,7 +93,7 @@ void UASControlParameters::activeUasSet(UASInterface *uas)
...
@@ -93,7 +93,7 @@ void UASControlParameters::activeUasSet(UASInterface *uas)
{
{
if
(
uas
)
{
if
(
uas
)
{
connect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
velocityChanged_NED
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitude
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitude
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
modeChanged
(
int
,
QString
,
QString
)),
this
,
SLOT
(
updateMode
(
int
,
QString
,
QString
)));
connect
(
uas
,
SIGNAL
(
modeChanged
(
int
,
QString
,
QString
)),
this
,
SLOT
(
updateMode
(
int
,
QString
,
QString
)));
connect
(
uas
,
SIGNAL
(
thrustChanged
(
UASInterface
*
,
double
)),
this
,
SLOT
(
thrustChanged
(
UASInterface
*
,
double
))
);
connect
(
uas
,
SIGNAL
(
thrustChanged
(
UASInterface
*
,
double
)),
this
,
SLOT
(
thrustChanged
(
UASInterface
*
,
double
))
);
...
...
src/ui/uas/UASView.cc
View file @
7cb7efae
...
@@ -91,7 +91,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
...
@@ -91,7 +91,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
connect
(
uas
,
SIGNAL
(
thrustChanged
(
UASInterface
*
,
double
)),
this
,
SLOT
(
updateThrust
(
UASInterface
*
,
double
)));
connect
(
uas
,
SIGNAL
(
thrustChanged
(
UASInterface
*
,
double
)),
this
,
SLOT
(
updateThrust
(
UASInterface
*
,
double
)));
connect
(
uas
,
SIGNAL
(
localPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateLocalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
localPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateLocalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
velocityChanged_NED
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateSpeed
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
statusChanged
(
UASInterface
*
,
QString
,
QString
)),
this
,
SLOT
(
updateState
(
UASInterface
*
,
QString
,
QString
)));
connect
(
uas
,
SIGNAL
(
statusChanged
(
UASInterface
*
,
QString
,
QString
)),
this
,
SLOT
(
updateState
(
UASInterface
*
,
QString
,
QString
)));
connect
(
uas
,
SIGNAL
(
modeChanged
(
int
,
QString
,
QString
)),
this
,
SLOT
(
updateMode
(
int
,
QString
,
QString
)));
connect
(
uas
,
SIGNAL
(
modeChanged
(
int
,
QString
,
QString
)),
this
,
SLOT
(
updateMode
(
int
,
QString
,
QString
)));
connect
(
uas
,
SIGNAL
(
loadChanged
(
UASInterface
*
,
double
)),
this
,
SLOT
(
updateLoad
(
UASInterface
*
,
double
)));
connect
(
uas
,
SIGNAL
(
loadChanged
(
UASInterface
*
,
double
)),
this
,
SLOT
(
updateLoad
(
UASInterface
*
,
double
)));
...
...
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