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
4a851400
Commit
4a851400
authored
Jul 28, 2011
by
oberion
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'dev-win' into dev-winXbee
Conflicts: qgroundcontrol.pri
parents
f4a1b73a
be676aed
Changes
14
Hide whitespace changes
Inline
Side-by-side
Showing
14 changed files
with
89 additions
and
82 deletions
+89
-82
qgroundcontrol.pri
qgroundcontrol.pri
+27
-24
Waypoint.cc
src/Waypoint.cc
+2
-2
SerialLink.cc
src/comm/SerialLink.cc
+3
-3
UDPLink.cc
src/comm/UDPLink.cc
+3
-3
JoystickInput.cc
src/input/JoystickInput.cc
+3
-3
tilecachequeue.cpp
src/libs/opmapcontrol/src/core/tilecachequeue.cpp
+4
-0
waypointitem.cpp
src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp
+2
-2
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+21
-21
HUD.cc
src/ui/HUD.cc
+2
-2
WaypointView.cc
src/ui/WaypointView.cc
+3
-3
MAV2DIcon.cc
src/ui/map/MAV2DIcon.cc
+5
-5
QGCMapWidget.cc
src/ui/map/QGCMapWidget.cc
+4
-4
Waypoint2DIcon.cc
src/ui/map/Waypoint2DIcon.cc
+4
-4
UASView.cc
src/ui/uas/UASView.cc
+6
-6
No files found.
qgroundcontrol.pri
View file @
4a851400
...
...
@@ -20,6 +20,8 @@
message(Qt version $$[QT_VERSION])
message(Using Qt from $(QTDIR))
release {
# DEFINES += QT_NO_DEBUG_OUTPUT
# DEFINES += QT_NO_WARNING_OUTPUT
...
...
@@ -363,24 +365,25 @@ DEFINES += QGC_OSG_ENABLED
BASEDIR_WIN = $$replace(BASEDIR,"/","\\")
TARGETDIR_WIN = $$replace(TARGETDIR,"/","\\")
exists($$TARGETDIR/debug) {
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\audio" "$$TARGETDIR_WIN\\debug\\audio" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\models" "$$TARGETDIR_WIN\\debug\\models" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\images\\earth.html" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\thirdParty\\libxbee\\lib\\libxbee.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$(QTDIR)\\plugins" "$$TARGETDIR_WIN\\debug" /E /I /EXCLUDE:copydebug.txt $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\phonond4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtCored4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtGuid4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtMultimediad4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtNetworkd4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtOpenGLd4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtSqld4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtSvgd4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtWebKitd4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtXmld4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtXmlPatternsd4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$
$
(QTDIR)\\plugins" "$$TARGETDIR_WIN\\debug" /E /I /EXCLUDE:copydebug.txt $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\phonond4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtCored4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtGuid4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtMultimediad4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtNetworkd4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtOpenGLd4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtSqld4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtSvgd4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtWebKitd4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtXmld4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtXmlPatternsd4.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
}
exists($$TARGETDIR/release) {
...
...
@@ -389,18 +392,18 @@ DEFINES += QGC_OSG_ENABLED
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\models" "$$TARGETDIR_WIN\\release\\models" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\images\\earth.html" "$$TARGETDIR_WIN\\release\\earth.html" $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\thirdParty\\libxbee\\lib\\libxbee.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$(QTDIR)\\plugins" "$$TARGETDIR_WIN\\release" /E /I /EXCLUDE:copyrelease.txt $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\phonon4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtCore4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtGui4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtMultimedia4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtNetwork4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtOpenGL4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtSql4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtSvg4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtWebKit4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtXml4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$(QTDIR)\\bin\\QtXmlPatterns4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$
$
(QTDIR)\\plugins" "$$TARGETDIR_WIN\\release" /E /I /EXCLUDE:copyrelease.txt $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\phonon4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtCore4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtGui4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtMultimedia4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtNetwork4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtOpenGL4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtSql4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtSvg4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtWebKit4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtXml4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$
$
(QTDIR)\\bin\\QtXmlPatterns4.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
}
...
...
src/Waypoint.cc
View file @
4a851400
...
...
@@ -221,8 +221,8 @@ void Waypoint::setAcceptanceRadius(double radius)
void
Waypoint
::
setParam1
(
double
param1
)
{
qDebug
()
<<
"SENDER:"
<<
QObject
::
sender
();
qDebug
()
<<
"PARAM1 SET REQ:"
<<
param1
;
//
qDebug() << "SENDER:" << QObject::sender();
//
qDebug() << "PARAM1 SET REQ:" << param1;
if
(
this
->
param1
!=
param1
)
{
this
->
param1
=
param1
;
emit
changed
(
this
);
...
...
src/comm/SerialLink.cc
View file @
4a851400
...
...
@@ -300,7 +300,7 @@ bool SerialLink::hardwareConnect()
emit
connected
(
true
);
}
qDebug
()
<<
"CONNECTING LINK: "
<<
__FILE__
<<
__LINE__
<<
"with settings"
<<
port
->
portName
()
<<
getBaudRate
()
<<
getDataBits
()
<<
getParityType
()
<<
getStopBits
();
//
qDebug() << "CONNECTING LINK: " << __FILE__ << __LINE__ << "with settings" << port->portName() << getBaudRate() << getDataBits() << getParityType() << getStopBits();
writeSettings
();
...
...
@@ -627,7 +627,7 @@ bool SerialLink::setBaudRateString(const QString& rate)
bool
SerialLink
::
setBaudRate
(
int
rate
)
{
qDebug
()
<<
"BAUD RATE:"
<<
rate
;
//
qDebug() << "BAUD RATE:" << rate;
bool
reconnect
=
false
;
bool
accepted
=
true
;
// This is changed if none of the data rates matches
...
...
@@ -796,7 +796,7 @@ bool SerialLink::setParityType(int parity)
bool
SerialLink
::
setDataBits
(
int
dataBits
)
{
qDebug
()
<<
"Setting"
<<
dataBits
<<
"data bits"
;
//
qDebug() << "Setting" << dataBits << "data bits";
bool
reconnect
=
false
;
if
(
isConnected
())
reconnect
=
true
;
bool
accepted
=
true
;
...
...
src/comm/UDPLink.cc
View file @
4a851400
...
...
@@ -85,9 +85,9 @@ void UDPLink::setPort(int port)
*/
void
UDPLink
::
addHost
(
const
QString
&
host
)
{
qDebug
()
<<
"UDP:"
<<
"ADDING HOST:"
<<
host
;
//
qDebug() << "UDP:" << "ADDING HOST:" << host;
if
(
host
.
contains
(
":"
))
{
qDebug
()
<<
"HOST: "
<<
host
.
split
(
":"
).
first
();
//
qDebug() << "HOST: " << host.split(":").first();
QHostInfo
info
=
QHostInfo
::
fromName
(
host
.
split
(
":"
).
first
());
if
(
info
.
error
()
==
QHostInfo
::
NoError
)
{
...
...
@@ -103,7 +103,7 @@ void UDPLink::addHost(const QString& host)
}
}
hosts
.
append
(
address
);
qDebug
()
<<
"Address:"
<<
address
.
toString
();
//
qDebug() << "Address:" << address.toString();
// Set port according to user input
ports
.
append
(
host
.
split
(
":"
).
last
().
toInt
());
}
...
...
src/input/JoystickInput.cc
View file @
4a851400
...
...
@@ -143,7 +143,7 @@ void JoystickInput::run()
switch
(
event
.
type
)
{
case
SDL_KEYDOWN
:
/* handle keyboard stuff here */
qDebug
()
<<
"KEY PRESSED!"
;
//
qDebug() << "KEY PRESSED!";
break
;
case
SDL_QUIT
:
...
...
@@ -153,7 +153,7 @@ void JoystickInput::run()
case
SDL_JOYBUTTONDOWN
:
/* Handle Joystick Button Presses */
if
(
event
.
jbutton
.
button
==
0
)
{
qDebug
()
<<
"BUTTON PRESSED!"
;
//
qDebug() << "BUTTON PRESSED!";
}
break
;
...
...
@@ -170,7 +170,7 @@ void JoystickInput::run()
break
;
default:
qDebug
()
<<
"SDL event occured"
;
//
qDebug() << "SDL event occured";
break
;
}
}
...
...
src/libs/opmapcontrol/src/core/tilecachequeue.cpp
View file @
4a851400
...
...
@@ -98,7 +98,9 @@ void TileCacheQueue::run()
else
{
#ifdef DEBUG_TILECACHEQUEUE
qDebug
()
<<
"Cache engine BEGIN WAIT"
;
#endif //DEBUG_TILECACHEQUEUE
waitmutex
.
lock
();
int
tout
=
4000
;
if
(
!
waitc
.
wait
(
&
waitmutex
,
tout
))
...
...
@@ -115,7 +117,9 @@ void TileCacheQueue::run()
}
mutex
.
unlock
();
}
#ifdef DEBUG_TILECACHEQUEUE
qDebug
()
<<
"Cache Engine DID NOT TimeOut"
;
#endif //DEBUG_TILECACHEQUEUE
waitmutex
.
unlock
();
}
}
...
...
src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp
View file @
4a851400
...
...
@@ -113,7 +113,7 @@ namespace mapcontrol
delete
textBG
;
coord
=
map
->
FromLocalToLatLng
(
this
->
pos
().
x
(),
this
->
pos
().
y
());
QString
coord_str
=
" "
+
QString
::
number
(
coord
.
Lat
(),
'f'
,
6
)
+
" "
+
QString
::
number
(
coord
.
Lng
(),
'f'
,
6
);
qDebug
()
<<
"WP MOVE:"
<<
coord_str
<<
__FILE__
<<
__LINE__
;
//
qDebug() << "WP MOVE:" << coord_str << __FILE__ << __LINE__;
isDragging
=
false
;
RefreshToolTip
();
...
...
@@ -129,7 +129,7 @@ namespace mapcontrol
coord
=
map
->
FromLocalToLatLng
(
this
->
pos
().
x
(),
this
->
pos
().
y
());
QString
coord_str
=
" "
+
QString
::
number
(
coord
.
Lat
(),
'f'
,
6
)
+
" "
+
QString
::
number
(
coord
.
Lng
(),
'f'
,
6
);
text
->
setText
(
coord_str
);
qDebug
()
<<
"WP DRAG:"
<<
coord_str
<<
__FILE__
<<
__LINE__
;
//
qDebug() << "WP DRAG:" << coord_str << __FILE__ << __LINE__;
textBG
->
setRect
(
text
->
boundingRect
());
emit
WPValuesChanged
(
this
);
...
...
src/uas/UASWaypointManager.cc
View file @
4a851400
...
...
@@ -57,7 +57,7 @@ void UASWaypointManager::timeout()
protocol_timer
.
start
(
PROTOCOL_TIMEOUT_MS
);
current_retries
--
;
emit
updateStatusString
(
tr
(
"Timeout, retrying (retries left: %1)"
).
arg
(
current_retries
));
qDebug
()
<<
"Timeout, retrying (retries left:"
<<
current_retries
<<
")"
;
//
qDebug() << "Timeout, retrying (retries left:" << current_retries << ")";
if
(
current_state
==
WP_GETLIST
)
{
sendWaypointRequestList
();
}
else
if
(
current_state
==
WP_GETLIST_GETWPS
)
{
...
...
@@ -74,7 +74,7 @@ void UASWaypointManager::timeout()
}
else
{
protocol_timer
.
stop
();
qDebug
()
<<
"Waypoint transaction (state="
<<
current_state
<<
") timed out going to state WP_IDLE"
;
//
qDebug() << "Waypoint transaction (state=" << current_state << ") timed out going to state WP_IDLE";
emit
updateStatusString
(
"Operation timed out."
);
...
...
@@ -92,7 +92,7 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
protocol_timer
.
start
(
PROTOCOL_TIMEOUT_MS
);
current_retries
=
PROTOCOL_MAX_RETRIES
;
qDebug
()
<<
"got waypoint count ("
<<
count
<<
") from ID "
<<
systemId
;
//
qDebug() << "got waypoint count (" << count << ") from ID " << systemId;
if
(
count
>
0
)
{
current_count
=
count
;
...
...
@@ -103,7 +103,7 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
}
else
{
protocol_timer
.
stop
();
emit
updateStatusString
(
"done."
);
qDebug
()
<<
"No waypoints on UAS "
<<
systemId
;
//
qDebug() << "No waypoints on UAS " << systemId;
current_state
=
WP_IDLE
;
current_count
=
0
;
current_wp_id
=
0
;
...
...
@@ -122,7 +122,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
current_retries
=
PROTOCOL_MAX_RETRIES
;
if
(
wp
->
seq
==
current_wp_id
)
{
//qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << "Frame:"<< (MAV_FRAME) wp->frame << "Command:" << (MAV_CMD) wp->command;
//
//
qDebug() << "Got WP: " << wp->seq << wp->x << wp->y << wp->z << wp->param4 << "auto:" << wp->autocontinue << "curr:" << wp->current << wp->param1 << wp->param2 << "Frame:"<< (MAV_FRAME) wp->frame << "Command:" << (MAV_CMD) wp->command;
Waypoint
*
lwp
=
new
Waypoint
(
wp
->
seq
,
wp
->
x
,
wp
->
y
,
wp
->
z
,
wp
->
param1
,
wp
->
param2
,
wp
->
param3
,
wp
->
param4
,
wp
->
autocontinue
,
wp
->
current
,
(
MAV_FRAME
)
wp
->
frame
,
(
MAV_CMD
)
wp
->
command
);
addWaypoint
(
lwp
,
false
);
...
...
@@ -145,7 +145,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
emit
readGlobalWPFromUAS
(
false
);
emit
updateStatusString
(
"done."
);
qDebug
()
<<
"got all waypoints from ID "
<<
systemId
;
//
qDebug() << "got all waypoints from ID " << systemId;
}
}
else
{
emit
updateStatusString
(
tr
(
"Waypoint ID mismatch, rejecting waypoint"
));
...
...
@@ -163,12 +163,12 @@ void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavli
protocol_timer
.
stop
();
current_state
=
WP_IDLE
;
emit
updateStatusString
(
"done."
);
qDebug
()
<<
"sent all waypoints to ID "
<<
systemId
;
//
qDebug() << "sent all waypoints to ID " << systemId;
}
else
if
(
current_state
==
WP_CLEARLIST
)
{
protocol_timer
.
stop
();
current_state
=
WP_IDLE
;
emit
updateStatusString
(
"done."
);
qDebug
()
<<
"cleared waypoint list of ID "
<<
systemId
;
//
qDebug() << "cleared waypoint list of ID " << systemId;
}
}
}
...
...
@@ -217,18 +217,18 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m
}
}
//qDebug() << "Updated waypoints list";
//
//
qDebug() << "Updated waypoints list";
}
emit
updateStatusString
(
QString
(
"New current waypoint %1"
).
arg
(
wpc
->
seq
));
//emit update to UI widgets
emit
currentWaypointChanged
(
wpc
->
seq
);
//qDebug() << "new current waypoint" << wpc->seq;
//
//
qDebug() << "new current waypoint" << wpc->seq;
}
}
void
UASWaypointManager
::
notifyOfChange
(
Waypoint
*
wp
)
{
qDebug
()
<<
"WAYPOINT CHANGED: ID:"
<<
wp
->
getId
();
//
qDebug() << "WAYPOINT CHANGED: ID:" << wp->getId();
// If only one waypoint was changed, emit only WP signal
if
(
wp
!=
NULL
)
{
emit
waypointChanged
(
uas
.
getUASID
(),
wp
);
...
...
@@ -713,7 +713,7 @@ void UASWaypointManager::writeWaypoints()
sendWaypointClearAll
();
}
else
{
//we're in another transaction, ignore command
qDebug
()
<<
"UASWaypointManager::sendWaypoints() doing something else ignoring command"
;
//
qDebug() << "UASWaypointManager::sendWaypoints() doing something else ignoring command";
}
}
...
...
@@ -731,7 +731,7 @@ void UASWaypointManager::sendWaypointClearAll()
uas
.
sendMessage
(
message
);
MG
::
SLEEP
::
usleep
(
PROTOCOL_DELAY_MS
*
1000
);
qDebug
()
<<
"sent waypoint clear all to ID "
<<
wpca
.
target_system
;
//
qDebug() << "sent waypoint clear all to ID " << wpca.target_system;
}
void
UASWaypointManager
::
sendWaypointSetCurrent
(
quint16
seq
)
...
...
@@ -749,7 +749,7 @@ void UASWaypointManager::sendWaypointSetCurrent(quint16 seq)
uas
.
sendMessage
(
message
);
MG
::
SLEEP
::
usleep
(
PROTOCOL_DELAY_MS
*
1000
);
qDebug
()
<<
"sent waypoint set current ("
<<
wpsc
.
seq
<<
") to ID "
<<
wpsc
.
target_system
;
//
qDebug() << "sent waypoint set current (" << wpsc.seq << ") to ID " << wpsc.target_system;
}
void
UASWaypointManager
::
sendWaypointCount
()
...
...
@@ -761,14 +761,14 @@ void UASWaypointManager::sendWaypointCount()
wpc
.
target_component
=
MAV_COMP_ID_WAYPOINTPLANNER
;
wpc
.
count
=
current_count
;
qDebug
()
<<
"sent waypoint count ("
<<
wpc
.
count
<<
") to ID "
<<
wpc
.
target_system
;
//
qDebug() << "sent waypoint count (" << wpc.count << ") to ID " << wpc.target_system;
emit
updateStatusString
(
QString
(
"Starting to transmit waypoints..."
));
mavlink_msg_waypoint_count_encode
(
uas
.
mavlink
->
getSystemId
(),
uas
.
mavlink
->
getComponentId
(),
&
message
,
&
wpc
);
uas
.
sendMessage
(
message
);
MG
::
SLEEP
::
usleep
(
PROTOCOL_DELAY_MS
*
1000
);
qDebug
()
<<
"sent waypoint count ("
<<
wpc
.
count
<<
") to ID "
<<
wpc
.
target_system
;
//
qDebug() << "sent waypoint count (" << wpc.count << ") to ID " << wpc.target_system;
}
void
UASWaypointManager
::
sendWaypointRequestList
()
...
...
@@ -785,7 +785,7 @@ void UASWaypointManager::sendWaypointRequestList()
uas
.
sendMessage
(
message
);
MG
::
SLEEP
::
usleep
(
PROTOCOL_DELAY_MS
*
1000
);
qDebug
()
<<
"sent waypoint list request to ID "
<<
wprl
.
target_system
;
//
qDebug() << "sent waypoint list request to ID " << wprl.target_system;
}
...
...
@@ -805,13 +805,13 @@ void UASWaypointManager::sendWaypointRequest(quint16 seq)
uas
.
sendMessage
(
message
);
MG
::
SLEEP
::
usleep
(
PROTOCOL_DELAY_MS
*
1000
);
qDebug
()
<<
"sent waypoint request ("
<<
wpr
.
seq
<<
") to ID "
<<
wpr
.
target_system
;
//
qDebug() << "sent waypoint request (" << wpr.seq << ") to ID " << wpr.target_system;
}
void
UASWaypointManager
::
sendWaypoint
(
quint16
seq
)
{
mavlink_message_t
message
;
qDebug
()
<<
" WP Buffer count: "
<<
waypoint_buffer
.
count
();
//
qDebug() <<" WP Buffer count: "<<waypoint_buffer.count();
if
(
seq
<
waypoint_buffer
.
count
())
{
...
...
@@ -824,7 +824,7 @@ void UASWaypointManager::sendWaypoint(quint16 seq)
emit
updateStatusString
(
QString
(
"Sending waypoint ID %1 of %2 total"
).
arg
(
wp
->
seq
).
arg
(
current_count
));
qDebug
()
<<
"sent waypoint ("
<<
wp
->
seq
<<
") to ID "
<<
wp
->
target_system
<<
" WP Buffer count: "
<<
waypoint_buffer
.
count
();
//
qDebug() << "sent waypoint (" << wp->seq << ") to ID " << wp->target_system<<" WP Buffer count: "<<waypoint_buffer.count();
mavlink_msg_waypoint_encode
(
uas
.
mavlink
->
getSystemId
(),
uas
.
mavlink
->
getComponentId
(),
&
message
,
wp
);
uas
.
sendMessage
(
message
);
...
...
@@ -846,5 +846,5 @@ void UASWaypointManager::sendWaypointAck(quint8 type)
uas
.
sendMessage
(
message
);
MG
::
SLEEP
::
usleep
(
PROTOCOL_DELAY_MS
*
1000
);
qDebug
()
<<
"sent waypoint ack ("
<<
wpa
.
type
<<
") to ID "
<<
wpa
.
target_system
;
//
qDebug() << "sent waypoint ack (" << wpa.type << ") to ID " << wpa.target_system;
}
src/ui/HUD.cc
View file @
4a851400
...
...
@@ -198,7 +198,7 @@ void HUD::showEvent(QShowEvent* event)
{
// React only to internal (pre-display)
// events
Q
_UNUSED
(
event
)
Q
GLWidget
::
showEvent
(
event
);
refreshTimer
->
start
(
updateInterval
);
}
...
...
@@ -206,7 +206,7 @@ void HUD::hideEvent(QHideEvent* event)
{
// React only to internal (pre-display)
// events
Q
_UNUSED
(
event
);
Q
GLWidget
::
hideEvent
(
event
);
refreshTimer
->
stop
();
}
...
...
src/ui/WaypointView.cc
View file @
4a851400
...
...
@@ -504,7 +504,7 @@ void WaypointView::updateValues()
if
(
customCommand
->
commandSpinBox
->
value
()
!=
wp
->
getAction
())
{
customCommand
->
commandSpinBox
->
setValue
(
wp
->
getAction
());
qDebug
()
<<
"Changed action"
;
//
qDebug() << "Changed action";
}
// Param 1
if
(
customCommand
->
param1SpinBox
->
value
()
!=
wp
->
getParam1
())
{
...
...
@@ -545,7 +545,7 @@ void WaypointView::updateValues()
if
(
currId
!=
lastId
)
{
qDebug
()
<<
"COLOR ID: "
<<
currId
;
//
qDebug() << "COLOR ID: " << currId;
if
(
currId
==
1
)
{
//backGroundColor = backGroundColor.lighter(150);
...
...
@@ -555,7 +555,7 @@ void WaypointView::updateValues()
{
backGroundColor
=
QColor
(
"#252528"
).
lighter
(
250
);
}
qDebug
()
<<
"COLOR:"
<<
backGroundColor
.
name
();
//
qDebug() << "COLOR:" << backGroundColor.name();
// Update color based on id
QString
groupBoxStyle
=
QString
(
"QGroupBox {padding: 0px; margin: 0px; border: 0px; background-color: %1; }"
).
arg
(
backGroundColor
.
name
());
...
...
src/ui/map/MAV2DIcon.cc
View file @
4a851400
...
...
@@ -53,7 +53,7 @@ void MAV2DIcon::setSelectedUAS(bool selected)
*/
void
MAV2DIcon
::
setYaw
(
float
yaw
)
{
//qDebug() << "MAV2Icon" << yaw;
//
//
qDebug() << "MAV2Icon" << yaw;
float
diff
=
fabs
(
yaw
-
this
->
yaw
);
while
(
diff
>
(
float
)
M_PI
)
{
diff
-=
(
float
)
M_PI
;
...
...
@@ -111,7 +111,7 @@ void MAV2DIcon::drawAirframePolygon(int airframe, QPainter& painter, int radius,
painter
.
rotate
(
yawRotate
);
//qDebug() << "ICON SIZE:" << radius;
//
//
qDebug() << "ICON SIZE:" << radius;
float
iconSize
=
radius
*
0.9
f
;
QPolygonF
poly
(
24
);
...
...
@@ -158,7 +158,7 @@ void MAV2DIcon::drawAirframePolygon(int airframe, QPainter& painter, int radius,
painter
.
rotate
(
yawRotate
);
//qDebug() << "ICON SIZE:" << radius;
//
//
qDebug() << "ICON SIZE:" << radius;
QPointF
front
(
0
,
0.2
);
front
=
front
*
iconSize
;
...
...
@@ -199,7 +199,7 @@ void MAV2DIcon::drawAirframePolygon(int airframe, QPainter& painter, int radius,
int
yawRotate
=
static_cast
<
int
>
(
yawDeg
)
%
360
;
painter
.
rotate
(
yawRotate
);
//qDebug() << "ICON SIZE:" << radius;
//
//
qDebug() << "ICON SIZE:" << radius;
float
iconSize
=
radius
*
0.7
f
;
...
...
@@ -254,7 +254,7 @@ void MAV2DIcon::drawAirframePolygon(int airframe, QPainter& painter, int radius,
painter
.
rotate
(
yawRotate
);
//qDebug() << "ICON SIZE:" << radius;
//
//
qDebug() << "ICON SIZE:" << radius;
float
iconSize
=
radius
*
0.9
f
;
QPolygonF
poly
(
3
);
...
...
src/ui/map/QGCMapWidget.cc
View file @
4a851400
...
...
@@ -171,7 +171,7 @@ void QGCMapWidget::mouseDoubleClickEvent(QMouseEvent* event)
*/
void
QGCMapWidget
::
addUAS
(
UASInterface
*
uas
)
{
qDebug
()
<<
"ADDING UAS"
;
// //
qDebug() << "ADDING UAS";
connect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
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
(
systemSpecsChanged
(
int
)),
this
,
SLOT
(
updateSystemSpecs
(
int
)));
...
...
@@ -390,7 +390,7 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
if
(
firingWaypointChange
==
wp
)
return
;
// Not in cycle, block now from entering it
firingWaypointChange
=
wp
;
qDebug
()
<<
"UPDATING WP FROM MAP"
;
// //
qDebug() << "UPDATING WP FROM MAP";
// Update WP values
internals
::
PointLatLng
pos
=
waypoint
->
Coord
();
...
...
@@ -405,9 +405,9 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
internals
::
PointLatLng
coord
=
waypoint
->
Coord
();
QString
coord_str
=
" "
+
QString
::
number
(
coord
.
Lat
(),
'f'
,
6
)
+
" "
+
QString
::
number
(
coord
.
Lng
(),
'f'
,
6
);
qDebug
()
<<
"MAP WP COORD (MAP):"
<<
coord_str
<<
__FILE__
<<
__LINE__
;
// //
qDebug() << "MAP WP COORD (MAP):" << coord_str << __FILE__ << __LINE__;
QString
wp_str
=
QString
::
number
(
wp
->
getLatitude
(),
'f'
,
6
)
+
" "
+
QString
::
number
(
wp
->
getLongitude
(),
'f'
,
6
);
qDebug
()
<<
"MAP WP COORD (WP):"
<<
wp_str
<<
__FILE__
<<
__LINE__
;
// //
qDebug() << "MAP WP COORD (WP):" << wp_str << __FILE__ << __LINE__;
firingWaypointChange
=
NULL
;
...
...
src/ui/map/Waypoint2DIcon.cc
View file @
4a851400
...
...
@@ -60,7 +60,7 @@ void Waypoint2DIcon::updateWaypoint()
SetHeading
(
waypoint
->
getYaw
());
SetCoord
(
internals
::
PointLatLng
(
waypoint
->
getLatitude
(),
waypoint
->
getLongitude
()));
qDebug
()
<<
"UPDATING WP:"
<<
waypoint
->
getId
()
<<
"LAT:"
<<
waypoint
->
getLatitude
()
<<
"LON:"
<<
waypoint
->
getLongitude
();
//
qDebug() << "UPDATING WP:" << waypoint->getId() << "LAT:" << waypoint->getLatitude() << "LON:" << waypoint->getLongitude();
SetDescription
(
waypoint
->
getDescription
());
SetAltitude
(
waypoint
->
getAltitude
());
...
...
@@ -68,7 +68,7 @@ void Waypoint2DIcon::updateWaypoint()
drawIcon
();
QRectF
newSize
=
boundingRect
();
qDebug
()
<<
"WIDTH"
<<
newSize
.
width
()
<<
"<"
<<
oldSize
.
width
();
//
qDebug() << "WIDTH" << newSize.width() << "<" << oldSize.width();
// If new size is smaller than old size, update surrounding
if
((
newSize
.
width
()
<=
oldSize
.
width
())
||
(
newSize
.
height
()
<=
oldSize
.
height
()))
...
...
@@ -78,8 +78,8 @@ void Waypoint2DIcon::updateWaypoint()
int
oldWidth
=
oldSize
.
width
()
+
20
;
int
oldHeight
=
oldSize
.
height
()
+
20
;
map
->
update
(
this
->
x
()
-
10
,
this
->
y
()
-
10
,
oldWidth
,
oldHeight
);
//qDebug() << "UPDATING DUE TO SMALLER SIZE";
//qDebug() << "X:" << this->x()-1 << "Y:" << this->y()-1 << "WIDTH:" << oldWidth << "HEIGHT:" << oldHeight;
//
//
qDebug() << "UPDATING DUE TO SMALLER SIZE";
//
//
qDebug() << "X:" << this->x()-1 << "Y:" << this->y()-1 << "WIDTH:" << oldWidth << "HEIGHT:" << oldHeight;
}
else
{
...
...
src/ui/uas/UASView.cc
View file @
4a851400
...
...
@@ -231,7 +231,7 @@ void UASView::mouseDoubleClickEvent (QMouseEvent * event)
{
Q_UNUSED
(
event
);
UASManager
::
instance
()
->
setActiveUAS
(
uas
);
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"DOUBLECLICKED"
;
//
qDebug() << __FILE__ << __LINE__ << "DOUBLECLICKED";
}
void
UASView
::
enterEvent
(
QEvent
*
event
)
...
...
@@ -242,10 +242,10 @@ void UASView::enterEvent(QEvent* event)
grabMouse
(
QCursor
(
Qt
::
PointingHandCursor
));
}
}
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"IN FOCUS"
;
//
qDebug() << __FILE__ << __LINE__ << "IN FOCUS";
if
(
event
->
type
()
==
QEvent
::
MouseButtonDblClick
)
{
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"UAS CLICKED!"
;
//
qDebug() << __FILE__ << __LINE__ << "UAS CLICKED!";
}
}
...
...
@@ -499,7 +499,7 @@ void UASView::refresh()
//repaint();
static
quint64
lastupdate
=
0
;
//qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
//
//
qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate;
lastupdate
=
MG
::
TIME
::
getGroundTimeNow
();
// FIXME
...
...
@@ -507,10 +507,10 @@ void UASView::refresh()
if
(
generalUpdateCount
==
4
)
{
#if (QGC_EVENTLOOP_DEBUG)
qDebug
()
<<
"EVENTLOOP:"
<<
__FILE__
<<
__LINE__
;
//
qDebug() << "EVENTLOOP:" << __FILE__ << __LINE__;
#endif
generalUpdateCount
=
0
;
//qDebug() << "UPDATING EVERYTHING";
//
//
qDebug() << "UPDATING EVERYTHING";
// State
m_ui
->
stateLabel
->
setText
(
state
);
m_ui
->
statusTextLabel
->
setText
(
stateDesc
);
...
...
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