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
89355f51
Unverified
Commit
89355f51
authored
Sep 01, 2020
by
Don Gagne
Committed by
GitHub
Sep 01, 2020
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #9049 from DonLakeFlyer/ControllerVehicle
Plan fixes
parents
0030c00e
485ceb3d
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
32 additions
and
31 deletions
+32
-31
v2.0
libs/mavlink/include/mavlink/v2.0
+1
-1
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+7
-6
QGCCameraIO.cc
src/Camera/QGCCameraIO.cc
+9
-8
MissionController.cc
src/MissionManager/MissionController.cc
+4
-4
MissionSettingsEditor.qml
src/PlanView/MissionSettingsEditor.qml
+5
-4
MockLink.cc
src/comm/MockLink.cc
+6
-8
No files found.
v2.0
@
d1eea85b
Subproject commit
99a977433a13705cd0624f8ff3b5f5210d526ba9
Subproject commit
d1eea85b685eec2204ad31c7f7f51486f218f86b
src/Camera/QGCCameraControl.cc
View file @
89355f51
...
...
@@ -1174,12 +1174,13 @@ QGCCameraControl::_requestAllParameters()
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_message_t
msg
;
mavlink_msg_param_ext_request_list_pack_chan
(
static_cast
<
uint8_t
>
(
mavlink
->
getSystemId
()),
static_cast
<
uint8_t
>
(
mavlink
->
getComponentId
()),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
static_cast
<
uint8_t
>
(
_vehicle
->
id
()),
static_cast
<
uint8_t
>
(
compID
()));
static_cast
<
uint8_t
>
(
mavlink
->
getSystemId
()),
static_cast
<
uint8_t
>
(
mavlink
->
getComponentId
()),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
static_cast
<
uint8_t
>
(
_vehicle
->
id
()),
static_cast
<
uint8_t
>
(
compID
()),
0
);
// trimmed messages = false
_vehicle
->
sendMessageOnLinkThreadSafe
(
_vehicle
->
priorityLink
(),
msg
);
qCDebug
(
CameraControlVerboseLog
)
<<
"Request all parameters"
;
}
...
...
src/Camera/QGCCameraIO.cc
View file @
89355f51
...
...
@@ -356,14 +356,15 @@ QGCCameraParamIO::paramRequest(bool reset)
strncpy
(
param_id
,
_fact
->
name
().
toStdString
().
c_str
(),
MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN
);
mavlink_message_t
msg
;
mavlink_msg_param_ext_request_read_pack_chan
(
static_cast
<
uint8_t
>
(
_pMavlink
->
getSystemId
()),
static_cast
<
uint8_t
>
(
_pMavlink
->
getComponentId
()),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
static_cast
<
uint8_t
>
(
_vehicle
->
id
()),
static_cast
<
uint8_t
>
(
_control
->
compID
()),
param_id
,
-
1
);
static_cast
<
uint8_t
>
(
_pMavlink
->
getSystemId
()),
static_cast
<
uint8_t
>
(
_pMavlink
->
getComponentId
()),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
static_cast
<
uint8_t
>
(
_vehicle
->
id
()),
static_cast
<
uint8_t
>
(
_control
->
compID
()),
param_id
,
-
1
,
0
);
// trimmed messages = false
_vehicle
->
sendMessageOnLinkThreadSafe
(
_vehicle
->
priorityLink
(),
msg
);
_paramRequestTimer
.
start
();
}
src/MissionManager/MissionController.cc
View file @
89355f51
...
...
@@ -392,14 +392,14 @@ VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate /*coordin
VisualMissionItem
*
MissionController
::
insertLandItem
(
QGeoCoordinate
coordinate
,
int
visualItemIndex
,
bool
makeCurrentItem
)
{
if
(
_
manag
erVehicle
->
fixedWing
())
{
if
(
_
controll
erVehicle
->
fixedWing
())
{
FixedWingLandingComplexItem
*
fwLanding
=
qobject_cast
<
FixedWingLandingComplexItem
*>
(
insertComplexMissionItem
(
FixedWingLandingComplexItem
::
name
,
coordinate
,
visualItemIndex
,
makeCurrentItem
));
return
fwLanding
;
}
else
if
(
_
manag
erVehicle
->
vtol
())
{
}
else
if
(
_
controll
erVehicle
->
vtol
())
{
VTOLLandingComplexItem
*
vtolLanding
=
qobject_cast
<
VTOLLandingComplexItem
*>
(
insertComplexMissionItem
(
VTOLLandingComplexItem
::
name
,
coordinate
,
visualItemIndex
,
makeCurrentItem
));
return
vtolLanding
;
}
else
{
return
_insertSimpleMissionItemWorker
(
coordinate
,
_
manag
erVehicle
->
vtol
()
?
MAV_CMD_NAV_VTOL_LAND
:
MAV_CMD_NAV_RETURN_TO_LAUNCH
,
visualItemIndex
,
makeCurrentItem
);
return
_insertSimpleMissionItemWorker
(
coordinate
,
_
controll
erVehicle
->
vtol
()
?
MAV_CMD_NAV_VTOL_LAND
:
MAV_CMD_NAV_RETURN_TO_LAUNCH
,
visualItemIndex
,
makeCurrentItem
);
}
}
...
...
@@ -1240,7 +1240,7 @@ void MissionController::_recalcFlightPathSegments(void)
bool
firstCoordinateNotFound
=
true
;
VisualMissionItem
*
lastFlyThroughVI
=
qobject_cast
<
VisualMissionItem
*>
(
_visualItems
->
get
(
0
));
bool
linkEndToHome
=
false
;
bool
linkStartToHome
=
_
manag
erVehicle
->
rover
()
?
true
:
false
;
bool
linkStartToHome
=
_
controll
erVehicle
->
rover
()
?
true
:
false
;
bool
foundRTL
=
false
;
bool
homePositionValid
=
_settingsItem
->
coordinate
().
isValid
();
bool
roiActive
=
false
;
...
...
src/PlanView/MissionSettingsEditor.qml
View file @
89355f51
...
...
@@ -37,6 +37,7 @@ Rectangle {
property
bool
_showCameraSection
:
(
_waypointsOnlyMode
||
QGroundControl
.
corePlugin
.
showAdvancedUI
)
&&
!
_controllerVehicle
.
apmFirmware
property
bool
_simpleMissionStart
:
QGroundControl
.
corePlugin
.
options
.
showSimpleMissionStart
property
bool
_showFlightSpeed
:
!
_controllerVehicle
.
vtol
&&
!
_simpleMissionStart
&&
!
_controllerVehicle
.
apmFirmware
property
bool
_allowFWVehicleTypeSelection
:
_noMissionItemsAdded
&&
!
globals
.
activeVehicle
readonly
property
string
_firmwareLabel
:
qsTr
(
"
Firmware
"
)
readonly
property
string
_vehicleLabel
:
qsTr
(
"
Vehicle
"
)
...
...
@@ -197,11 +198,11 @@ Rectangle {
fact
:
QGroundControl
.
settingsManager
.
appSettings
.
offlineEditingFirmwareClass
indexModel
:
false
Layout.preferredWidth
:
_fieldWidth
visible
:
_multipleFirmware
&&
_
noMissionItemsAdded
visible
:
_multipleFirmware
&&
_
allowFWVehicleTypeSelection
}
QGCLabel
{
text
:
_controllerVehicle
.
firmwareTypeString
visible
:
_multipleFirmware
&&
!
_
noMissionItemsAdded
visible
:
_multipleFirmware
&&
!
_
allowFWVehicleTypeSelection
}
QGCLabel
{
...
...
@@ -213,11 +214,11 @@ Rectangle {
fact
:
QGroundControl
.
settingsManager
.
appSettings
.
offlineEditingVehicleClass
indexModel
:
false
Layout.preferredWidth
:
_fieldWidth
visible
:
_multipleVehicleTypes
&&
_
noMissionItemsAdded
visible
:
_multipleVehicleTypes
&&
_
allowFWVehicleTypeSelection
}
QGCLabel
{
text
:
_controllerVehicle
.
vehicleTypeString
visible
:
_multipleVehicleTypes
&&
!
_
noMissionItemsAdded
visible
:
_multipleVehicleTypes
&&
!
_
allowFWVehicleTypeSelection
}
QGCLabel
{
...
...
src/comm/MockLink.cc
View file @
89355f51
...
...
@@ -7,7 +7,6 @@
*
****************************************************************************/
#include "MockLink.h"
#include "QGCLoggingCategory.h"
#include "QGCApplication.h"
...
...
@@ -28,11 +27,6 @@
QGC_LOGGING_CATEGORY
(
MockLinkLog
,
"MockLinkLog"
)
QGC_LOGGING_CATEGORY
(
MockLinkVerboseLog
,
"MockLinkVerboseLog"
)
/// @file
/// @brief Mock implementation of a Link.
///
/// @author Don Gagne <don@thegagnes.com>
// Vehicle position is set close to default Gazebo vehicle location. This allows for multi-vehicle
// testing of a gazebo vehicle and a mocklink vehicle
#if 1
...
...
@@ -410,12 +404,14 @@ void MockLink::_sendBatteryStatus(void)
mavlink_message_t
msg
;
uint16_t
rgVoltages
[
10
];
uint16_t
rgVoltagesNone
[
10
];
uint16_t
rgVoltagesExtNone
[
4
];
for
(
int
i
=
0
;
i
<
10
;
i
++
)
{
rgVoltages
[
i
]
=
UINT16_MAX
;
rgVoltagesNone
[
i
]
=
UINT16_MAX
;
}
rgVoltages
[
0
]
=
rgVoltages
[
1
]
=
rgVoltages
[
2
]
=
4200
;
memset
(
rgVoltagesExtNone
,
0
,
sizeof
(
rgVoltagesExtNone
));
mavlink_msg_battery_status_pack_chan
(
_vehicleSystemId
,
...
...
@@ -432,7 +428,8 @@ void MockLink::_sendBatteryStatus(void)
-
1
,
// energy consumed not supported
_battery1PctRemaining
,
_battery1TimeRemaining
,
_battery1ChargeState
);
_battery1ChargeState
,
rgVoltagesExtNone
);
respondWithMavlinkMessage
(
msg
);
mavlink_msg_battery_status_pack_chan
(
...
...
@@ -450,7 +447,8 @@ void MockLink::_sendBatteryStatus(void)
-
1
,
// energy consumed not supported
_battery2PctRemaining
,
_battery2TimeRemaining
,
_battery2ChargeState
);
_battery2ChargeState
,
rgVoltagesExtNone
);
respondWithMavlinkMessage
(
msg
);
}
...
...
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