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
30bcc904
Commit
30bcc904
authored
Jan 07, 2016
by
ChukRhodes
Browse files
Options
Browse Files
Download
Plain Diff
Merge remote-tracking branch 'refs/remotes/mavlink/master'
parents
c1591744
e5a83d8d
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
120 additions
and
24 deletions
+120
-24
AirframeFactMetaData.xml
src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml
+57
-3
MissionItemIndicator.qml
src/FlightMap/MapItems/MissionItemIndicator.qml
+1
-1
MissionEditor.qml
src/MissionEditor/MissionEditor.qml
+1
-0
MavCmdInfo.json
src/MissionManager/MavCmdInfo.json
+1
-1
MissionController.cc
src/MissionManager/MissionController.cc
+7
-4
LogDownload.qml
src/ViewWidgets/LogDownload.qml
+1
-1
LogDownloadController.cc
src/ViewWidgets/LogDownloadController.cc
+50
-13
LogDownloadController.h
src/ViewWidgets/LogDownloadController.h
+2
-1
No files found.
src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml
View file @
30bcc904
<?xml version='1.0' encoding='UTF-8'?>
<airframes>
<version>
1
</version>
<airframe_group
image=
""
name=
"Coaxial Helicopter"
>
<airframe
id=
"15001"
maintainer=
"Emmanuel Roussel"
name=
"Coaxial Helicopter (such as Esky Lama v4 or Esky Big Lama)"
>
<maintainer>
Emmanuel Roussel
</maintainer>
<type>
Coaxial Helicopter
</type>
<output
name=
"MAIN1"
>
Left swashplate servomotor, pitch axis
</output>
<output
name=
"MAIN2"
>
Right swashplate servomotor, roll axis
</output>
<output
name=
"MAIN3"
>
Upper rotor (CCW)
</output>
<output
name=
"MAIN4"
>
Lower rotor (CW)
</output>
</airframe>
</airframe_group>
<airframe_group
image=
"AirframeFlyingWing.png"
name=
"Flying Wing"
>
<airframe
id=
"3030"
maintainer=
"Simon Wilks <simon@px4.io>"
name=
"IO Camflyer"
>
<maintainer>
Simon Wilks
<
simon@px4.io
>
</maintainer>
...
...
@@ -160,6 +170,13 @@
<maintainer>
Lorenz Meier
<
lorenz@px4.io
>
</maintainer>
<type>
Quadrotor x
</type>
</airframe>
<airframe
id=
"4009"
maintainer=
"Mark Whitehorn <kd0aij@gmail.com>"
name=
"Lumenier QAV250"
>
<maintainer>
Mark Whitehorn
<
kd0aij@gmail.com
>
</maintainer>
<type>
Quadrotor x
</type>
<output
name=
"AUX1"
>
feed-through of RC AUX1 channel
</output>
<output
name=
"AUX2"
>
feed-through of RC AUX2 channel
</output>
<output
name=
"AUX3"
>
feed-through of RC AUX3 channel
</output>
</airframe>
<airframe
id=
"4010"
maintainer=
"Lorenz Meier <lorenz@px4.io>"
name=
"DJI Flame Wheel F330"
>
<maintainer>
Lorenz Meier
<
lorenz@px4.io
>
</maintainer>
<type>
Quadrotor x
</type>
...
...
@@ -182,6 +199,10 @@
<maintainer>
Thomas Gubler
<
thomas@px4.io
>
</maintainer>
<type>
Quadrotor x
</type>
</airframe>
<airframe
id=
"4030"
maintainer=
"Andreas Antener <andreas@uaventure.com>"
name=
"Generic Quadrotor X config"
>
<maintainer>
Andreas Antener
<
andreas@uaventure.com
>
</maintainer>
<type>
Quadrotor x
</type>
</airframe>
</airframe_group>
<airframe_group
image=
""
name=
"Rover"
>
<airframe
id=
"50001"
maintainer=
"John Doe <john@example.com>"
name=
"Axial Racing AX10"
>
...
...
@@ -227,8 +248,8 @@
<output
name=
"AUX3"
>
feed-through of RC AUX3 channel
</output>
<output
name=
"MAIN1"
>
aileron
</output>
<output
name=
"MAIN2"
>
elevator
</output>
<output
name=
"MAIN3"
>
throttle
</output>
<output
name=
"MAIN4"
>
rudder
</output>
<output
name=
"MAIN3"
>
rudder
</output>
<output
name=
"MAIN4"
>
throttle
</output>
<output
name=
"MAIN5"
>
flaps
</output>
</airframe>
<airframe
id=
"2102"
maintainer=
"Lorenz Meier <lorenz@px4.io>"
name=
"Skywalker (3DR Aero)"
>
...
...
@@ -265,9 +286,38 @@
<output
name=
"MAIN4"
>
rudder
</output>
<output
name=
"MAIN5"
>
flaps
</output>
</airframe>
<airframe
id=
"2105"
maintainer=
"Andreas Antener <andreas@uaventure.com>"
name=
"Bormatec Maja"
>
<maintainer>
Andreas Antener
<
andreas@uaventure.com
>
</maintainer>
<type>
Standard Plane
</type>
<output
name=
"AUX1"
>
feed-through of RC AUX1 channel
</output>
<output
name=
"AUX2"
>
feed-through of RC AUX2 channel
</output>
<output
name=
"AUX3"
>
feed-through of RC AUX3 channel
</output>
<output
name=
"MAIN1"
>
aileron
</output>
<output
name=
"MAIN2"
>
aileron
</output>
<output
name=
"MAIN3"
>
elevator
</output>
<output
name=
"MAIN4"
>
rudder
</output>
<output
name=
"MAIN5"
>
throttle
</output>
<output
name=
"MAIN6"
>
wheel
</output>
<output
name=
"MAIN7"
>
flaps
</output>
</airframe>
<airframe
id=
"2106"
maintainer=
"Andreas Antener <andreas@uaventure.com>"
name=
"Applied Aeronautics Albatross"
>
<maintainer>
Andreas Antener
<
andreas@uaventure.com
>
</maintainer>
<type>
Standard Plane
</type>
<output
name=
"AUX1"
>
feed-through of RC AUX1 channel
</output>
<output
name=
"AUX2"
>
feed-through of RC AUX2 channel
</output>
<output
name=
"AUX3"
>
feed-through of RC AUX3 channel
</output>
<output
name=
"MAIN1"
>
aileron right
</output>
<output
name=
"MAIN2"
>
aileron left
</output>
<output
name=
"MAIN3"
>
v-tail right
</output>
<output
name=
"MAIN4"
>
v-tail left
</output>
<output
name=
"MAIN5"
>
throttle
</output>
<output
name=
"MAIN6"
>
wheel
</output>
<output
name=
"MAIN7"
>
flaps right
</output>
<output
name=
"MAIN8"
>
flaps left
</output>
</airframe>
</airframe_group>
<airframe_group
image=
""
name=
"Standard VTOL"
>
<airframe
id=
"13005"
maintainer=
"Simon Wilks <simon@uaventure.com>"
name=
"
Generic AAERT tailplane airframe with
Quad VTOL."
>
<airframe
id=
"13005"
maintainer=
"Simon Wilks <simon@uaventure.com>"
name=
"
Fun Cub
Quad VTOL."
>
<maintainer>
Simon Wilks
<
simon@uaventure.com
>
</maintainer>
<type>
Standard VTOL
</type>
</airframe>
...
...
@@ -275,6 +325,10 @@
<maintainer>
Simon Wilks
<
simon@uaventure.com
>
</maintainer>
<type>
Standard VTOL
</type>
</airframe>
<airframe
id=
"13007"
maintainer=
"Sander Smeets <sander@droneslab.com>"
name=
"Generic AAVVT v-tail plane airframe with Quad VTOL."
>
<maintainer>
Sander Smeets
<
sander@droneslab.com
>
</maintainer>
<type>
Standard VTOL
</type>
</airframe>
</airframe_group>
<airframe_group
image=
""
name=
"Tricopter Y+"
>
<airframe
id=
"14001"
maintainer=
"Trent Lukaczyk <aerialhedgehog@gmail.com>"
name=
"Generic Tricopter Y+ Geometry"
>
...
...
src/FlightMap/MapItems/MissionItemIndicator.qml
View file @
30bcc904
...
...
@@ -43,7 +43,7 @@ MapQuickItem {
MissionItemIndexLabel
{
id
:
_label
isCurrentItem
:
missionItem
.
isCurrentItem
label
:
missionItem
.
sequenceNumber
label
:
missionItem
.
sequenceNumber
==
0
?
"
H
"
:
missionItem
.
sequenceNumber
onClicked
:
_item
.
clicked
()
}
}
src/MissionEditor/MissionEditor.qml
View file @
30bcc904
...
...
@@ -219,6 +219,7 @@ QGCView {
//offlineHomePosition = coordinate
}
else
if
(
addMissionItemsButton
.
checked
)
{
var
index
=
controller
.
addMissionItem
(
coordinate
)
addMissionItemsButtonAutoOffTimer
.
stop
()
addMissionItemsButtonAutoOffTimer
.
start
()
setCurrentItem
(
index
)
}
else
{
...
...
src/MissionManager/MavCmdInfo.json
View file @
30bcc904
...
...
@@ -594,7 +594,7 @@
"friendlyName"
:
"VTOL Transition"
,
"description"
:
"Perform flight mode transition"
,
"category"
:
"Basic"
,
"param
7
"
:
{
"param
1
"
:
{
"label"
:
"Mode:"
,
"default"
:
3
,
"decimalPlaces"
:
0
,
...
...
src/MissionManager/MissionController.cc
View file @
30bcc904
...
...
@@ -484,19 +484,22 @@ void MissionController::_initAllMissionItems(void)
}
homeItem
->
setHomePositionSpecialCase
(
true
);
if
(
_activeVehicle
)
{
homeItem
->
setCoordinate
(
_activeVehicle
->
homePosition
());
homeItem
->
setHomePositionValid
(
_activeVehicle
->
homePositionAvailable
());
if
(
homeItem
->
homePositionValid
())
{
homeItem
->
setCoordinate
(
_activeVehicle
->
homePosition
());
}
}
else
{
homeItem
->
setHomePositionValid
(
false
);
}
homeItem
->
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
homeItem
->
setFrame
(
MAV_FRAME_GLOBAL
);
if
(
!
homeItem
->
homePositionValid
())
{
QGeoCoordinate
homeCoord
=
homeItem
->
coordinate
();
homeCoord
.
setAltitude
(
0.0
);
homeItem
->
setCoordinate
(
homeCoord
);
// Set a bogus home position, the important value is 0.0 Altitude
homeItem
->
setCoordinate
(
QGeoCoordinate
(
37.803784
,
-
122.462276
,
0.0
));
}
qDebug
()
<<
"home item"
<<
homeItem
->
homePositionValid
()
<<
homeItem
->
coordinate
();
for
(
int
i
=
0
;
i
<
_missionItems
->
count
();
i
++
)
{
_initMissionItem
(
qobject_cast
<
MissionItem
*>
(
_missionItems
->
get
(
i
)));
}
...
...
src/ViewWidgets/LogDownload.qml
View file @
30bcc904
...
...
@@ -94,7 +94,7 @@ QGCView {
//-- Have we received this entry already?
if
(
controller
.
model
.
get
(
styleData
.
row
).
received
)
{
var
d
=
controller
.
model
.
get
(
styleData
.
row
).
time
if
(
d
.
getUTCFullYear
()
<
198
0
)
if
(
d
.
getUTCFullYear
()
<
201
0
)
return
"
Date Unknown
"
else
return
d
.
toLocaleString
()
...
...
src/ViewWidgets/LogDownloadController.cc
View file @
30bcc904
...
...
@@ -67,6 +67,7 @@ LogDownloadController::LogDownloadController(void)
,
_requestingLogEntries
(
false
)
,
_downloadingLogs
(
false
)
,
_retries
(
0
)
,
_apmOneBased
(
0
)
{
MultiVehicleManager
*
manager
=
qgcApp
()
->
toolbox
()
->
multiVehicleManager
();
connect
(
manager
,
&
MultiVehicleManager
::
activeVehicleChanged
,
this
,
&
LogDownloadController
::
_setActiveVehicle
);
...
...
@@ -114,6 +115,11 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t
}
//-- If this is the first, pre-fill it
if
(
!
_logEntriesModel
.
count
()
&&
num_logs
>
0
)
{
//-- Is this APM? They send a first entry with bogus ID and only the
// count is valid. From now on, all entries are 1-based.
if
(
_vehicle
->
firmwareType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
_apmOneBased
=
1
;
}
for
(
int
i
=
0
;
i
<
num_logs
;
i
++
)
{
QGCLogEntry
*
entry
=
new
QGCLogEntry
(
i
);
_logEntriesModel
.
append
(
entry
);
...
...
@@ -121,14 +127,18 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t
}
//-- Update this log record
if
(
num_logs
>
0
)
{
if
(
id
<
_logEntriesModel
.
count
())
{
QGCLogEntry
*
entry
=
_logEntriesModel
[
id
];
entry
->
setSize
(
size
);
entry
->
setTime
(
QDateTime
::
fromTime_t
(
time_utc
));
entry
->
setReceived
(
true
);
entry
->
setStatus
(
QString
(
"Available"
));
}
else
{
qWarning
()
<<
"Received log entry for out-of-bound index:"
<<
id
;
//-- Skip if empty (APM first packet)
if
(
size
)
{
id
-=
_apmOneBased
;
if
(
id
<
_logEntriesModel
.
count
())
{
QGCLogEntry
*
entry
=
_logEntriesModel
[
id
];
entry
->
setSize
(
size
);
entry
->
setTime
(
QDateTime
::
fromTime_t
(
time_utc
));
entry
->
setReceived
(
true
);
entry
->
setStatus
(
QString
(
"Available"
));
}
else
{
qWarning
()
<<
"Received log entry for out-of-bound index:"
<<
id
;
}
}
}
else
{
//-- No logs to list
...
...
@@ -164,13 +174,18 @@ LogDownloadController::_entriesComplete()
//----------------------------------------------------------------------------------------
void
LogDownloadController
::
_resetSelection
()
LogDownloadController
::
_resetSelection
(
bool
canceled
)
{
int
num_logs
=
_logEntriesModel
.
count
();
for
(
int
i
=
0
;
i
<
num_logs
;
i
++
)
{
QGCLogEntry
*
entry
=
_logEntriesModel
[
i
];
if
(
entry
)
{
entry
->
setSelected
(
false
);
if
(
entry
->
selected
())
{
if
(
canceled
)
{
entry
->
setStatus
(
QString
(
"Canceled"
));
}
entry
->
setSelected
(
false
);
}
}
}
emit
selectionChanged
();
...
...
@@ -227,6 +242,9 @@ LogDownloadController::_findMissingEntries()
if
(
end
<
0
)
{
end
=
start
;
}
//-- APM "Fix"
start
+=
_apmOneBased
;
end
+=
_apmOneBased
;
//-- Request these entries again
_requestLogList
((
uint32_t
)
start
,
(
uint32_t
)
end
);
}
else
{
...
...
@@ -241,6 +259,8 @@ LogDownloadController::_logData(UASInterface* uas, uint32_t ofs, uint16_t id, ui
if
(
!
_uas
||
uas
!=
_uas
||
!
_downloadData
)
{
return
;
}
//-- APM "Fix"
id
-=
_apmOneBased
;
if
(
_downloadData
->
ID
!=
id
)
{
qWarning
()
<<
"Received log data for wrong log"
;
return
;
...
...
@@ -360,6 +380,8 @@ void
LogDownloadController
::
_requestLogData
(
uint8_t
id
,
uint32_t
offset
,
uint32_t
count
)
{
if
(
_vehicle
)
{
//-- APM "Fix"
id
+=
_apmOneBased
;
qCDebug
(
LogDownloadLog
)
<<
"Request log data (id:"
<<
id
<<
"offset:"
<<
offset
<<
"size:"
<<
count
<<
")"
;
mavlink_message_t
msg
;
mavlink_msg_log_request_data_pack
(
...
...
@@ -423,6 +445,16 @@ LogDownloadController::download(void)
if
(
!
_downloadPath
.
isEmpty
())
{
if
(
!
_downloadPath
.
endsWith
(
QDir
::
separator
()))
_downloadPath
+=
QDir
::
separator
();
//-- Iterate selected entries and shown them as waiting
int
num_logs
=
_logEntriesModel
.
count
();
for
(
int
i
=
0
;
i
<
num_logs
;
i
++
)
{
QGCLogEntry
*
entry
=
_logEntriesModel
[
i
];
if
(
entry
)
{
if
(
entry
->
selected
())
{
entry
->
setStatus
(
QString
(
"Waiting"
));
}
}
}
//-- Start download process
_downloadingLogs
=
true
;
emit
downloadingLogsChanged
();
...
...
@@ -464,13 +496,18 @@ LogDownloadController::_prepareLogDownload()
emit
selectionChanged
();
bool
result
=
false
;
QString
ftime
;
if
(
entry
->
time
().
date
().
year
()
<
198
0
)
{
if
(
entry
->
time
().
date
().
year
()
<
201
0
)
{
ftime
=
"UnknownDate"
;
}
else
{
ftime
=
entry
->
time
().
toString
(
"yyyy-M-d-hh-mm-ss"
);
}
_downloadData
=
new
LogDownloadData
(
entry
);
_downloadData
->
filename
=
QString
(
"log_"
)
+
QString
::
number
(
entry
->
id
())
+
"_"
+
ftime
+
".txt"
;
_downloadData
->
filename
=
QString
(
"log_"
)
+
QString
::
number
(
entry
->
id
())
+
"_"
+
ftime
;
if
(
_vehicle
->
firmwareType
()
==
MAV_AUTOPILOT_PX4
)
{
_downloadData
->
filename
+=
".px4log"
;
}
else
{
_downloadData
->
filename
+=
".bin"
;
}
_downloadData
->
file
.
setFileName
(
_downloadPath
+
_downloadData
->
filename
);
//-- Append a number to the end if the filename already exists
if
(
_downloadData
->
file
.
exists
()){
...
...
@@ -539,7 +576,7 @@ LogDownloadController::cancel(void)
delete
_downloadData
;
_downloadData
=
0
;
}
_resetSelection
();
_resetSelection
(
true
);
_downloadingLogs
=
false
;
emit
downloadingLogsChanged
();
}
...
...
src/ViewWidgets/LogDownloadController.h
View file @
30bcc904
...
...
@@ -171,7 +171,7 @@ private:
void
_findMissingEntries
();
void
_receivedAllEntries
();
void
_receivedAllData
();
void
_resetSelection
();
void
_resetSelection
(
bool
canceled
=
false
);
void
_findMissingData
();
void
_requestLogList
(
uint32_t
start
=
0
,
uint32_t
end
=
0xFFFF
);
void
_requestLogData
(
uint8_t
id
,
uint32_t
offset
=
0
,
uint32_t
count
=
0xFFFFFFFF
);
...
...
@@ -187,6 +187,7 @@ private:
bool
_requestingLogEntries
;
bool
_downloadingLogs
;
int
_retries
;
int
_apmOneBased
;
QString
_downloadPath
;
};
...
...
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