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
d779e7f1
Commit
d779e7f1
authored
Dec 09, 2012
by
Bryant
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed compilation warnings with regards to unused variables and uninitialized variables.
parent
975f6fb5
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
31 additions
and
42 deletions
+31
-42
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+11
-20
QGCFlightGearLink.cc
src/comm/QGCFlightGearLink.cc
+9
-6
UAS.cc
src/uas/UAS.cc
+3
-2
HSIDisplay.cc
src/ui/HSIDisplay.cc
+6
-5
HUD.cc
src/ui/HUD.cc
+1
-0
MAVLinkDecoder.cc
src/ui/MAVLinkDecoder.cc
+1
-5
UASView.cc
src/ui/uas/UASView.cc
+0
-4
No files found.
src/comm/MAVLinkSimulationLink.cc
View file @
d779e7f1
...
@@ -207,7 +207,6 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -207,7 +207,6 @@ void MAVLinkSimulationLink::mainloop()
uint8_t
buffer
[
MAVLINK_MAX_PACKET_LEN
];
uint8_t
buffer
[
MAVLINK_MAX_PACKET_LEN
];
int
bufferlength
;
int
bufferlength
;
int
messageSize
;
mavlink_message_t
msg
;
mavlink_message_t
msg
;
// Timers
// Timers
...
@@ -458,7 +457,7 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -458,7 +457,7 @@ void MAVLinkSimulationLink::mainloop()
chan
.
chan7_raw
=
(
chan
.
chan4_raw
+
chan
.
chan2_raw
)
/
2.0
f
;
chan
.
chan7_raw
=
(
chan
.
chan4_raw
+
chan
.
chan2_raw
)
/
2.0
f
;
chan
.
chan8_raw
=
0
;
chan
.
chan8_raw
=
0
;
chan
.
rssi
=
100
;
chan
.
rssi
=
100
;
m
essageSize
=
m
avlink_msg_rc_channels_raw_encode
(
systemId
,
componentId
,
&
msg
,
&
chan
);
mavlink_msg_rc_channels_raw_encode
(
systemId
,
componentId
,
&
msg
,
&
chan
);
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
//add data into datastream
...
@@ -513,7 +512,7 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -513,7 +512,7 @@ void MAVLinkSimulationLink::mainloop()
detectionCounter
=
0
;
detectionCounter
=
0
;
}
}
detected
.
detected
=
1
;
detected
.
detected
=
1
;
m
essageSize
=
m
avlink_msg_pattern_detected_encode
(
systemId
,
componentId
,
&
msg
,
&
detected
);
mavlink_msg_pattern_detected_encode
(
systemId
,
componentId
,
&
msg
,
&
detected
);
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
//add data into datastream
...
@@ -528,7 +527,7 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -528,7 +527,7 @@ void MAVLinkSimulationLink::mainloop()
status
.
load
=
33
*
detectionCounter
%
1000
;
status
.
load
=
33
*
detectionCounter
%
1000
;
// Pack message and get size of encoded byte string
// Pack message and get size of encoded byte string
m
essageSize
=
m
avlink_msg_sys_status_encode
(
systemId
,
componentId
,
&
msg
,
&
status
);
mavlink_msg_sys_status_encode
(
systemId
,
componentId
,
&
msg
,
&
status
);
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
//add data into datastream
...
@@ -546,7 +545,7 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -546,7 +545,7 @@ void MAVLinkSimulationLink::mainloop()
/*
/*
// Pack message and get size of encoded byte string
// Pack message and get size of encoded byte string
m
essageSize = m
avlink_msg_boot_pack(systemId, componentId, &msg, version);
mavlink_msg_boot_pack(systemId, componentId, &msg, version);
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
//add data into datastream
...
@@ -568,7 +567,7 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -568,7 +567,7 @@ void MAVLinkSimulationLink::mainloop()
typeCounter
++
;
typeCounter
++
;
// Pack message and get size of encoded byte string
// Pack message and get size of encoded byte string
m
essageSize
=
m
avlink_msg_heartbeat_pack
(
systemId
,
componentId
,
&
msg
,
mavType
,
MAV_AUTOPILOT_PIXHAWK
,
system
.
base_mode
,
system
.
custom_mode
,
system
.
system_status
);
mavlink_msg_heartbeat_pack
(
systemId
,
componentId
,
&
msg
,
mavType
,
MAV_AUTOPILOT_PIXHAWK
,
system
.
base_mode
,
system
.
custom_mode
,
system
.
system_status
);
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
//qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
...
@@ -577,7 +576,7 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -577,7 +576,7 @@ void MAVLinkSimulationLink::mainloop()
streampointer
+=
bufferlength
;
streampointer
+=
bufferlength
;
// Pack message and get size of encoded byte string
// Pack message and get size of encoded byte string
m
essageSize
=
m
avlink_msg_heartbeat_pack
(
systemId
+
1
,
componentId
+
1
,
&
msg
,
mavType
,
MAV_AUTOPILOT_GENERIC
,
system
.
base_mode
,
system
.
custom_mode
,
system
.
system_status
);
mavlink_msg_heartbeat_pack
(
systemId
+
1
,
componentId
+
1
,
&
msg
,
mavType
,
MAV_AUTOPILOT_GENERIC
,
system
.
base_mode
,
system
.
custom_mode
,
system
.
system_status
);
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
//qDebug() << "CRC:" << msg.ck_a << msg.ck_b;
...
@@ -597,7 +596,7 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -597,7 +596,7 @@ void MAVLinkSimulationLink::mainloop()
// // HEARTBEAT VEHICLE 2
// // HEARTBEAT VEHICLE 2
// // Pack message and get size of encoded byte string
// // Pack message and get size of encoded byte string
// m
essageSize = m
avlink_msg_heartbeat_pack(54, componentId, &msg, MAV_HELICOPTER, MAV_AUTOPILOT_ARDUPILOTMEGA);
// mavlink_msg_heartbeat_pack(54, componentId, &msg, MAV_HELICOPTER, MAV_AUTOPILOT_ARDUPILOTMEGA);
// // Allocate buffer with packet data
// // Allocate buffer with packet data
// bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
// bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
// //add data into datastream
// //add data into datastream
...
@@ -607,23 +606,15 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -607,23 +606,15 @@ void MAVLinkSimulationLink::mainloop()
// // HEARTBEAT VEHICLE 3
// // HEARTBEAT VEHICLE 3
// // Pack message and get size of encoded byte string
// // Pack message and get size of encoded byte string
// m
essageSize = m
avlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
// mavlink_msg_heartbeat_pack(60, componentId, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK);
// // Allocate buffer with packet data
// // Allocate buffer with packet data
// bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
// bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
// //add data into datastream
// //add data into datastream
// memcpy(stream+streampointer,buffer, bufferlength);
// memcpy(stream+streampointer,buffer, bufferlength);
// streampointer += bufferlength;
// streampointer += bufferlength;
// STATUS VEHICLE 2
mavlink_sys_status_t
status2
;
mavlink_heartbeat_t
system2
;
system2
.
base_mode
=
MAV_MODE_PREFLIGHT
;
status2
.
voltage_battery
=
voltage
;
status2
.
load
=
120
;
system2
.
system_status
=
MAV_STATE_STANDBY
;
// Pack message and get size of encoded byte string
// Pack message and get size of encoded byte string
m
essageSize
=
m
avlink_msg_sys_status_encode
(
54
,
componentId
,
&
msg
,
&
status
);
mavlink_msg_sys_status_encode
(
54
,
componentId
,
&
msg
,
&
status
);
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
//add data into datastream
...
@@ -646,7 +637,7 @@ void MAVLinkSimulationLink::mainloop()
...
@@ -646,7 +637,7 @@ void MAVLinkSimulationLink::mainloop()
// Attitude
// Attitude
// Pack message and get size of encoded byte string
// Pack message and get size of encoded byte string
m
essageSize = m
avlink_msg_attitude_pack(systemId, componentId, &msg, usec, roll, pitch, yaw, 0, 0, 0);
mavlink_msg_attitude_pack(systemId, componentId, &msg, usec, roll, pitch, yaw, 0, 0, 0);
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
//add data into datastream
...
@@ -681,7 +672,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
...
@@ -681,7 +672,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
{
{
// Parse bytes
// Parse bytes
mavlink_message_t
msg
;
mavlink_message_t
msg
;
mavlink_status_t
comm
;
mavlink_status_t
comm
=
{}
;
uint8_t
stream
[
2048
];
uint8_t
stream
[
2048
];
int
streampointer
=
0
;
int
streampointer
=
0
;
...
...
src/comm/QGCFlightGearLink.cc
View file @
d779e7f1
...
@@ -147,7 +147,15 @@ void QGCFlightGearLink::setRemoteHost(const QString& host)
...
@@ -147,7 +147,15 @@ void QGCFlightGearLink::setRemoteHost(const QString& host)
void
QGCFlightGearLink
::
updateActuators
(
uint64_t
time
,
float
act1
,
float
act2
,
float
act3
,
float
act4
,
float
act5
,
float
act6
,
float
act7
,
float
act8
)
void
QGCFlightGearLink
::
updateActuators
(
uint64_t
time
,
float
act1
,
float
act2
,
float
act3
,
float
act4
,
float
act5
,
float
act6
,
float
act7
,
float
act8
)
{
{
Q_UNUSED
(
time
);
Q_UNUSED
(
act1
);
Q_UNUSED
(
act2
);
Q_UNUSED
(
act3
);
Q_UNUSED
(
act4
);
Q_UNUSED
(
act5
);
Q_UNUSED
(
act6
);
Q_UNUSED
(
act7
);
Q_UNUSED
(
act8
);
}
}
void
QGCFlightGearLink
::
updateControls
(
uint64_t
time
,
float
rollAilerons
,
float
pitchElevator
,
float
yawRudder
,
float
throttle
,
uint8_t
systemMode
,
uint8_t
navMode
)
void
QGCFlightGearLink
::
updateControls
(
uint64_t
time
,
float
rollAilerons
,
float
pitchElevator
,
float
yawRudder
,
float
throttle
,
uint8_t
systemMode
,
uint8_t
navMode
)
...
@@ -225,13 +233,10 @@ void QGCFlightGearLink::readBytes()
...
@@ -225,13 +233,10 @@ void QGCFlightGearLink::readBytes()
}
}
// Parse string
// Parse string
double
time
;
float
roll
,
pitch
,
yaw
,
rollspeed
,
pitchspeed
,
yawspeed
;
float
roll
,
pitch
,
yaw
,
rollspeed
,
pitchspeed
,
yawspeed
;
double
lat
,
lon
,
alt
;
double
lat
,
lon
,
alt
;
double
vx
,
vy
,
vz
,
xacc
,
yacc
,
zacc
;
double
vx
,
vy
,
vz
,
xacc
,
yacc
,
zacc
;
double
airspeed
;
time
=
values
.
at
(
0
).
toDouble
();
lat
=
values
.
at
(
1
).
toDouble
()
*
1e7
;
lat
=
values
.
at
(
1
).
toDouble
()
*
1e7
;
lon
=
values
.
at
(
2
).
toDouble
()
*
1e7
;
lon
=
values
.
at
(
2
).
toDouble
()
*
1e7
;
alt
=
values
.
at
(
3
).
toDouble
()
*
1e3
;
alt
=
values
.
at
(
3
).
toDouble
()
*
1e3
;
...
@@ -250,8 +255,6 @@ void QGCFlightGearLink::readBytes()
...
@@ -250,8 +255,6 @@ void QGCFlightGearLink::readBytes()
vy
=
values
.
at
(
14
).
toDouble
()
*
1e2
;
vy
=
values
.
at
(
14
).
toDouble
()
*
1e2
;
vz
=
values
.
at
(
15
).
toDouble
()
*
1e2
;
vz
=
values
.
at
(
15
).
toDouble
()
*
1e2
;
airspeed
=
values
.
at
(
16
).
toDouble
();
// Send updated state
// Send updated state
emit
hilStateChanged
(
QGC
::
groundTimeUsecs
(),
roll
,
pitch
,
yaw
,
rollspeed
,
emit
hilStateChanged
(
QGC
::
groundTimeUsecs
(),
roll
,
pitch
,
yaw
,
rollspeed
,
pitchspeed
,
yawspeed
,
lat
,
lon
,
alt
,
pitchspeed
,
yawspeed
,
lat
,
lon
,
alt
,
...
...
src/uas/UAS.cc
View file @
d779e7f1
...
@@ -2432,6 +2432,9 @@ void UAS::disarmSystem()
...
@@ -2432,6 +2432,9 @@ void UAS::disarmSystem()
*/
*/
void
UAS
::
setManualControlCommands
(
double
roll
,
double
pitch
,
double
yaw
,
double
thrust
,
int
xHat
,
int
yHat
,
int
buttons
)
void
UAS
::
setManualControlCommands
(
double
roll
,
double
pitch
,
double
yaw
,
double
thrust
,
int
xHat
,
int
yHat
,
int
buttons
)
{
{
Q_UNUSED
(
xHat
);
Q_UNUSED
(
yHat
);
// Scale values
// Scale values
double
rollPitchScaling
=
1.0
f
*
1000.0
f
;
double
rollPitchScaling
=
1.0
f
*
1000.0
f
;
double
yawScaling
=
1.0
f
*
1000.0
f
;
double
yawScaling
=
1.0
f
*
1000.0
f
;
...
@@ -2720,7 +2723,6 @@ void UAS::stopHil()
...
@@ -2720,7 +2723,6 @@ void UAS::stopHil()
void
UAS
::
shutdown
()
void
UAS
::
shutdown
()
{
{
bool
result
=
false
;
QMessageBox
msgBox
;
QMessageBox
msgBox
;
msgBox
.
setIcon
(
QMessageBox
::
Critical
);
msgBox
.
setIcon
(
QMessageBox
::
Critical
);
msgBox
.
setText
(
"Shutting down the UAS"
);
msgBox
.
setText
(
"Shutting down the UAS"
);
...
@@ -2739,7 +2741,6 @@ void UAS::shutdown()
...
@@ -2739,7 +2741,6 @@ void UAS::shutdown()
mavlink_message_t
msg
;
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_ALL
,
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN
,
1
,
0
,
2
,
0
,
0
,
0
,
0
,
0
);
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_ALL
,
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN
,
1
,
0
,
2
,
0
,
0
,
0
,
0
,
0
);
sendMessage
(
msg
);
sendMessage
(
msg
);
result
=
true
;
}
}
}
}
...
...
src/ui/HSIDisplay.cc
View file @
d779e7f1
...
@@ -1075,11 +1075,12 @@ void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float az
...
@@ -1075,11 +1075,12 @@ void HSIDisplay::updateSatellite(int uasid, int satid, float elevation, float az
{
{
Q_UNUSED
(
uasid
);
Q_UNUSED
(
uasid
);
// If slot is empty, insert object
// If slot is empty, insert object
if
(
satid
!=
0
)
// Satellite PRNs currently range from 1-32, but are never zero
if
(
satid
!=
0
)
{
// Satellite PRNs currently range from 1-32, but are never zero
if
(
gpsSatellites
.
contains
(
satid
))
{
if
(
gpsSatellites
.
contains
(
satid
))
{
gpsSatellites
.
value
(
satid
)
->
update
(
satid
,
elevation
,
azimuth
,
snr
,
used
);
gpsSatellites
.
value
(
satid
)
->
update
(
satid
,
elevation
,
azimuth
,
snr
,
used
);
}
else
{
}
else
{
gpsSatellites
.
insert
(
satid
,
new
GPSSatellite
(
satid
,
elevation
,
azimuth
,
snr
,
used
));
gpsSatellites
.
insert
(
satid
,
new
GPSSatellite
(
satid
,
elevation
,
azimuth
,
snr
,
used
));
}
}
}
}
}
...
...
src/ui/HUD.cc
View file @
d779e7f1
...
@@ -335,6 +335,7 @@ void HUD::updateAttitude(UASInterface* uas, int component, double roll, double p
...
@@ -335,6 +335,7 @@ void HUD::updateAttitude(UASInterface* uas, int component, double roll, double p
void
HUD
::
updateBattery
(
UASInterface
*
uas
,
double
voltage
,
double
percent
,
int
seconds
)
void
HUD
::
updateBattery
(
UASInterface
*
uas
,
double
voltage
,
double
percent
,
int
seconds
)
{
{
Q_UNUSED
(
uas
);
Q_UNUSED
(
uas
);
Q_UNUSED
(
seconds
);
fuelStatus
=
tr
(
"BAT [%1% | %2V]"
).
arg
(
percent
,
2
,
'f'
,
0
,
QChar
(
'0'
)).
arg
(
voltage
,
4
,
'f'
,
1
,
QChar
(
'0'
));
fuelStatus
=
tr
(
"BAT [%1% | %2V]"
).
arg
(
percent
,
2
,
'f'
,
0
,
QChar
(
'0'
)).
arg
(
voltage
,
4
,
'f'
,
1
,
QChar
(
'0'
));
if
(
percent
<
20.0
f
)
{
if
(
percent
<
20.0
f
)
{
fuelColor
=
warningColor
;
fuelColor
=
warningColor
;
...
...
src/ui/MAVLinkDecoder.cc
View file @
d779e7f1
...
@@ -101,13 +101,11 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
...
@@ -101,13 +101,11 @@ void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t messag
}
}
quint64
MAVLinkDecoder
::
getUnixTimeFromMs
(
int
systemID
,
quint64
time
)
quint64
MAVLinkDecoder
::
getUnixTimeFromMs
(
int
systemID
,
quint64
time
)
{
{
bool
isNull
=
false
;
quint64
ret
=
0
;
quint64
ret
=
0
;
if
(
time
==
0
)
if
(
time
==
0
)
{
{
ret
=
QGC
::
groundTimeMilliseconds
()
-
onboardToGCSUnixTimeOffsetAndDelay
[
systemID
];
ret
=
QGC
::
groundTimeMilliseconds
()
-
onboardToGCSUnixTimeOffsetAndDelay
[
systemID
];
isNull
=
true
;
}
}
// Check if time is smaller than 40 years,
// Check if time is smaller than 40 years,
// assuming no system without Unix timestamp
// assuming no system without Unix timestamp
...
@@ -183,7 +181,6 @@ quint64 MAVLinkDecoder::getUnixTimeFromMs(int systemID, quint64 time)
...
@@ -183,7 +181,6 @@ quint64 MAVLinkDecoder::getUnixTimeFromMs(int systemID, quint64 time)
void
MAVLinkDecoder
::
emitFieldValue
(
mavlink_message_t
*
msg
,
int
fieldid
,
quint64
time
)
void
MAVLinkDecoder
::
emitFieldValue
(
mavlink_message_t
*
msg
,
int
fieldid
,
quint64
time
)
{
{
bool
multiComponentSourceDetected
=
false
;
bool
multiComponentSourceDetected
=
false
;
bool
wrongComponent
=
false
;
// Store component ID
// Store component ID
if
(
componentID
[
msg
->
msgid
]
==
-
1
)
if
(
componentID
[
msg
->
msgid
]
==
-
1
)
...
@@ -196,7 +193,6 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
...
@@ -196,7 +193,6 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
if
(
componentID
[
msg
->
msgid
]
!=
msg
->
compid
)
if
(
componentID
[
msg
->
msgid
]
!=
msg
->
compid
)
{
{
componentMulti
[
msg
->
msgid
]
=
true
;
componentMulti
[
msg
->
msgid
]
=
true
;
wrongComponent
=
true
;
}
}
}
}
...
...
src/ui/uas/UASView.cc
View file @
d779e7f1
...
@@ -573,10 +573,6 @@ void UASView::refresh()
...
@@ -573,10 +573,6 @@ void UASView::refresh()
//qDebug() << "UPDATING UAS WIDGET!" << uas->getUASName();
//qDebug() << "UPDATING UAS WIDGET!" << uas->getUASName();
quint64
lastupdate
=
0
;
//// qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
lastupdate
=
QGC
::
groundTimeMilliseconds
();
if
(
generalUpdateCount
==
4
)
if
(
generalUpdateCount
==
4
)
{
{
#if (QGC_EVENTLOOP_DEBUG)
#if (QGC_EVENTLOOP_DEBUG)
...
...
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