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
abc118d0
Commit
abc118d0
authored
Oct 03, 2016
by
Don Gagne
Committed by
GitHub
Oct 03, 2016
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #4096 from DonLakeFlyer/Mav2Prep
Must use pack_chan and encode_chan due to mav 2.0 problem
parents
01c4ef3c
63f0271b
Changes
34
Hide whitespace changes
Inline
Side-by-side
Showing
34 changed files
with
774 additions
and
885 deletions
+774
-885
APMSensorsComponentController.cc
src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
+6
-2
ESP8266ComponentController.cc
src/AutoPilotPlugins/Common/ESP8266ComponentController.cc
+5
-2
ParameterManager.cc
src/FactSystem/ParameterManager.cc
+44
-23
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+23
-13
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+5
-5
APMGeoFenceManager.cc
src/FirmwarePlugin/APM/APMGeoFenceManager.cc
+19
-17
APMRallyPointManager.cc
src/FirmwarePlugin/APM/APMRallyPointManager.cc
+21
-19
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+12
-4
FirmwarePlugin.cc
src/FirmwarePlugin/FirmwarePlugin.cc
+2
-1
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+2
-1
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+30
-10
FollowMe.cc
src/FollowMe/FollowMe.cc
+6
-5
RTCMMavlink.cc
src/GPS/RTCM/RTCMMavlink.cc
+6
-3
MissionManager.cc
src/MissionManager/MissionManager.cc
+33
-9
QGroundControlQmlGlobal.cc
src/QmlControls/QGroundControlQmlGlobal.cc
+0
-6
QGroundControlQmlGlobal.h
src/QmlControls/QGroundControlQmlGlobal.h
+0
-3
MultiVehicleManager.cc
src/Vehicle/MultiVehicleManager.cc
+10
-9
Vehicle.cc
src/Vehicle/Vehicle.cc
+55
-20
Vehicle.h
src/Vehicle/Vehicle.h
+0
-4
LogDownloadController.cc
src/ViewWidgets/LogDownloadController.cc
+22
-19
LinkInterface.h
src/comm/LinkInterface.h
+8
-10
LinkManager.cc
src/comm/LinkManager.cc
+1
-1
LogReplayLink.cc
src/comm/LogReplayLink.cc
+1
-1
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+2
-153
MAVLinkProtocol.h
src/comm/MAVLinkProtocol.h
+3
-67
MockLink.cc
src/comm/MockLink.cc
+152
-136
MockLinkFileServer.cc
src/comm/MockLinkFileServer.cc
+8
-7
MockLinkMissionItemHandler.cc
src/comm/MockLinkMissionItemHandler.cc
+30
-20
FileManager.cc
src/uas/FileManager.cc
+17
-9
UAS.cc
src/uas/UAS.cc
+232
-190
QGCMAVLinkInspector.cc
src/ui/QGCMAVLinkInspector.cc
+0
-80
QGCMAVLinkInspector.h
src/ui/QGCMAVLinkInspector.h
+0
-5
QGCMAVLinkInspector.ui
src/ui/QGCMAVLinkInspector.ui
+19
-22
MavlinkSettings.qml
src/ui/preferences/MavlinkSettings.qml
+0
-9
No files found.
src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
View file @
abc118d0
...
...
@@ -468,9 +468,13 @@ void APMSensorsComponentController::nextClicked(void)
ack
.
command
=
0
;
ack
.
result
=
1
;
mavlink_msg_command_ack_encode
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
&
msg
,
&
ack
);
mavlink_msg_command_ack_encode_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
ack
);
_vehicle
->
sendMessageOn
PriorityLink
(
msg
);
_vehicle
->
sendMessageOn
Link
(
_vehicle
->
priorityLink
(),
msg
);
if
(
_compassMotCalInProgress
)
{
_stopCalibration
(
StopCalibrationSuccess
);
...
...
src/AutoPilotPlugins/Common/ESP8266ComponentController.cc
View file @
abc118d0
...
...
@@ -318,9 +318,11 @@ void
ESP8266ComponentController
::
_reboot
()
{
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink_msg_command_long_pack_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(),
MAV_COMP_ID_UDP_BRIDGE
,
...
...
@@ -339,9 +341,10 @@ void
ESP8266ComponentController
::
_restoreDefaults
()
{
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink_msg_command_long_pack
_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(),
MAV_COMP_ID_UDP_BRIDGE
,
...
...
src/FactSystem/ParameterManager.cc
View file @
abc118d0
...
...
@@ -395,7 +395,12 @@ void ParameterManager::refreshAllParameters(uint8_t componentID)
Q_ASSERT
(
mavlink
);
mavlink_message_t
msg
;
mavlink_msg_param_request_list_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
componentID
);
mavlink_msg_param_request_list_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(),
componentID
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
QString
what
=
(
componentID
==
MAV_COMP_ID_ALL
)
?
"MAV_COMP_ID_ALL"
:
QString
::
number
(
componentID
);
...
...
@@ -618,13 +623,14 @@ void ParameterManager::_readParameterRaw(int componentId, const QString& paramNa
char
fixedParamName
[
MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN
];
strncpy
(
fixedParamName
,
paramName
.
toStdString
().
c_str
(),
sizeof
(
fixedParamName
));
mavlink_msg_param_request_read_pack
(
_mavlink
->
getSystemId
(),
// Our system id
_mavlink
->
getComponentId
(),
// Our component id
&
msg
,
// Pack into this mavlink_message_t
_vehicle
->
id
(),
// Target system id
componentId
,
// Target component id
fixedParamName
,
// Named parameter being requested
paramIndex
);
// Parameter index being requested, -1 for named
mavlink_msg_param_request_read_pack_chan
(
_mavlink
->
getSystemId
(),
// QGC system id
_mavlink
->
getComponentId
(),
// QGC component id
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
// Pack into this mavlink_message_t
_vehicle
->
id
(),
// Target system id
componentId
,
// Target component id
fixedParamName
,
// Named parameter being requested
paramIndex
);
// Parameter index being requested, -1 for named
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
...
...
@@ -677,7 +683,11 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN
strncpy
(
p
.
param_id
,
paramName
.
toStdString
().
c_str
(),
sizeof
(
p
.
param_id
));
mavlink_message_t
msg
;
mavlink_msg_param_set_encode
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
&
p
);
mavlink_msg_param_set_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
p
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
...
...
@@ -756,7 +766,11 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian
p
.
target_system
=
(
uint8_t
)
_vehicle
->
id
();
p
.
target_component
=
(
uint8_t
)
componentId
;
mavlink_message_t
msg
;
mavlink_msg_param_set_encode
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
&
p
);
mavlink_msg_param_set_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
p
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
// Give the user some feedback things loaded properly
...
...
@@ -787,7 +801,13 @@ void ParameterManager::_saveToEEPROM(void)
_saveRequired
=
false
;
if
(
_vehicle
->
firmwarePlugin
()
->
isCapable
(
_vehicle
,
FirmwarePlugin
::
MavCmdPreflightStorageCapability
))
{
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
0
,
MAV_CMD_PREFLIGHT_STORAGE
,
1
,
1
,
-
1
,
-
1
,
-
1
,
0
,
0
,
0
);
mavlink_msg_command_long_pack_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(),
0
,
MAV_CMD_PREFLIGHT_STORAGE
,
1
,
1
,
-
1
,
-
1
,
-
1
,
0
,
0
,
0
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
qCDebug
(
ParameterManagerLog
)
<<
"_saveToEEPROM"
;
}
else
{
...
...
@@ -1409,17 +1429,18 @@ void ParameterManager::resetAllParametersToDefaults(void)
mavlink_message_t
msg
;
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
// Target systeem
_vehicle
->
defaultComponentId
(),
// Target component
MAV_CMD_PREFLIGHT_STORAGE
,
0
,
// Confirmation
2
,
// 2 = Reset params to default
-
1
,
// -1 = No change to mission storage
0
,
// 0 = Ignore
0
,
0
,
0
,
0
);
// Unused
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_command_long_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(),
// Target systeem
_vehicle
->
defaultComponentId
(),
// Target component
MAV_CMD_PREFLIGHT_STORAGE
,
0
,
// Confirmation
2
,
// 2 = Reset params to default
-
1
,
// -1 = No change to mission storage
0
,
// 0 = Ignore
0
,
0
,
0
,
0
);
// Unused
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
abc118d0
...
...
@@ -211,7 +211,7 @@ int APMFirmwarePlugin::manualControlReservedButtonCount(void)
return
-
1
;
}
void
APMFirmwarePlugin
::
_handleParamValue
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
void
APMFirmwarePlugin
::
_handle
Incoming
ParamValue
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
{
Q_UNUSED
(
vehicle
);
...
...
@@ -251,10 +251,14 @@ void APMFirmwarePlugin::_handleParamValue(Vehicle* vehicle, mavlink_message_t* m
paramValue
.
param_value
=
paramUnion
.
param_float
;
mavlink_msg_param_value_encode
(
message
->
sysid
,
message
->
compid
,
message
,
&
paramValue
);
mavlink_msg_param_value_encode_chan
(
message
->
sysid
,
message
->
compid
,
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
message
,
&
paramValue
);
}
void
APMFirmwarePlugin
::
_handle
ParamSet
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
void
APMFirmwarePlugin
::
_handle
OutgoingParamSet
(
Vehicle
*
vehicle
,
LinkInterface
*
outgoingLink
,
mavlink_message_t
*
message
)
{
Q_UNUSED
(
vehicle
);
...
...
@@ -294,10 +298,10 @@ void APMFirmwarePlugin::_handleParamSet(Vehicle* vehicle, mavlink_message_t* mes
qCCritical
(
APMFirmwarePluginLog
)
<<
"Invalid/Unsupported data type used in parameter:"
<<
paramSet
.
param_type
;
}
mavlink_msg_param_set_encode
(
message
->
sysid
,
message
->
compid
,
message
,
&
paramSet
);
mavlink_msg_param_set_encode
_chan
(
message
->
sysid
,
message
->
compid
,
outgoingLink
->
mavlinkChannel
()
,
message
,
&
paramSet
);
}
bool
APMFirmwarePlugin
::
_handleStatusText
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
bool
APMFirmwarePlugin
::
_handle
Incoming
StatusText
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
{
QString
messageText
;
...
...
@@ -406,7 +410,7 @@ bool APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m
return
true
;
}
void
APMFirmwarePlugin
::
_handleHeartbeat
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
void
APMFirmwarePlugin
::
_handle
Incoming
Heartbeat
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
{
bool
flying
=
false
;
...
...
@@ -435,19 +439,19 @@ bool APMFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_m
switch
(
message
->
msgid
)
{
case
MAVLINK_MSG_ID_PARAM_VALUE
:
_handleParamValue
(
vehicle
,
message
);
_handle
Incoming
ParamValue
(
vehicle
,
message
);
break
;
case
MAVLINK_MSG_ID_STATUSTEXT
:
return
_handleStatusText
(
vehicle
,
message
);
return
_handle
Incoming
StatusText
(
vehicle
,
message
);
case
MAVLINK_MSG_ID_HEARTBEAT
:
_handleHeartbeat
(
vehicle
,
message
);
_handle
Incoming
Heartbeat
(
vehicle
,
message
);
break
;
}
return
true
;
}
void
APMFirmwarePlugin
::
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
void
APMFirmwarePlugin
::
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
LinkInterface
*
outgoingLink
,
mavlink_message_t
*
message
)
{
//-- Don't process messages to/from UDP Bridge. It doesn't suffer from these issues
if
(
message
->
compid
==
MAV_COMP_ID_UDP_BRIDGE
)
{
...
...
@@ -456,7 +460,7 @@ void APMFirmwarePlugin::adjustOutgoingMavlinkMessage(Vehicle* vehicle, mavlink_m
switch
(
message
->
msgid
)
{
case
MAVLINK_MSG_ID_PARAM_SET
:
_handle
ParamSet
(
vehicle
,
message
);
_handle
OutgoingParamSet
(
vehicle
,
outgoingLink
,
message
);
break
;
}
}
...
...
@@ -518,7 +522,10 @@ void APMFirmwarePlugin::_adjustSeverity(mavlink_message_t* message) const
break
;
}
mavlink_msg_statustext_encode
(
message
->
sysid
,
message
->
compid
,
message
,
&
statusText
);
mavlink_msg_statustext_encode
(
message
->
sysid
,
message
->
compid
,
message
,
&
statusText
);
}
void
APMFirmwarePlugin
::
_setInfoSeverity
(
mavlink_message_t
*
message
)
const
...
...
@@ -527,7 +534,10 @@ void APMFirmwarePlugin::_setInfoSeverity(mavlink_message_t* message) const
mavlink_msg_statustext_decode
(
message
,
&
statusText
);
statusText
.
severity
=
MAV_SEVERITY_INFO
;
mavlink_msg_statustext_encode
(
message
->
sysid
,
message
->
compid
,
message
,
&
statusText
);
mavlink_msg_statustext_encode
(
message
->
sysid
,
message
->
compid
,
message
,
&
statusText
);
}
void
APMFirmwarePlugin
::
_adjustCalibrationMessageSeverity
(
mavlink_message_t
*
message
)
const
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
abc118d0
...
...
@@ -83,7 +83,7 @@ public:
void
pauseVehicle
(
Vehicle
*
vehicle
);
int
manualControlReservedButtonCount
(
void
);
bool
adjustIncomingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
void
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
void
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
LinkInterface
*
outgoingLink
,
mavlink_message_t
*
message
)
final
;
void
initializeVehicle
(
Vehicle
*
vehicle
)
final
;
bool
sendHomePositionToVehicle
(
void
)
final
;
void
addMetaDataToFact
(
QObject
*
parameterMetaData
,
Fact
*
fact
,
MAV_TYPE
vehicleType
)
final
;
...
...
@@ -114,10 +114,10 @@ private:
static
bool
_isTextSeverityAdjustmentNeeded
(
const
APMFirmwareVersion
&
firmwareVersion
);
void
_setInfoSeverity
(
mavlink_message_t
*
message
)
const
;
QString
_getMessageText
(
mavlink_message_t
*
message
)
const
;
void
_handleParamValue
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handleParamSe
t
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
bool
_handleStatusTex
t
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handle
Heartbeat
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handle
Incoming
ParamValue
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
bool
_handleIncomingStatusTex
t
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handleIncomingHeartbea
t
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handle
OutgoingParamSet
(
Vehicle
*
vehicle
,
LinkInterface
*
outgoingLink
,
mavlink_message_t
*
message
);
void
_soloVideoHandshake
(
Vehicle
*
vehicle
);
bool
_textSeverityAdjustmentNeeded
;
...
...
src/FirmwarePlugin/APM/APMGeoFenceManager.cc
View file @
abc118d0
...
...
@@ -178,13 +178,14 @@ void APMGeoFenceManager::_requestFencePoint(uint8_t pointIndex)
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
qCDebug
(
GeoFenceManagerLog
)
<<
"APMGeoFenceManager::_requestFencePoint"
<<
pointIndex
;
mavlink_msg_fence_fetch_point_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
_vehicle
->
defaultComponentId
(),
pointIndex
);
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_fence_fetch_point_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(),
_vehicle
->
defaultComponentId
(),
pointIndex
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
void
APMGeoFenceManager
::
_sendFencePoint
(
uint8_t
pointIndex
)
...
...
@@ -206,16 +207,17 @@ void APMGeoFenceManager::_sendFencePoint(uint8_t pointIndex)
// Total point count, +1 polygon close in last index, +1 for breach in index 0
uint8_t
totalPointCount
=
_polygon
.
count
()
+
1
+
1
;
mavlink_msg_fence_point_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
_vehicle
->
defaultComponentId
(),
pointIndex
,
// Index of point to set
totalPointCount
,
fenceCoord
.
latitude
(),
fenceCoord
.
longitude
());
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_fence_point_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(),
_vehicle
->
defaultComponentId
(),
pointIndex
,
// Index of point to set
totalPointCount
,
fenceCoord
.
latitude
(),
fenceCoord
.
longitude
());
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
bool
APMGeoFenceManager
::
inProgress
(
void
)
const
...
...
src/FirmwarePlugin/APM/APMRallyPointManager.cc
View file @
abc118d0
...
...
@@ -109,13 +109,14 @@ void APMRallyPointManager::_requestRallyPoint(uint8_t pointIndex)
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
qCDebug
(
RallyPointManagerLog
)
<<
"APMRallyPointManager::_requestRallyPoint"
<<
pointIndex
;
mavlink_msg_rally_fetch_point_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
_vehicle
->
defaultComponentId
(),
pointIndex
);
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_rally_fetch_point_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(),
_vehicle
->
defaultComponentId
(),
pointIndex
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
void
APMRallyPointManager
::
_sendRallyPoint
(
uint8_t
pointIndex
)
...
...
@@ -124,18 +125,19 @@ void APMRallyPointManager::_sendRallyPoint(uint8_t pointIndex)
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
QGeoCoordinate
point
=
_rgPoints
[
pointIndex
];
mavlink_msg_rally_point_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
_vehicle
->
defaultComponentId
(),
pointIndex
,
_rgPoints
.
count
(),
point
.
latitude
()
*
1e7
,
point
.
longitude
()
*
1e7
,
point
.
altitude
(),
0
,
0
,
0
);
// break_alt, land_dir, flags
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_rally_point_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(),
_vehicle
->
defaultComponentId
(),
pointIndex
,
_rgPoints
.
count
(),
point
.
latitude
()
*
1e7
,
point
.
longitude
()
*
1e7
,
point
.
altitude
(),
0
,
0
,
0
);
// break_alt, land_dir, flags
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
bool
APMRallyPointManager
::
inProgress
(
void
)
const
...
...
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
abc118d0
...
...
@@ -141,9 +141,13 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitu
cmd
.
target_component
=
vehicle
->
defaultComponentId
();
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_msg_command_long_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
mavlink_msg_command_long_encode_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
vehicle
->
sendMessageOn
PriorityLink
(
msg
);
vehicle
->
sendMessageOn
Link
(
vehicle
->
priorityLink
(),
msg
);
}
void
ArduCopterFirmwarePlugin
::
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
...
...
@@ -179,9 +183,13 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
cmd
.
z
=
-
(
altitudeRel
-
vehicle
->
altitudeRelative
()
->
rawValue
().
toDouble
());
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_msg_set_position_target_local_ned_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
mavlink_msg_set_position_target_local_ned_encode_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
vehicle
->
sendMessageOn
PriorityLink
(
msg
);
vehicle
->
sendMessageOn
Link
(
vehicle
->
priorityLink
(),
msg
);
}
bool
ArduCopterFirmwarePlugin
::
isPaused
(
const
Vehicle
*
vehicle
)
const
...
...
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
abc118d0
...
...
@@ -112,9 +112,10 @@ bool FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_mess
return
true
;
}
void
FirmwarePlugin
::
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
void
FirmwarePlugin
::
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
LinkInterface
*
outgoingLink
,
mavlink_message_t
*
message
)
{
Q_UNUSED
(
vehicle
);
Q_UNUSED
(
outgoingLink
);
Q_UNUSED
(
message
);
// Generic plugin does no message adjustment
}
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
abc118d0
...
...
@@ -159,8 +159,9 @@ public:
/// This is handy to adjust or differences in mavlink spec implementations such that the base code can remain
/// mavlink generic.
/// @param vehicle Vehicle message came from
/// @param outgoingLink Link that messae is going out on
/// @param message[in,out] Mavlink message to adjust if needed.
virtual
void
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
virtual
void
adjustOutgoingMavlinkMessage
(
Vehicle
*
vehicle
,
LinkInterface
*
outgoingLink
,
mavlink_message_t
*
message
);
/// Determines how to handle the first item of the mission item list. Internally to QGC the first item
/// is always the home position.
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
abc118d0
...
...
@@ -283,9 +283,13 @@ void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
cmd
.
target_component
=
vehicle
->
defaultComponentId
();
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_msg_command_long_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
mavlink_msg_command_long_encode_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
vehicle
->
sendMessageOn
PriorityLink
(
msg
);
vehicle
->
sendMessageOn
Link
(
vehicle
->
priorityLink
(),
msg
);
}
void
PX4FirmwarePlugin
::
guidedModeRTL
(
Vehicle
*
vehicle
)
...
...
@@ -317,8 +321,12 @@ void PX4FirmwarePlugin::guidedModeOrbit(Vehicle* vehicle, const QGeoCoordinate&
cmd
.
param7
=
centerCoord
.
isValid
()
?
centerCoord
.
altitude
()
:
NAN
;
cmd
.
target_system
=
vehicle
->
id
();
cmd
.
target_component
=
vehicle
->
defaultComponentId
();
mavlink_msg_command_long_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_command_long_encode_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
vehicle
->
sendMessageOnLink
(
vehicle
->
priorityLink
(),
msg
);
}
void
PX4FirmwarePlugin
::
guidedModeTakeoff
(
Vehicle
*
vehicle
,
double
altitudeRel
)
...
...
@@ -347,8 +355,12 @@ void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitudeRel)
cmd
.
target_system
=
vehicle
->
id
();
cmd
.
target_component
=
vehicle
->
defaultComponentId
();
mavlink_msg_command_long_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_command_long_encode_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
vehicle
->
sendMessageOnLink
(
vehicle
->
priorityLink
(),
msg
);
}
void
PX4FirmwarePlugin
::
guidedModeGotoLocation
(
Vehicle
*
vehicle
,
const
QGeoCoordinate
&
gotoCoord
)
...
...
@@ -374,9 +386,13 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
cmd
.
target_component
=
vehicle
->
defaultComponentId
();
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_msg_command_long_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
mavlink_msg_command_long_encode_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
vehicle
->
sendMessageOn
PriorityLink
(
msg
);
vehicle
->
sendMessageOn
Link
(
vehicle
->
priorityLink
(),
msg
);
}
void
PX4FirmwarePlugin
::
guidedModeChangeAltitude
(
Vehicle
*
vehicle
,
double
altitudeRel
)
...
...
@@ -402,9 +418,13 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
cmd
.
target_component
=
vehicle
->
defaultComponentId
();
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_msg_command_long_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
mavlink_msg_command_long_encode_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
vehicle
->
sendMessageOn
PriorityLink
(
msg
);
vehicle
->
sendMessageOn
Link
(
vehicle
->
priorityLink
(),
msg
);
}
void
PX4FirmwarePlugin
::
setGuidedMode
(
Vehicle
*
vehicle
,
bool
guidedMode
)
...
...
src/FollowMe/FollowMe.cc
View file @
abc118d0
...
...
@@ -140,11 +140,12 @@ void FollowMe::_sendGCSMotionReport(void)
Vehicle
*
vehicle
=
qobject_cast
<
Vehicle
*>
(
vehicles
[
i
]);
if
(
vehicle
->
flightMode
().
compare
(
PX4FirmwarePlugin
::
followMeFlightMode
,
Qt
::
CaseInsensitive
)
==
0
)
{
mavlink_message_t
message
;
mavlink_msg_follow_target_encode
(
mavlinkProtocol
->
getSystemId
(),
mavlinkProtocol
->
getComponentId
(),
&
message
,
&
follow_target
);
vehicle
->
sendMessageOnPriorityLink
(
message
);
mavlink_msg_follow_target_encode_chan
(
mavlinkProtocol
->
getSystemId
(),
mavlinkProtocol
->
getComponentId
(),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
message
,
&
follow_target
);
vehicle
->
sendMessageOnLink
(
vehicle
->
priorityLink
(),
message
);
}
}
}
...
...
src/GPS/RTCM/RTCMMavlink.cc
View file @
abc118d0
...
...
@@ -61,8 +61,11 @@ void RTCMMavlink::sendMessageToVehicle(const mavlink_gps_rtcm_data_t& msg)
for
(
int
i
=
0
;
i
<
vehicles
.
count
();
i
++
)
{
Vehicle
*
vehicle
=
qobject_cast
<
Vehicle
*>
(
vehicles
[
i
]);
mavlink_message_t
message
;
mavlink_msg_gps_rtcm_data_encode
(
mavlinkProtocol
->
getSystemId
(),
mavlinkProtocol
->
getComponentId
(),
&
message
,
&
msg
);
vehicle
->
sendMessageOnPriorityLink
(
message
);
mavlink_msg_gps_rtcm_data_encode_chan
(
mavlinkProtocol
->
getSystemId
(),
mavlinkProtocol
->
getComponentId
(),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
message
,
&
msg
);
vehicle
->
sendMessageOnLink
(
vehicle
->
priorityLink
(),
message
);
}
}
src/MissionManager/MissionManager.cc
View file @
abc118d0
...
...
@@ -90,9 +90,13 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
missionCount
.
target_component
=
MAV_COMP_ID_MISSIONPLANNER
;
missionCount
.
count
=
_missionItems
.
count
();
mavlink_msg_mission_count_encode
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
&
message
,
&
missionCount
);
_dedicatedLink
=
_vehicle
->
priorityLink
();
mavlink_msg_mission_count_encode_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_dedicatedLink
->
mavlinkChannel
(),
&
message
,
&
missionCount
);
_vehicle
->
sendMessageOnLink
(
_dedicatedLink
,
message
);
_startAckTimeout
(
AckMissionRequest
);
emit
inProgressChanged
(
true
);
...
...
@@ -125,9 +129,13 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC
missionItem
.
current
=
altChangeOnly
?
3
:
2
;
missionItem
.
autocontinue
=
true
;
mavlink_msg_mission_item_encode
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
&
messageOut
,
&
missionItem
);
_dedicatedLink
=
_vehicle
->
priorityLink
();
mavlink_msg_mission_item_encode_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_dedicatedLink
->
mavlinkChannel
(),
&
messageOut
,
&
missionItem
);
_vehicle
->
sendMessageOnLink
(
_dedicatedLink
,
messageOut
);
_startAckTimeout
(
AckGuidedItem
);
emit
inProgressChanged
(
true
);
...
...
@@ -157,9 +165,13 @@ void MissionManager::requestMissionItems(void)
request
.
target_system
=
_vehicle
->
id
();
request
.
target_component
=
MAV_COMP_ID_MISSIONPLANNER
;
mavlink_msg_mission_request_list_encode
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
&
message
,
&
request
);
_dedicatedLink
=
_vehicle
->
priorityLink
();
mavlink_msg_mission_request_list_encode_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_dedicatedLink
->
mavlinkChannel
(),
&
message
,
&
request
);
_vehicle
->
sendMessageOnLink
(
_dedicatedLink
,
message
);
_startAckTimeout
(
AckMissionCount
);
emit
inProgressChanged
(
true
);
...
...
@@ -223,7 +235,11 @@ void MissionManager::_readTransactionComplete(void)
missionAck
.
target_component
=
MAV_COMP_ID_MISSIONPLANNER
;
missionAck
.
type
=
MAV_MISSION_ACCEPTED
;
mavlink_msg_mission_ack_encode
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
&
message
,
&
missionAck
);
mavlink_msg_mission_ack_encode_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_dedicatedLink
->
mavlinkChannel
(),
&
message
,
&
missionAck
);
_vehicle
->
sendMessageOnLink
(
_dedicatedLink
,
message
);
...
...
@@ -269,7 +285,11 @@ void MissionManager::_requestNextMissionItem(void)
missionRequest
.
target_component
=
MAV_COMP_ID_MISSIONPLANNER
;
missionRequest
.
seq
=
_itemIndicesToRead
[
0
];
mavlink_msg_mission_request_encode
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
&
message
,
&
missionRequest
);
mavlink_msg_mission_request_encode_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_dedicatedLink
->
mavlinkChannel
(),
&
message
,
&
missionRequest
);
_vehicle
->
sendMessageOnLink
(
_dedicatedLink
,
message
);
_startAckTimeout
(
AckMissionItem
);
...
...
@@ -377,7 +397,11 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message)
missionItem
.
current
=
missionRequest
.
seq
==
0
;
missionItem
.
autocontinue
=
item
->
autoContinue
();
mavlink_msg_mission_item_encode
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
&
messageOut
,
&
missionItem
);
mavlink_msg_mission_item_encode_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_dedicatedLink
->
mavlinkChannel
(),
&
messageOut
,
&
missionItem
);
_vehicle
->
sendMessageOnLink
(
_dedicatedLink
,
messageOut
);
_startAckTimeout
(
AckMissionRequest
);
...
...
src/QmlControls/QGroundControlQmlGlobal.cc
View file @
abc118d0
...
...
@@ -188,12 +188,6 @@ void QGroundControlQmlGlobal::setIsSaveLogPromptNotArmed(bool prompt)
emit
isSaveLogPromptNotArmedChanged
(
prompt
);
}
void
QGroundControlQmlGlobal
::
setIsMultiplexingEnabled
(
bool
enable
)
{
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
enableMultiplexing
(
enable
);
emit
isMultiplexingEnabledChanged
(
enable
);
}
void
QGroundControlQmlGlobal
::
setIsVersionCheckEnabled
(
bool
enable
)
{
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
enableVersionCheck
(
enable
);
...
...
src/QmlControls/QGroundControlQmlGlobal.h
View file @
abc118d0
...
...
@@ -87,7 +87,6 @@ public:
Q_PROPERTY
(
qreal
baseFontPointSize
READ
baseFontPointSize
WRITE
setBaseFontPointSize
NOTIFY
baseFontPointSizeChanged
)
// MavLink Protocol
Q_PROPERTY
(
bool
isMultiplexingEnabled
READ
isMultiplexingEnabled
WRITE
setIsMultiplexingEnabled
NOTIFY
isMultiplexingEnabledChanged
)
Q_PROPERTY
(
bool
isVersionCheckEnabled
READ
isVersionCheckEnabled
WRITE
setIsVersionCheckEnabled
NOTIFY
isVersionCheckEnabledChanged
)
Q_PROPERTY
(
int
mavlinkSystemID
READ
mavlinkSystemID
WRITE
setMavlinkSystemID
NOTIFY
mavlinkSystemIDChanged
)
...
...
@@ -179,7 +178,6 @@ public:
bool
virtualTabletJoystick
()
{
return
_virtualTabletJoystick
;
}
qreal
baseFontPointSize
()
{
return
_baseFontPointSize
;
}
bool
isMultiplexingEnabled
()
{
return
_toolbox
->
mavlinkProtocol
()
->
multiplexingEnabled
();
}
bool
isVersionCheckEnabled
()
{
return
_toolbox
->
mavlinkProtocol
()
->
versionCheckEnabled
();
}
int
mavlinkSystemID
()
{
return
_toolbox
->
mavlinkProtocol
()
->
getSystemId
();
}
...
...
@@ -204,7 +202,6 @@ public:
void
setVirtualTabletJoystick
(
bool
enabled
);
void
setBaseFontPointSize
(
qreal
size
);
void
setIsMultiplexingEnabled
(
bool
enable
);
void
setIsVersionCheckEnabled
(
bool
enable
);
void
setMavlinkSystemID
(
int
id
);
...
...
src/Vehicle/MultiVehicleManager.cc
View file @
abc118d0
...
...
@@ -307,15 +307,16 @@ void MultiVehicleManager::_sendGCSHeartbeat(void)
Vehicle
*
vehicle
=
qobject_cast
<
Vehicle
*>
(
_vehicles
[
i
]);
mavlink_message_t
message
;
mavlink_msg_heartbeat_pack
(
_mavlinkProtocol
->
getSystemId
(),
_mavlinkProtocol
->
getComponentId
(),
&
message
,
MAV_TYPE_GCS
,
// MAV_TYPE
MAV_AUTOPILOT_INVALID
,
// MAV_AUTOPILOT
MAV_MODE_MANUAL_ARMED
,
// MAV_MODE
0
,
// custom mode
MAV_STATE_ACTIVE
);
// MAV_STATE
vehicle
->
sendMessageOnPriorityLink
(
message
);
mavlink_msg_heartbeat_pack_chan
(
_mavlinkProtocol
->
getSystemId
(),
_mavlinkProtocol
->
getComponentId
(),
vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
message
,
MAV_TYPE_GCS
,
// MAV_TYPE
MAV_AUTOPILOT_INVALID
,
// MAV_AUTOPILOT
MAV_MODE_MANUAL_ARMED
,
// MAV_MODE
0
,
// custom mode
MAV_STATE_ACTIVE
);
// MAV_STATE
vehicle
->
sendMessageOnLink
(
vehicle
->
priorityLink
(),
message
);
}
}
...
...
src/Vehicle/Vehicle.cc
View file @
abc118d0
...
...
@@ -221,7 +221,11 @@ Vehicle::Vehicle(LinkInterface* link,
versionCmd
.
param2
=
versionCmd
.
param3
=
versionCmd
.
param4
=
versionCmd
.
param5
=
versionCmd
.
param6
=
versionCmd
.
param7
=
0
;
versionCmd
.
target_system
=
id
();
versionCmd
.
target_component
=
MAV_COMP_ID_ALL
;
mavlink_msg_command_long_encode
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
versionMsg
,
&
versionCmd
);
mavlink_msg_command_long_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
versionMsg
,
&
versionCmd
);
sendMessageMultiple
(
versionMsg
);
_firmwarePlugin
->
initializeVehicle
(
this
);
...
...
@@ -874,10 +878,7 @@ void Vehicle::_sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
}
// Give the plugin a chance to adjust
_firmwarePlugin
->
adjustOutgoingMavlinkMessage
(
this
,
&
message
);
static
const
uint8_t
messageKeys
[
256
]
=
MAVLINK_MESSAGE_CRCS
;
mavlink_finalize_message_chan
(
&
message
,
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
link
->
getMavlinkChannel
(),
message
.
len
,
message
.
len
,
messageKeys
[
message
.
msgid
]);
_firmwarePlugin
->
adjustOutgoingMavlinkMessage
(
this
,
link
,
&
message
);
// Write message into buffer, prepending start sign
uint8_t
buffer
[
MAVLINK_MAX_PACKET_LEN
];
...
...
@@ -1277,9 +1278,13 @@ void Vehicle::setArmed(bool armed)
cmd
.
target_system
=
id
();
cmd
.
target_component
=
defaultComponentId
();
mavlink_msg_command_long_encode
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
mavlink_msg_command_long_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
sendMessageOn
PriorityLink
(
msg
);
sendMessageOn
Link
(
priorityLink
(),
msg
);
}
bool
Vehicle
::
flightModeSetAvailable
(
void
)
...
...
@@ -1309,8 +1314,14 @@ void Vehicle::setFlightMode(const QString& flightMode)
newBaseMode
|=
base_mode
;
mavlink_message_t
msg
;
mavlink_msg_set_mode_pack
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
id
(),
newBaseMode
,
custom_mode
);
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_set_mode_pack_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
id
(),
newBaseMode
,
custom_mode
);
sendMessageOnLink
(
priorityLink
(),
msg
);
}
else
{
qWarning
()
<<
"FirmwarePlugin::setFlightMode failed, flightMode:"
<<
flightMode
;
}
...
...
@@ -1330,8 +1341,14 @@ void Vehicle::setHilMode(bool hilMode)
newBaseMode
|=
MAV_MODE_FLAG_HIL_ENABLED
;
}
mavlink_msg_set_mode_pack
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
id
(),
newBaseMode
,
_custom_mode
);
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_set_mode_pack_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
id
(),
newBaseMode
,
_custom_mode
);
sendMessageOnLink
(
priorityLink
(),
msg
);
}
void
Vehicle
::
requestDataStream
(
MAV_DATA_STREAM
stream
,
uint16_t
rate
,
bool
sendMultiple
)
...
...
@@ -1345,13 +1362,17 @@ void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool send
dataStream
.
target_system
=
id
();
dataStream
.
target_component
=
defaultComponentId
();
mavlink_msg_request_data_stream_encode
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
&
dataStream
);
mavlink_msg_request_data_stream_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
dataStream
);
if
(
sendMultiple
)
{
// We use sendMessageMultiple since we really want these to make it to the vehicle
sendMessageMultiple
(
msg
);
}
else
{
sendMessageOn
PriorityLink
(
msg
);
sendMessageOn
Link
(
priorityLink
(),
msg
);
}
}
...
...
@@ -1360,7 +1381,7 @@ void Vehicle::_sendMessageMultipleNext(void)
if
(
_nextSendMessageMultipleIndex
<
_sendMessageMultipleList
.
count
())
{
qCDebug
(
VehicleLog
)
<<
"_sendMessageMultipleNext:"
<<
_sendMessageMultipleList
[
_nextSendMessageMultipleIndex
].
message
.
msgid
;
sendMessageOn
PriorityLink
(
_sendMessageMultipleList
[
_nextSendMessageMultipleIndex
].
message
);
sendMessageOn
Link
(
priorityLink
(),
_sendMessageMultipleList
[
_nextSendMessageMultipleIndex
].
message
);
if
(
--
_sendMessageMultipleList
[
_nextSendMessageMultipleIndex
].
retryCount
<=
0
)
{
_sendMessageMultipleList
.
removeAt
(
_nextSendMessageMultipleIndex
);
...
...
@@ -1764,9 +1785,13 @@ void Vehicle::emergencyStop(void)
cmd
.
param7
=
0.0
f
;
cmd
.
target_system
=
id
();
cmd
.
target_component
=
defaultComponentId
();
mavlink_msg_command_long_encode
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
mavlink_msg_command_long_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
sendMessageOn
PriorityLink
(
msg
);
sendMessageOn
Link
(
priorityLink
(),
msg
);
}
void
Vehicle
::
setCurrentMissionSequence
(
int
seq
)
...
...
@@ -1775,8 +1800,14 @@ void Vehicle::setCurrentMissionSequence(int seq)
seq
--
;
}
mavlink_message_t
msg
;
mavlink_msg_mission_set_current_pack
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
id
(),
_compID
,
seq
);
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_mission_set_current_pack_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
id
(),
_compID
,
seq
);
sendMessageOnLink
(
priorityLink
(),
msg
);
}
void
Vehicle
::
doCommandLong
(
int
component
,
MAV_CMD
command
,
float
param1
,
float
param2
,
float
param3
,
float
param4
,
float
param5
,
float
param6
,
float
param7
)
...
...
@@ -1795,9 +1826,13 @@ void Vehicle::doCommandLong(int component, MAV_CMD command, float param1, float
cmd
.
param7
=
param7
;
cmd
.
target_system
=
id
();
cmd
.
target_component
=
component
;
mavlink_msg_command_long_encode
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
mavlink_msg_command_long_encode_chan
(
_mavlink
->
getSystemId
(),
_mavlink
->
getComponentId
(),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
sendMessageOn
PriorityLink
(
msg
);
sendMessageOn
Link
(
priorityLink
(),
msg
);
}
void
Vehicle
::
setPrearmError
(
const
QString
&
prearmError
)
...
...
src/Vehicle/Vehicle.h
View file @
abc118d0
...
...
@@ -430,10 +430,6 @@ public:
/// @return true: message sent, false: Link no longer connected
bool
sendMessageOnLink
(
LinkInterface
*
link
,
mavlink_message_t
message
);
/// Sends a message to the priority link
/// @return true: message sent, false: Link no longer connected
bool
sendMessageOnPriorityLink
(
mavlink_message_t
message
)
{
return
sendMessageOnLink
(
priorityLink
(),
message
);
}
/// Sends the specified messages multiple times to the vehicle in order to attempt to
/// guarantee that it makes it to the vehicle.
void
sendMessageMultiple
(
mavlink_message_t
message
);
...
...
src/ViewWidgets/LogDownloadController.cc
View file @
abc118d0
...
...
@@ -458,12 +458,13 @@ LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t cou
id
+=
_apmOneBased
;
qCDebug
(
LogDownloadLog
)
<<
"Request log data (id:"
<<
id
<<
"offset:"
<<
offset
<<
"size:"
<<
count
<<
")"
;
mavlink_message_t
msg
;
mavlink_msg_log_request_data_pack
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
&
msg
,
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
()
->
id
(),
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
()
->
defaultComponentId
(),
id
,
offset
,
count
);
mavlink_msg_log_request_data_pack_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
()
->
id
(),
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
()
->
defaultComponentId
(),
id
,
offset
,
count
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
}
...
...
@@ -485,14 +486,15 @@ LogDownloadController::_requestLogList(uint32_t start, uint32_t end)
qCDebug
(
LogDownloadLog
)
<<
"Request log entry list ("
<<
start
<<
"through"
<<
end
<<
")"
;
_setListing
(
true
);
mavlink_message_t
msg
;
mavlink_msg_log_request_list_pack
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
&
msg
,
_vehicle
->
id
(),
_vehicle
->
defaultComponentId
(),
start
,
end
);
mavlink_msg_log_request_list_pack_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(),
_vehicle
->
defaultComponentId
(),
start
,
end
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
//-- Wait 5 seconds before bitching about not getting anything
_timer
.
start
(
5000
);
...
...
@@ -650,11 +652,12 @@ LogDownloadController::eraseAll(void)
{
if
(
_vehicle
&&
_uas
)
{
mavlink_message_t
msg
;
mavlink_msg_log_erase_pack
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
&
msg
,
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
()
->
id
(),
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
()
->
defaultComponentId
());
mavlink_msg_log_erase_pack_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
()
->
id
(),
qgcApp
()
->
toolbox
()
->
multiVehicleManager
()
->
activeVehicle
()
->
defaultComponentId
());
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
refresh
();
}
...
...
src/comm/LinkInterface.h
View file @
abc118d0
...
...
@@ -7,15 +7,6 @@
*
****************************************************************************/
/**
* @file
* @brief Brief Description
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _LINKINTERFACE_H_
#define _LINKINTERFACE_H_
...
...
@@ -25,6 +16,7 @@
#include <QMutexLocker>
#include <QMetaType>
#include <QSharedPointer>
#include <QDebug>
#include "QGCMAVLink.h"
...
...
@@ -124,7 +116,13 @@ public:
/// mavlink channel to use for this link, as used by mavlink_parse_char. The mavlink channel is only
/// set into the link when it is added to LinkManager
uint8_t
getMavlinkChannel
(
void
)
const
{
Q_ASSERT
(
_mavlinkChannelSet
);
return
_mavlinkChannel
;
}
uint8_t
mavlinkChannel
(
void
)
const
{
if
(
!
_mavlinkChannelSet
)
{
qWarning
()
<<
"Call to LinkInterface::mavlinkChannel with _mavlinkChannelSet == false"
;
}
return
_mavlinkChannel
;
}
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of
// connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
...
...
src/comm/LinkManager.cc
View file @
abc118d0
...
...
@@ -270,7 +270,7 @@ void LinkManager::_deleteLink(LinkInterface* link)
}
// Free up the mavlink channel associated with this link
_mavlinkChannelsUsedBitMask
&=
~
(
1
<<
link
->
getM
avlinkChannel
());
_mavlinkChannelsUsedBitMask
&=
~
(
1
<<
link
->
m
avlinkChannel
());
_links
.
removeOne
(
link
);
delete
link
;
...
...
src/comm/LogReplayLink.cc
View file @
abc118d0
...
...
@@ -167,7 +167,7 @@ quint64 LogReplayLink::_seekToNextMavlinkMessage(mavlink_message_t* nextMsg)
char
nextByte
;
mavlink_status_t
comm
;
while
(
_logFile
.
getChar
(
&
nextByte
))
{
// Loop over every byte
bool
messageFound
=
mavlink_parse_char
(
getM
avlinkChannel
(),
nextByte
,
nextMsg
,
&
comm
);
bool
messageFound
=
mavlink_parse_char
(
m
avlinkChannel
(),
nextByte
,
nextMsg
,
&
comm
);
// If we've found a message, jump back to the start of the message, grab the timestamp,
// and go back to the end of this file.
...
...
src/comm/MAVLinkProtocol.cc
View file @
abc118d0
...
...
@@ -51,13 +51,7 @@ const char* MAVLinkProtocol::_logFileExtension = "mavlink"; ///< Ext
*/
MAVLinkProtocol
::
MAVLinkProtocol
(
QGCApplication
*
app
)
:
QGCTool
(
app
)
,
m_multiplexingEnabled
(
false
)
,
m_enable_version_check
(
true
)
,
m_paramRetransmissionTimeout
(
350
)
,
m_paramRewriteTimeout
(
500
)
,
m_paramGuardEnabled
(
true
)
,
m_actionGuardEnabled
(
false
)
,
m_actionRetransmissionTimeout
(
100
)
,
versionMismatchIgnore
(
false
)
,
systemId
(
255
)
#ifndef __mobile__
...
...
@@ -124,7 +118,6 @@ void MAVLinkProtocol::loadSettings()
QSettings
settings
;
settings
.
beginGroup
(
"QGC_MAVLINK_PROTOCOL"
);
enableVersionCheck
(
settings
.
value
(
"VERSION_CHECK_ENABLED"
,
m_enable_version_check
).
toBool
());
enableMultiplexing
(
settings
.
value
(
"MULTIPLEXING_ENABLED"
,
m_multiplexingEnabled
).
toBool
());
// Only set system id if it was valid
int
temp
=
settings
.
value
(
"GCS_SYSTEM_ID"
,
systemId
).
toInt
();
...
...
@@ -132,15 +125,6 @@ void MAVLinkProtocol::loadSettings()
{
systemId
=
temp
;
}
// Parameter interface settings
bool
ok
;
temp
=
settings
.
value
(
"PARAMETER_RETRANSMISSION_TIMEOUT"
,
m_paramRetransmissionTimeout
).
toInt
(
&
ok
);
if
(
ok
)
m_paramRetransmissionTimeout
=
temp
;
temp
=
settings
.
value
(
"PARAMETER_REWRITE_TIMEOUT"
,
m_paramRewriteTimeout
).
toInt
(
&
ok
);
if
(
ok
)
m_paramRewriteTimeout
=
temp
;
m_paramGuardEnabled
=
settings
.
value
(
"PARAMETER_TRANSMISSION_GUARD_ENABLED"
,
m_paramGuardEnabled
).
toBool
();
settings
.
endGroup
();
}
void
MAVLinkProtocol
::
storeSettings
()
...
...
@@ -149,18 +133,13 @@ void MAVLinkProtocol::storeSettings()
QSettings
settings
;
settings
.
beginGroup
(
"QGC_MAVLINK_PROTOCOL"
);
settings
.
setValue
(
"VERSION_CHECK_ENABLED"
,
m_enable_version_check
);
settings
.
setValue
(
"MULTIPLEXING_ENABLED"
,
m_multiplexingEnabled
);
settings
.
setValue
(
"GCS_SYSTEM_ID"
,
systemId
);
// Parameter interface settings
settings
.
setValue
(
"PARAMETER_RETRANSMISSION_TIMEOUT"
,
m_paramRetransmissionTimeout
);
settings
.
setValue
(
"PARAMETER_REWRITE_TIMEOUT"
,
m_paramRewriteTimeout
);
settings
.
setValue
(
"PARAMETER_TRANSMISSION_GUARD_ENABLED"
,
m_paramGuardEnabled
);
settings
.
endGroup
();
}
void
MAVLinkProtocol
::
resetMetadataForLink
(
const
LinkInterface
*
link
)
{
int
channel
=
link
->
getM
avlinkChannel
();
int
channel
=
link
->
m
avlinkChannel
();
totalReceiveCounter
[
channel
]
=
0
;
totalLossCounter
[
channel
]
=
0
;
totalErrorCounter
[
channel
]
=
0
;
...
...
@@ -188,7 +167,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
mavlink_message_t
message
;
mavlink_status_t
status
;
int
mavlinkChannel
=
link
->
getM
avlinkChannel
();
int
mavlinkChannel
=
link
->
m
avlinkChannel
();
static
int
mavlink09Count
=
0
;
static
int
nonmavlinkCount
=
0
;
...
...
@@ -235,19 +214,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{
decodedFirstPacket
=
true
;
if
(
message
.
msgid
==
MAVLINK_MSG_ID_PING
)
{
// process ping requests (tgt_system and tgt_comp must be zero)
mavlink_ping_t
ping
;
mavlink_msg_ping_decode
(
&
message
,
&
ping
);
if
(
!
ping
.
target_system
&&
!
ping
.
target_component
)
{
mavlink_message_t
msg
;
mavlink_msg_ping_pack
(
getSystemId
(),
getComponentId
(),
&
msg
,
ping
.
time_usec
,
ping
.
seq
,
message
.
sysid
,
message
.
compid
);
_sendMessage
(
msg
);
}
}
if
(
message
.
msgid
==
MAVLINK_MSG_ID_RADIO_STATUS
)
{
// process telemetry status message
...
...
@@ -375,19 +341,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// kind of inefficient, but no issue for a groundstation pc.
// It buys as reentrancy for the whole code over all threads
emit
messageReceived
(
link
,
message
);
// Multiplex message if enabled
if
(
m_multiplexingEnabled
)
{
// Emit message on all links that are currently connected
for
(
int
i
=
0
;
i
<
_linkMgr
->
links
()
->
count
();
i
++
)
{
LinkInterface
*
currLink
=
_linkMgr
->
links
()
->
value
<
LinkInterface
*>
(
i
);
// Only forward this message to the other links,
// not the link the message was received on
if
(
currLink
&&
currLink
!=
link
)
_sendMessage
(
currLink
,
message
,
message
.
sysid
,
message
.
compid
);
}
}
}
}
}
...
...
@@ -417,110 +370,6 @@ int MAVLinkProtocol::getComponentId()
return
0
;
}
/**
* @param message message to send
*/
void
MAVLinkProtocol
::
_sendMessage
(
mavlink_message_t
message
)
{
for
(
int
i
=
0
;
i
<
_linkMgr
->
links
()
->
count
();
i
++
)
{
LinkInterface
*
link
=
_linkMgr
->
links
()
->
value
<
LinkInterface
*>
(
i
);
_sendMessage
(
link
,
message
);
}
}
/**
* @param link the link to send the message over
* @param message message to send
*/
void
MAVLinkProtocol
::
_sendMessage
(
LinkInterface
*
link
,
mavlink_message_t
message
)
{
// Create buffer
static
uint8_t
buffer
[
MAVLINK_MAX_PACKET_LEN
];
// Rewriting header to ensure correct link ID is set
static
uint8_t
messageKeys
[
256
]
=
MAVLINK_MESSAGE_CRCS
;
mavlink_finalize_message_chan
(
&
message
,
this
->
getSystemId
(),
this
->
getComponentId
(),
link
->
getMavlinkChannel
(),
message
.
len
,
message
.
len
,
messageKeys
[
message
.
msgid
]);
// Write message into buffer, prepending start sign
int
len
=
mavlink_msg_to_send_buffer
(
buffer
,
&
message
);
// If link is connected
if
(
link
->
isConnected
())
{
// Send the portion of the buffer now occupied by the message
link
->
writeBytesSafe
((
const
char
*
)
buffer
,
len
);
}
}
/**
* @param link the link to send the message over
* @param message message to send
* @param systemid id of the system the message is originating from
* @param componentid id of the component the message is originating from
*/
void
MAVLinkProtocol
::
_sendMessage
(
LinkInterface
*
link
,
mavlink_message_t
message
,
quint8
systemid
,
quint8
componentid
)
{
// Create buffer
static
uint8_t
buffer
[
MAVLINK_MAX_PACKET_LEN
];
// Rewriting header to ensure correct link ID is set
static
uint8_t
messageKeys
[
256
]
=
MAVLINK_MESSAGE_CRCS
;
mavlink_finalize_message_chan
(
&
message
,
systemid
,
componentid
,
link
->
getMavlinkChannel
(),
message
.
len
,
message
.
len
,
messageKeys
[
message
.
msgid
]);
// Write message into buffer, prepending start sign
int
len
=
mavlink_msg_to_send_buffer
(
buffer
,
&
message
);
// If link is connected
if
(
link
->
isConnected
())
{
// Send the portion of the buffer now occupied by the message
link
->
writeBytesSafe
((
const
char
*
)
buffer
,
len
);
}
}
void
MAVLinkProtocol
::
enableMultiplexing
(
bool
enabled
)
{
bool
changed
=
false
;
if
(
enabled
!=
m_multiplexingEnabled
)
changed
=
true
;
m_multiplexingEnabled
=
enabled
;
if
(
changed
)
emit
multiplexingChanged
(
m_multiplexingEnabled
);
}
void
MAVLinkProtocol
::
enableParamGuard
(
bool
enabled
)
{
if
(
enabled
!=
m_paramGuardEnabled
)
{
m_paramGuardEnabled
=
enabled
;
emit
paramGuardChanged
(
m_paramGuardEnabled
);
}
}
void
MAVLinkProtocol
::
enableActionGuard
(
bool
enabled
)
{
if
(
enabled
!=
m_actionGuardEnabled
)
{
m_actionGuardEnabled
=
enabled
;
emit
actionGuardChanged
(
m_actionGuardEnabled
);
}
}
void
MAVLinkProtocol
::
setParamRetransmissionTimeout
(
int
ms
)
{
if
(
ms
!=
m_paramRetransmissionTimeout
)
{
m_paramRetransmissionTimeout
=
ms
;
emit
paramRetransmissionTimeoutChanged
(
m_paramRetransmissionTimeout
);
}
}
void
MAVLinkProtocol
::
setParamRewriteTimeout
(
int
ms
)
{
if
(
ms
!=
m_paramRewriteTimeout
)
{
m_paramRewriteTimeout
=
ms
;
emit
paramRewriteTimeoutChanged
(
m_paramRewriteTimeout
);
}
}
void
MAVLinkProtocol
::
setActionRetransmissionTimeout
(
int
ms
)
{
if
(
ms
!=
m_actionRetransmissionTimeout
)
{
m_actionRetransmissionTimeout
=
ms
;
emit
actionRetransmissionTimeoutChanged
(
m_actionRetransmissionTimeout
);
}
}
void
MAVLinkProtocol
::
enableVersionCheck
(
bool
enabled
)
{
m_enable_version_check
=
enabled
;
...
...
src/comm/MAVLinkProtocol.h
View file @
abc118d0
...
...
@@ -64,54 +64,30 @@ public:
bool
versionCheckEnabled
()
const
{
return
m_enable_version_check
;
}
/** @brief Get the multiplexing state */
bool
multiplexingEnabled
()
const
{
return
m_multiplexingEnabled
;
}
/** @brief Get the protocol version */
int
getVersion
()
{
return
MAVLINK_VERSION
;
}
/** @brief Get state of parameter retransmission */
bool
paramGuardEnabled
()
{
return
m_paramGuardEnabled
;
}
/** @brief Get parameter read timeout */
int
getParamRetransmissionTimeout
()
{
return
m_paramRetransmissionTimeout
;
}
/** @brief Get parameter write timeout */
int
getParamRewriteTimeout
()
{
return
m_paramRewriteTimeout
;
}
/** @brief Get state of action retransmission */
bool
actionGuardEnabled
()
{
return
m_actionGuardEnabled
;
}
/** @brief Get parameter read timeout */
int
getActionRetransmissionTimeout
()
{
return
m_actionRetransmissionTimeout
;
}
/**
* Retrieve a total of all successfully parsed packets for the specified link.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
*/
qint32
getReceivedPacketCount
(
const
LinkInterface
*
link
)
const
{
return
totalReceiveCounter
[
link
->
getM
avlinkChannel
()];
return
totalReceiveCounter
[
link
->
m
avlinkChannel
()];
}
/**
* Retrieve a total of all parsing errors for the specified link.
* @returns -1 if this is not available for this protocol, # of errors otherwise.
*/
qint32
getParsingErrorCount
(
const
LinkInterface
*
link
)
const
{
return
totalErrorCounter
[
link
->
getM
avlinkChannel
()];
return
totalErrorCounter
[
link
->
m
avlinkChannel
()];
}
/**
* Retrieve a total of all dropped packets for the specified link.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
*/
qint32
getDroppedPacketCount
(
const
LinkInterface
*
link
)
const
{
return
totalLossCounter
[
link
->
getM
avlinkChannel
()];
return
totalLossCounter
[
link
->
m
avlinkChannel
()];
}
/**
* Reset the counters for all metadata for this link.
...
...
@@ -131,24 +107,6 @@ public slots:
/** @brief Set the system id of this application */
void
setSystemId
(
int
id
);
/** @brief Enabled/disable packet multiplexing */
void
enableMultiplexing
(
bool
enabled
);
/** @brief Enable / disable parameter retransmission */
void
enableParamGuard
(
bool
enabled
);
/** @brief Enable / disable action retransmission */
void
enableActionGuard
(
bool
enabled
);
/** @brief Set parameter read timeout */
void
setParamRetransmissionTimeout
(
int
ms
);
/** @brief Set parameter write timeout */
void
setParamRewriteTimeout
(
int
ms
);
/** @brief Set parameter read timeout */
void
setActionRetransmissionTimeout
(
int
ms
);
/** @brief Enable / disable version check */
void
enableVersionCheck
(
bool
enabled
);
...
...
@@ -166,13 +124,7 @@ public slots:
#endif
protected:
bool
m_multiplexingEnabled
;
///< Enable/disable packet multiplexing
bool
m_enable_version_check
;
///< Enable checking of version match of MAV and QGC
int
m_paramRetransmissionTimeout
;
///< Timeout for parameter retransmission
int
m_paramRewriteTimeout
;
///< Timeout for sending re-write request
bool
m_paramGuardEnabled
;
///< Parameter retransmission/rewrite enabled
bool
m_actionGuardEnabled
;
///< Action request retransmission enabled
int
m_actionRetransmissionTimeout
;
///< Timeout for parameter retransmission
QMutex
receiveMutex
;
///< Mutex to protect receiveBytes function
int
lastIndex
[
256
][
256
];
///< Store the last received sequence ID for each system/componenet pair
int
totalReceiveCounter
[
MAVLINK_COMM_NUM_BUFFERS
];
///< The total number of successfully received messages
...
...
@@ -189,24 +141,12 @@ signals:
/** @brief Message received and directly copied via signal */
void
messageReceived
(
LinkInterface
*
link
,
mavlink_message_t
message
);
/** @brief Emitted if multiplexing is started / stopped */
void
multiplexingChanged
(
bool
enabled
);
/** @brief Emitted if version check is enabled / disabled */
void
versionCheckChanged
(
bool
enabled
);
/** @brief Emitted if a message from the protocol should reach the user */
void
protocolStatusMessage
(
const
QString
&
title
,
const
QString
&
message
);
/** @brief Emitted if a new system ID was set */
void
systemIdChanged
(
int
systemId
);
/** @brief Emitted if param guard status changed */
void
paramGuardChanged
(
bool
enabled
);
/** @brief Emitted if param read timeout changed */
void
paramRetransmissionTimeoutChanged
(
int
ms
);
/** @brief Emitted if param write timeout changed */
void
paramRewriteTimeoutChanged
(
int
ms
);
/** @brief Emitted if action guard status changed */
void
actionGuardChanged
(
bool
enabled
);
/** @brief Emitted if action request timeout changed */
void
actionRetransmissionTimeoutChanged
(
int
ms
);
void
receiveLossPercentChanged
(
int
uasId
,
float
lossPercent
);
void
receiveLossTotalChanged
(
int
uasId
,
int
totalLoss
);
...
...
@@ -232,10 +172,6 @@ private slots:
void
_vehicleCountChanged
(
int
count
);
private:
void
_sendMessage
(
mavlink_message_t
message
);
void
_sendMessage
(
LinkInterface
*
link
,
mavlink_message_t
message
);
void
_sendMessage
(
LinkInterface
*
link
,
mavlink_message_t
message
,
quint8
systemid
,
quint8
componentid
);
#ifndef __mobile__
bool
_closeLogFile
(
void
);
void
_startLogging
(
void
);
...
...
src/comm/MockLink.cc
View file @
abc118d0
...
...
@@ -260,14 +260,15 @@ void MockLink::_sendHeartBeat(void)
{
mavlink_message_t
msg
;
mavlink_msg_heartbeat_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
msg
,
_vehicleType
,
// MAV_TYPE
_firmwareType
,
// MAV_AUTOPILOT
_mavBaseMode
,
// MAV_MODE
_mavCustomMode
,
// custom mode
_mavState
);
// MAV_STATE
mavlink_msg_heartbeat_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
_vehicleType
,
// MAV_TYPE
_firmwareType
,
// MAV_AUTOPILOT
_mavBaseMode
,
// MAV_MODE
_mavCustomMode
,
// custom mode
_mavState
);
// MAV_STATE
respondWithMavlinkMessage
(
msg
);
}
...
...
@@ -276,16 +277,17 @@ void MockLink::_sendVibration(void)
{
mavlink_message_t
msg
;
mavlink_msg_vibration_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
msg
,
0
,
// time_usec
50.5
,
// vibration_x,
10.5
,
// vibration_y,
60.0
,
// vibration_z,
1
,
// clipping_0
2
,
// clipping_0
3
);
// clipping_0
mavlink_msg_vibration_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
0
,
// time_usec
50.5
,
// vibration_x,
10.5
,
// vibration_y,
60.0
,
// vibration_z,
1
,
// clipping_0
2
,
// clipping_0
3
);
// clipping_0
respondWithMavlinkMessage
(
msg
);
}
...
...
@@ -346,7 +348,7 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
for
(
qint64
i
=
0
;
i
<
cBytes
;
i
++
)
{
if
(
!
mavlink_parse_char
(
getM
avlinkChannel
(),
bytes
[
i
],
&
msg
,
&
comm
))
{
if
(
!
mavlink_parse_char
(
m
avlinkChannel
(),
bytes
[
i
],
&
msg
,
&
comm
))
{
continue
;
}
...
...
@@ -603,14 +605,15 @@ void MockLink::_paramRequestListWorker(void)
qCDebug
(
MockLinkLog
)
<<
"Sending msg_param_value"
<<
componentId
<<
paramId
<<
paramType
<<
_mapParamName2Value
[
componentId
][
paramId
];
mavlink_msg_param_value_pack
(
_vehicleSystemId
,
componentId
,
// component id
&
responseMsg
,
// Outgoing message
paramId
,
// Parameter name
_floatUnionForParam
(
componentId
,
paramName
),
// Parameter value
paramType
,
// MAV_PARAM_TYPE
cParameters
,
// Total number of parameters
_currentParamRequestListParamIndex
);
// Index of this parameter
mavlink_msg_param_value_pack_chan
(
_vehicleSystemId
,
componentId
,
// component id
mavlinkChannel
(),
&
responseMsg
,
// Outgoing message
paramId
,
// Parameter name
_floatUnionForParam
(
componentId
,
paramName
),
// Parameter value
paramType
,
// MAV_PARAM_TYPE
cParameters
,
// Total number of parameters
_currentParamRequestListParamIndex
);
// Index of this parameter
respondWithMavlinkMessage
(
responseMsg
);
}
...
...
@@ -650,14 +653,15 @@ void MockLink::_handleParamSet(const mavlink_message_t& msg)
// Respond with a param_value to ack
mavlink_message_t
responseMsg
;
mavlink_msg_param_value_pack
(
_vehicleSystemId
,
componentId
,
// component id
&
responseMsg
,
// Outgoing message
paramId
,
// Parameter name
request
.
param_value
,
// Send same value back
request
.
param_type
,
// Send same type back
_mapParamName2Value
[
componentId
].
count
(),
// Total number of parameters
_mapParamName2Value
[
componentId
].
keys
().
indexOf
(
paramId
));
// Index of this parameter
mavlink_msg_param_value_pack_chan
(
_vehicleSystemId
,
componentId
,
// component id
mavlinkChannel
(),
&
responseMsg
,
// Outgoing message
paramId
,
// Parameter name
request
.
param_value
,
// Send same value back
request
.
param_type
,
// Send same type back
_mapParamName2Value
[
componentId
].
count
(),
// Total number of parameters
_mapParamName2Value
[
componentId
].
keys
().
indexOf
(
paramId
));
// Index of this parameter
respondWithMavlinkMessage
(
responseMsg
);
}
...
...
@@ -676,14 +680,15 @@ void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
valueUnion
.
type
=
MAV_PARAM_TYPE_UINT32
;
valueUnion
.
param_uint32
=
0
;
// Special case of magic hash check value
mavlink_msg_param_value_pack
(
_vehicleSystemId
,
componentId
,
&
responseMsg
,
request
.
param_id
,
valueUnion
.
param_float
,
MAV_PARAM_TYPE_UINT32
,
0
,
-
1
);
mavlink_msg_param_value_pack_chan
(
_vehicleSystemId
,
componentId
,
mavlinkChannel
(),
&
responseMsg
,
request
.
param_id
,
valueUnion
.
param_float
,
MAV_PARAM_TYPE_UINT32
,
0
,
-
1
);
respondWithMavlinkMessage
(
responseMsg
);
return
;
}
...
...
@@ -717,14 +722,15 @@ void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
return
;
}
mavlink_msg_param_value_pack
(
_vehicleSystemId
,
componentId
,
// component id
&
responseMsg
,
// Outgoing message
paramId
,
// Parameter name
_floatUnionForParam
(
componentId
,
paramId
),
// Parameter value
_mapParamName2MavParamType
[
paramId
],
// Parameter type
_mapParamName2Value
[
componentId
].
count
(),
// Total number of parameters
_mapParamName2Value
[
componentId
].
keys
().
indexOf
(
paramId
));
// Index of this parameter
mavlink_msg_param_value_pack_chan
(
_vehicleSystemId
,
componentId
,
// component id
mavlinkChannel
(),
&
responseMsg
,
// Outgoing message
paramId
,
// Parameter name
_floatUnionForParam
(
componentId
,
paramId
),
// Parameter value
_mapParamName2MavParamType
[
paramId
],
// Parameter type
_mapParamName2Value
[
componentId
].
count
(),
// Total number of parameters
_mapParamName2Value
[
componentId
].
keys
().
indexOf
(
paramId
));
// Index of this parameter
respondWithMavlinkMessage
(
responseMsg
);
}
...
...
@@ -738,12 +744,13 @@ void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
chanRaw
[
channel
]
=
raw
;
mavlink_message_t
responseMsg
;
mavlink_msg_rc_channels_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
responseMsg
,
// Outgoing message
0
,
// time since boot, ignored
18
,
// channel count
chanRaw
[
0
],
// channel raw value
mavlink_msg_rc_channels_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
responseMsg
,
// Outgoing message
0
,
// time since boot, ignored
18
,
// channel count
chanRaw
[
0
],
// channel raw value
chanRaw
[
1
],
// channel raw value
chanRaw
[
2
],
// channel raw value
chanRaw
[
3
],
// channel raw value
...
...
@@ -801,11 +808,12 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg)
}
mavlink_message_t
commandAck
;
mavlink_msg_command_ack_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
commandAck
,
request
.
command
,
commandResult
);
mavlink_msg_command_ack_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
commandAck
,
request
.
command
,
commandResult
);
respondWithMavlinkMessage
(
commandAck
);
}
...
...
@@ -827,20 +835,21 @@ void MockLink::_respondWithAutopilotVersion(void)
flightVersion
|=
FIRMWARE_VERSION_TYPE_DEV
<<
(
8
*
0
);
}
mavlink_msg_autopilot_version_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
msg
,
0
,
// capabilities,
flightVersion
,
// flight_sw_version,
0
,
// middleware_sw_version,
0
,
// os_sw_version,
0
,
// board_version,
(
uint8_t
*
)
&
customVersion
,
// flight_custom_version,
(
uint8_t
*
)
&
customVersion
,
// middleware_custom_version,
(
uint8_t
*
)
&
customVersion
,
// os_custom_version,
0
,
// vendor_id,
0
,
// product_id,
0
);
// uid
mavlink_msg_autopilot_version_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
0
,
// capabilities,
flightVersion
,
// flight_sw_version,
0
,
// middleware_sw_version,
0
,
// os_sw_version,
0
,
// board_version,
(
uint8_t
*
)
&
customVersion
,
// flight_custom_version,
(
uint8_t
*
)
&
customVersion
,
// middleware_custom_version,
(
uint8_t
*
)
&
customVersion
,
// os_custom_version,
0
,
// vendor_id,
0
,
// product_id,
0
);
// uid
respondWithMavlinkMessage
(
msg
);
}
...
...
@@ -859,14 +868,15 @@ void MockLink::_sendHomePosition(void)
bogus
[
2
]
=
0.0
f
;
bogus
[
3
]
=
0.0
f
;
mavlink_msg_home_position_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
msg
,
(
int32_t
)(
_vehicleLatitude
*
1E7
),
(
int32_t
)(
_vehicleLongitude
*
1E7
),
(
int32_t
)(
_vehicleAltitude
*
1000
),
0.0
f
,
0.0
f
,
0.0
f
,
&
bogus
[
0
],
mavlink_msg_home_position_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
(
int32_t
)(
_vehicleLatitude
*
1E7
),
(
int32_t
)(
_vehicleLongitude
*
1E7
),
(
int32_t
)(
_vehicleAltitude
*
1000
),
0.0
f
,
0.0
f
,
0.0
f
,
&
bogus
[
0
],
0.0
f
,
0.0
f
,
0.0
f
);
respondWithMavlinkMessage
(
msg
);
}
...
...
@@ -876,18 +886,19 @@ void MockLink::_sendGpsRawInt(void)
static
uint64_t
timeTick
=
0
;
mavlink_message_t
msg
;
mavlink_msg_gps_raw_int_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
msg
,
timeTick
++
,
// time since boot
3
,
// 3D fix
(
int32_t
)(
_vehicleLatitude
*
1E7
),
(
int32_t
)(
_vehicleLongitude
*
1E7
),
(
int32_t
)(
_vehicleAltitude
*
1000
),
UINT16_MAX
,
UINT16_MAX
,
// HDOP/VDOP not known
UINT16_MAX
,
// velocity not known
UINT16_MAX
,
// course over ground not known
8
);
// satellite count
mavlink_msg_gps_raw_int_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
timeTick
++
,
// time since boot
3
,
// 3D fix
(
int32_t
)(
_vehicleLatitude
*
1E7
),
(
int32_t
)(
_vehicleLongitude
*
1E7
),
(
int32_t
)(
_vehicleAltitude
*
1000
),
UINT16_MAX
,
UINT16_MAX
,
// HDOP/VDOP not known
UINT16_MAX
,
// velocity not known
UINT16_MAX
,
// course over ground not known
8
);
// satellite count
respondWithMavlinkMessage
(
msg
);
}
...
...
@@ -914,11 +925,12 @@ void MockLink::_sendStatusTextMessages(void)
mavlink_message_t
msg
;
const
struct
StatusMessage
*
status
=
&
rgMessages
[
i
];
mavlink_msg_statustext_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
msg
,
status
->
severity
,
status
->
msg
);
mavlink_msg_statustext_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
status
->
severity
,
status
->
msg
);
respondWithMavlinkMessage
(
msg
);
}
}
...
...
@@ -1065,21 +1077,22 @@ void MockLink::_sendRCChannels(void)
{
mavlink_message_t
msg
;
mavlink_msg_rc_channels_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
msg
,
0
,
// time_boot_ms
8
,
// chancount
1500
,
// chan1_raw
1500
,
// chan2_raw
1500
,
// chan3_raw
1500
,
// chan4_raw
1500
,
// chan5_raw
1500
,
// chan6_raw
1500
,
// chan7_raw
1500
,
// chan8_raw
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
0
);
// rssi
mavlink_msg_rc_channels_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
0
,
// time_boot_ms
8
,
// chancount
1500
,
// chan1_raw
1500
,
// chan2_raw
1500
,
// chan3_raw
1500
,
// chan4_raw
1500
,
// chan5_raw
1500
,
// chan6_raw
1500
,
// chan7_raw
1500
,
// chan8_raw
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
UINT16_MAX
,
0
);
// rssi
respondWithMavlinkMessage
(
msg
);
...
...
@@ -1106,11 +1119,12 @@ void MockLink::_handlePreFlightCalibration(const mavlink_command_long_t& request
}
mavlink_message_t
msg
;
mavlink_msg_statustext_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
msg
,
MAV_SEVERITY_INFO
,
pCalMessage
);
mavlink_msg_statustext_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
MAV_SEVERITY_INFO
,
pCalMessage
);
respondWithMavlinkMessage
(
msg
);
}
...
...
@@ -1126,14 +1140,15 @@ void MockLink::_handleLogRequestList(const mavlink_message_t& msg)
}
mavlink_message_t
responseMsg
;
mavlink_msg_log_entry_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
responseMsg
,
_logDownloadLogId
,
// log id
1
,
// num_logs
1
,
// last_log_num
0
,
// time_utc
_logDownloadFileSize
);
// size
mavlink_msg_log_entry_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
responseMsg
,
_logDownloadLogId
,
// log id
1
,
// num_logs
1
,
// last_log_num
0
,
// time_utc
_logDownloadFileSize
);
// size
respondWithMavlinkMessage
(
responseMsg
);
}
...
...
@@ -1181,13 +1196,14 @@ void MockLink::_logDownloadWorker(void)
qDebug
()
<<
"MockLink::_logDownloadWorker"
<<
_logDownloadCurrentOffset
<<
_logDownloadBytesRemaining
;
mavlink_message_t
responseMsg
;
mavlink_msg_log_data_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
responseMsg
,
_logDownloadLogId
,
_logDownloadCurrentOffset
,
bytesToRead
,
&
buffer
[
0
]);
mavlink_msg_log_data_pack_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
responseMsg
,
_logDownloadLogId
,
_logDownloadCurrentOffset
,
bytesToRead
,
&
buffer
[
0
]);
respondWithMavlinkMessage
(
responseMsg
);
_logDownloadCurrentOffset
+=
bytesToRead
;
...
...
src/comm/MockLinkFileServer.cc
View file @
abc118d0
...
...
@@ -365,13 +365,14 @@ void MockLinkFileServer::_sendResponse(uint8_t targetSystemId, uint8_t targetCom
request
->
hdr
.
seqNumber
=
seqNumber
;
mavlink_msg_file_transfer_protocol_pack
(
_systemIdServer
,
// System ID
0
,
// Component ID
&
mavlinkMessage
,
// Mavlink Message to pack into
0
,
// Target network
targetSystemId
,
targetComponentId
,
(
uint8_t
*
)
request
);
// Payload
mavlink_msg_file_transfer_protocol_pack_chan
(
_systemIdServer
,
// System ID
0
,
// Component ID
_mockLink
->
mavlinkChannel
(),
&
mavlinkMessage
,
// Mavlink Message to pack into
0
,
// Target network
targetSystemId
,
targetComponentId
,
(
uint8_t
*
)
request
);
// Payload
_mockLink
->
respondWithMavlinkMessage
(
mavlinkMessage
);
}
...
...
src/comm/MockLinkMissionItemHandler.cc
View file @
abc118d0
...
...
@@ -96,12 +96,13 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message
mavlink_message_t
responseMsg
;
mavlink_msg_mission_count_pack
(
_mockLink
->
vehicleId
(),
MAV_COMP_ID_MISSIONPLANNER
,
&
responseMsg
,
// Outgoing message
msg
.
sysid
,
// Target is original sender
msg
.
compid
,
// Target is original sender
itemCount
);
// Number of mission items
mavlink_msg_mission_count_pack_chan
(
_mockLink
->
vehicleId
(),
MAV_COMP_ID_MISSIONPLANNER
,
_mockLink
->
mavlinkChannel
(),
&
responseMsg
,
// Outgoing message
msg
.
sysid
,
// Target is original sender
msg
.
compid
,
// Target is original sender
itemCount
);
// Number of mission items
_mockLink
->
respondWithMavlinkMessage
(
responseMsg
);
}
else
{
qCDebug
(
MockLinkMissionItemHandlerLog
)
<<
"_handleMissionRequestList not responding due to failure mode"
;
...
...
@@ -149,18 +150,19 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
item
=
_missionItems
[
request
.
seq
];
}
mavlink_msg_mission_item_pack
(
_mockLink
->
vehicleId
(),
MAV_COMP_ID_MISSIONPLANNER
,
&
responseMsg
,
// Outgoing message
msg
.
sysid
,
// Target is original sender
msg
.
compid
,
// Target is original sender
request
.
seq
,
// Index of mission item being sent
item
.
frame
,
item
.
command
,
item
.
current
,
item
.
autocontinue
,
item
.
param1
,
item
.
param2
,
item
.
param3
,
item
.
param4
,
item
.
x
,
item
.
y
,
item
.
z
);
mavlink_msg_mission_item_pack_chan
(
_mockLink
->
vehicleId
(),
MAV_COMP_ID_MISSIONPLANNER
,
_mockLink
->
mavlinkChannel
(),
&
responseMsg
,
// Outgoing message
msg
.
sysid
,
// Target is original sender
msg
.
compid
,
// Target is original sender
request
.
seq
,
// Index of mission item being sent
item
.
frame
,
item
.
command
,
item
.
current
,
item
.
autocontinue
,
item
.
param1
,
item
.
param2
,
item
.
param3
,
item
.
param4
,
item
.
x
,
item
.
y
,
item
.
z
);
_mockLink
->
respondWithMavlinkMessage
(
responseMsg
);
}
}
...
...
@@ -218,7 +220,11 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
missionRequest
.
target_component
=
_mavlinkProtocol
->
getComponentId
();
missionRequest
.
seq
=
sequenceNumber
;
mavlink_msg_mission_request_encode
(
_mockLink
->
vehicleId
(),
MAV_COMP_ID_MISSIONPLANNER
,
&
message
,
&
missionRequest
);
mavlink_msg_mission_request_encode_chan
(
_mockLink
->
vehicleId
(),
MAV_COMP_ID_MISSIONPLANNER
,
_mockLink
->
mavlinkChannel
(),
&
message
,
&
missionRequest
);
_mockLink
->
respondWithMavlinkMessage
(
message
);
// If response with Mission Item doesn't come before timer fires it's an error
...
...
@@ -238,7 +244,11 @@ void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType)
missionAck
.
target_component
=
_mavlinkProtocol
->
getComponentId
();
missionAck
.
type
=
ackType
;
mavlink_msg_mission_ack_encode
(
_mockLink
->
vehicleId
(),
MAV_COMP_ID_MISSIONPLANNER
,
&
message
,
&
missionAck
);
mavlink_msg_mission_ack_encode_chan
(
_mockLink
->
vehicleId
(),
MAV_COMP_ID_MISSIONPLANNER
,
_mockLink
->
mavlinkChannel
(),
&
message
,
&
missionAck
);
_mockLink
->
respondWithMavlinkMessage
(
message
);
}
...
...
src/uas/FileManager.cc
View file @
abc118d0
...
...
@@ -731,15 +731,23 @@ void FileManager::_sendRequest(Request* request)
if
(
_systemIdQGC
==
0
)
{
_systemIdQGC
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
();
}
// Unit testing code can end up here without _dedicateLink set since it tests inidividual commands.
LinkInterface
*
link
;
if
(
_dedicatedLink
)
{
link
=
_dedicatedLink
;
}
else
{
link
=
_vehicle
->
priorityLink
();
}
Q_ASSERT
(
_vehicle
);
mavlink_msg_file_transfer_protocol_pack
(
_systemIdQGC
,
// QGC System
ID
0
,
// QGC Component ID
&
message
,
// Mavlink Message to pack into
0
,
// Target network
_systemIdServer
,
// Target system
0
,
// Target component
(
uint8_t
*
)
request
);
// Payload
mavlink_msg_file_transfer_protocol_pack_chan
(
_systemIdQGC
,
// QGC System ID
0
,
// QGC Component
ID
link
->
mavlinkChannel
(),
&
message
,
// Mavlink Message to pack into
0
,
// Target network
_systemIdServer
,
// Target system
0
,
// Target component
(
uint8_t
*
)
request
);
// Payload
_vehicle
->
sendMessageOnLink
(
_dedicatedL
ink
,
message
);
_vehicle
->
sendMessageOnLink
(
l
ink
,
message
);
}
src/uas/UAS.cc
View file @
abc118d0
...
...
@@ -798,21 +798,22 @@ void UAS::startCalibration(UASInterface::StartCalibrationType calType)
}
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
_vehicle
->
defaultComponentId
(),
// target component
MAV_CMD_PREFLIGHT_CALIBRATION
,
// command id
0
,
// 0=first transmission of command
gyroCal
,
// gyro cal
magCal
,
// mag cal
0
,
// ground pressure
radioCal
,
// radio cal
accelCal
,
// accel cal
airspeedCal
,
// PX4: airspeed cal, ArduPilot: compass mot
escCal
);
// esc cal
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_command_long_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
uasId
,
_vehicle
->
defaultComponentId
(),
// target component
MAV_CMD_PREFLIGHT_CALIBRATION
,
// command id
0
,
// 0=first transmission of command
gyroCal
,
// gyro cal
magCal
,
// mag cal
0
,
// ground pressure
radioCal
,
// radio cal
accelCal
,
// accel cal
airspeedCal
,
// PX4: airspeed cal, ArduPilot: compass mot
escCal
);
// esc cal
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
void
UAS
::
stopCalibration
(
void
)
...
...
@@ -822,21 +823,22 @@ void UAS::stopCalibration(void)
}
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
_vehicle
->
defaultComponentId
(),
// target component
MAV_CMD_PREFLIGHT_CALIBRATION
,
// command id
0
,
// 0=first transmission of command
0
,
// gyro cal
0
,
// mag cal
0
,
// ground pressure
0
,
// radio cal
0
,
// accel cal
0
,
// airspeed cal
0
);
// unused
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_command_long_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
uasId
,
_vehicle
->
defaultComponentId
(),
// target component
MAV_CMD_PREFLIGHT_CALIBRATION
,
// command id
0
,
// 0=first transmission of command
0
,
// gyro cal
0
,
// mag cal
0
,
// ground pressure
0
,
// radio cal
0
,
// accel cal
0
,
// airspeed cal
0
);
// unused
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
void
UAS
::
startBusConfig
(
UASInterface
::
StartBusConfigType
calType
)
...
...
@@ -857,21 +859,22 @@ void UAS::startBusConfig(UASInterface::StartBusConfigType calType)
}
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
_vehicle
->
defaultComponentId
(),
// target component
MAV_CMD_PREFLIGHT_UAVCAN
,
// command id
0
,
// 0=first transmission of command
actuatorCal
,
// actuators
0
,
0
,
0
,
0
,
0
,
0
);
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_command_long_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
uasId
,
_vehicle
->
defaultComponentId
(),
// target component
MAV_CMD_PREFLIGHT_UAVCAN
,
// command id
0
,
// 0=first transmission of command
actuatorCal
,
// actuators
0
,
0
,
0
,
0
,
0
,
0
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
void
UAS
::
stopBusConfig
(
void
)
...
...
@@ -881,21 +884,22 @@ void UAS::stopBusConfig(void)
}
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
_vehicle
->
defaultComponentId
(),
// target component
MAV_CMD_PREFLIGHT_UAVCAN
,
// command id
0
,
// 0=first transmission of command
0
,
0
,
0
,
0
,
0
,
0
,
0
);
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_command_long_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
uasId
,
_vehicle
->
defaultComponentId
(),
// target component
MAV_CMD_PREFLIGHT_UAVCAN
,
// command id
0
,
// 0=first transmission of command
0
,
0
,
0
,
0
,
0
,
0
,
0
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
/**
...
...
@@ -1144,8 +1148,13 @@ void UAS::requestImage()
if
(
imagePacketsArrived
==
0
)
{
mavlink_message_t
msg
;
mavlink_msg_data_transmission_handshake_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
MAVLINK_DATA_STREAM_IMG_JPEG
,
0
,
0
,
0
,
0
,
0
,
50
);
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_data_transmission_handshake_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
MAVLINK_DATA_STREAM_IMG_JPEG
,
0
,
0
,
0
,
0
,
0
,
50
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
}
...
...
@@ -1243,8 +1252,12 @@ void UAS::executeCommand(MAV_CMD command, int confirmation, float param1, float
cmd
.
param7
=
param7
;
cmd
.
target_system
=
uasId
;
cmd
.
target_component
=
component
;
mavlink_msg_command_long_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
cmd
);
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_command_long_encode_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
&
cmd
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
/**
...
...
@@ -1299,19 +1312,19 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
float
attitudeQuaternion
[
4
];
mavlink_euler_to_quaternion
(
roll
,
pitch
,
yaw
,
attitudeQuaternion
);
uint8_t
typeMask
=
0x7
;
// disable rate control
mavlink_msg_set_attitude_target_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
message
,
QGC
::
groundTimeUsecs
()
,
this
->
uasId
,
0
,
typeMask
,
attitudeQuaternion
,
0
,
0
,
0
,
thrust
);
mavlink_msg_set_attitude_target_pack
_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
()
,
&
message
,
QGC
::
groundTimeUsecs
()
,
this
->
uasId
,
0
,
typeMask
,
attitudeQuaternion
,
0
,
0
,
0
,
thrust
);
}
else
if
(
joystickMode
==
Vehicle
::
JoystickModePosition
)
{
// Send the the local position setpoint (local pos sp external message)
static
float
px
=
0
;
...
...
@@ -1322,26 +1335,26 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
py
+=
roll
;
pz
-=
2.0
f
*
(
thrust
-
0.5
);
uint16_t
typeMask
=
(
1
<<
11
)
|
(
7
<<
6
)
|
(
7
<<
3
);
// select only POSITION control
mavlink_msg_set_position_target_local_ned_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
message
,
QGC
::
groundTimeUsecs
()
,
this
->
uasId
,
0
,
MAV_FRAME_LOCAL_NED
,
typeMask
,
px
,
py
,
pz
,
0
,
0
,
0
,
0
,
0
,
0
,
yaw
,
0
);
mavlink_msg_set_position_target_local_ned_pack
_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
()
,
&
message
,
QGC
::
groundTimeUsecs
()
,
this
->
uasId
,
0
,
MAV_FRAME_LOCAL_NED
,
typeMask
,
px
,
py
,
pz
,
0
,
0
,
0
,
0
,
0
,
0
,
yaw
,
0
);
}
else
if
(
joystickMode
==
Vehicle
::
JoystickModeForce
)
{
// Send the the force setpoint (local pos sp external message)
float
dcm
[
3
][
3
];
...
...
@@ -1350,26 +1363,26 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
const
float
fy
=
-
dcm
[
1
][
2
]
*
thrust
;
const
float
fz
=
-
dcm
[
2
][
2
]
*
thrust
;
uint16_t
typeMask
=
(
3
<<
10
)
|
(
7
<<
3
)
|
(
7
<<
0
)
|
(
1
<<
9
);
// select only FORCE control (disable everything else)
mavlink_msg_set_position_target_local_ned_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
message
,
QGC
::
groundTimeUsecs
()
,
this
->
uasId
,
0
,
MAV_FRAME_LOCAL_NED
,
typeMask
,
0
,
0
,
0
,
0
,
0
,
0
,
fx
,
fy
,
fz
,
0
,
0
);
mavlink_msg_set_position_target_local_ned_pack
_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
()
,
&
message
,
QGC
::
groundTimeUsecs
()
,
this
->
uasId
,
0
,
MAV_FRAME_LOCAL_NED
,
typeMask
,
0
,
0
,
0
,
0
,
0
,
0
,
fx
,
fy
,
fz
,
0
,
0
);
}
else
if
(
joystickMode
==
Vehicle
::
JoystickModeVelocity
)
{
// Send the the local velocity setpoint (local pos sp external message)
static
float
vx
=
0
;
...
...
@@ -1382,26 +1395,26 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
vz
-=
2.0
f
*
(
thrust
-
0.5
);
yawrate
+=
yaw
;
//XXX: not sure what scale to apply here
uint16_t
typeMask
=
(
1
<<
10
)
|
(
7
<<
6
)
|
(
7
<<
0
);
// select only VELOCITY control
mavlink_msg_set_position_target_local_ned_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
message
,
QGC
::
groundTimeUsecs
()
,
this
->
uasId
,
0
,
MAV_FRAME_LOCAL_NED
,
typeMask
,
0
,
0
,
0
,
vx
,
vy
,
vz
,
0
,
0
,
0
,
0
,
yawrate
);
mavlink_msg_set_position_target_local_ned_pack
_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
()
,
&
message
,
QGC
::
groundTimeUsecs
()
,
this
->
uasId
,
0
,
MAV_FRAME_LOCAL_NED
,
typeMask
,
0
,
0
,
0
,
vx
,
vy
,
vz
,
0
,
0
,
0
,
0
,
yawrate
);
}
else
if
(
joystickMode
==
Vehicle
::
JoystickModeRC
)
{
// Save the new manual control inputs
...
...
@@ -1424,10 +1437,15 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
//qDebug() << newRollCommand << newPitchCommand << newYawCommand << newThrustCommand;
// Send the MANUAL_COMMAND message
mavlink_msg_manual_control_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
message
,
this
->
uasId
,
newPitchCommand
,
newRollCommand
,
newThrustCommand
,
newYawCommand
,
buttons
);
mavlink_msg_manual_control_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
message
,
this
->
uasId
,
newPitchCommand
,
newRollCommand
,
newThrustCommand
,
newYawCommand
,
buttons
);
}
_vehicle
->
sendMessageOn
PriorityLink
(
message
);
_vehicle
->
sendMessageOn
Link
(
_vehicle
->
priorityLink
(),
message
);
// Emit an update in control values to other UI elements, like the HSI display
emit
attitudeThrustSetPointChanged
(
this
,
roll
,
pitch
,
yaw
,
thrust
,
QGC
::
groundTimeMilliseconds
());
}
...
...
@@ -1453,16 +1471,20 @@ void UAS::setManual6DOFControlCommands(double x, double y, double z, double roll
// Do not control rates and throttle
quint8
mask
=
(
1
<<
0
)
|
(
1
<<
1
)
|
(
1
<<
2
);
// ignore rates
mask
|=
(
1
<<
6
);
// ignore throttle
mavlink_msg_set_attitude_target_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
message
,
QGC
::
groundTimeMilliseconds
(),
this
->
uasId
,
_vehicle
->
defaultComponentId
(),
mask
,
q
,
0
,
0
,
0
,
0
);
_vehicle
->
sendMessageOnPriorityLink
(
message
);
mavlink_msg_set_attitude_target_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
message
,
QGC
::
groundTimeMilliseconds
(),
this
->
uasId
,
_vehicle
->
defaultComponentId
(),
mask
,
q
,
0
,
0
,
0
,
0
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
message
);
quint16
position_mask
=
(
1
<<
3
)
|
(
1
<<
4
)
|
(
1
<<
5
)
|
(
1
<<
6
)
|
(
1
<<
7
)
|
(
1
<<
8
);
mavlink_msg_set_position_target_local_ned_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
message
,
QGC
::
groundTimeMilliseconds
(),
this
->
uasId
,
_vehicle
->
defaultComponentId
(),
MAV_FRAME_LOCAL_NED
,
position_mask
,
x
,
y
,
z
,
0
,
0
,
0
,
0
,
0
,
0
,
yaw
,
yawrate
);
_vehicle
->
sendMessageOnPriorityLink
(
message
);
mavlink_msg_set_position_target_local_ned_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
message
,
QGC
::
groundTimeMilliseconds
(),
this
->
uasId
,
_vehicle
->
defaultComponentId
(),
MAV_FRAME_LOCAL_NED
,
position_mask
,
x
,
y
,
z
,
0
,
0
,
0
,
0
,
0
,
0
,
yaw
,
yawrate
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
message
);
qDebug
()
<<
__FILE__
<<
__LINE__
<<
": SENT 6DOF CONTROL MESSAGES: x"
<<
x
<<
" y: "
<<
y
<<
" z: "
<<
z
<<
" roll: "
<<
roll
<<
" pitch: "
<<
pitch
<<
" yaw: "
<<
yaw
;
//emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, QGC::groundTimeMilliseconds());
...
...
@@ -1485,8 +1507,14 @@ void UAS::pairRX(int rxType, int rxSubType)
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
_vehicle
->
defaultComponentId
(),
MAV_CMD_START_RX_PAIR
,
0
,
rxType
,
rxSubType
,
0
,
0
,
0
,
0
,
0
);
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_command_long_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
uasId
,
_vehicle
->
defaultComponentId
(),
MAV_CMD_START_RX_PAIR
,
0
,
rxType
,
rxSubType
,
0
,
0
,
0
,
0
,
0
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
/**
...
...
@@ -1706,10 +1734,13 @@ void UAS::sendHilState(quint64 time_us, float roll, float pitch, float yaw, floa
sinPhi_2
*
sinTheta_2
*
cosPsi_2
);
mavlink_message_t
msg
;
mavlink_msg_hil_state_quaternion_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
time_us
,
q
,
rollspeed
,
pitchspeed
,
yawspeed
,
lat
*
1e7
f
,
lon
*
1e7
f
,
alt
*
1000
,
vx
*
100
,
vy
*
100
,
vz
*
100
,
ind_airspeed
*
100
,
true_airspeed
*
100
,
xacc
*
1000
/
9.81
,
yacc
*
1000
/
9.81
,
zacc
*
1000
/
9.81
);
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_hil_state_quaternion_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
time_us
,
q
,
rollspeed
,
pitchspeed
,
yawspeed
,
lat
*
1e7
f
,
lon
*
1e7
f
,
alt
*
1000
,
vx
*
100
,
vy
*
100
,
vz
*
100
,
ind_airspeed
*
100
,
true_airspeed
*
100
,
xacc
*
1000
/
9.81
,
yacc
*
1000
/
9.81
,
zacc
*
1000
/
9.81
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
}
else
{
...
...
@@ -1783,11 +1814,14 @@ void UAS::sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, fl
float
temperature_corrupt
=
addZeroMeanNoise
(
temperature
,
temperature_var
);
mavlink_message_t
msg
;
mavlink_msg_hil_sensor_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
time_us
,
xacc_corrupt
,
yacc_corrupt
,
zacc_corrupt
,
rollspeed_corrupt
,
pitchspeed_corrupt
,
yawspeed_corrupt
,
xmag_corrupt
,
ymag_corrupt
,
zmag_corrupt
,
abs_pressure_corrupt
,
diff_pressure_corrupt
,
pressure_alt_corrupt
,
temperature_corrupt
,
fields_changed
);
_vehicle
->
sendMessageOnPriorityLink
(
msg
);
mavlink_msg_hil_sensor_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
time_us
,
xacc_corrupt
,
yacc_corrupt
,
zacc_corrupt
,
rollspeed_corrupt
,
pitchspeed_corrupt
,
yawspeed_corrupt
,
xmag_corrupt
,
ymag_corrupt
,
zmag_corrupt
,
abs_pressure_corrupt
,
diff_pressure_corrupt
,
pressure_alt_corrupt
,
temperature_corrupt
,
fields_changed
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
lastSendTimeSensors
=
QGC
::
groundTimeMilliseconds
();
}
else
...
...
@@ -1821,10 +1855,13 @@ void UAS::sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, floa
{
#if 0
mavlink_message_t msg;
mavlink_msg_hil_optical_flow_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
time_us, 0, 0 /* hack */, flow_x, flow_y, 0.0f /* hack */, 0.0f /* hack */, 0.0f /* hack */, 0 /* hack */, quality, ground_distance);
mavlink_msg_hil_optical_flow_pack_chan(mavlink->getSystemId(),
mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
time_us, 0, 0 /* hack */, flow_x, flow_y, 0.0f /* hack */, 0.0f /* hack */, 0.0f /* hack */, 0 /* hack */, quality, ground_distance);
_vehicle->sendMessageOn
PriorityLink(
msg);
_vehicle->sendMessageOn
Link(_vehicle->priorityLink(),
msg);
lastSendTimeOpticalFlow = QGC::groundTimeMilliseconds();
#endif
}
...
...
@@ -1859,10 +1896,13 @@ void UAS::sendHilGps(quint64 time_us, double lat, double lon, double alt, int fi
course
=
(
course
/
M_PI
)
*
180.0
f
;
mavlink_message_t
msg
;
mavlink_msg_hil_gps_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
time_us
,
fix_type
,
lat
*
1e7
,
lon
*
1e7
,
alt
*
1e3
,
eph
*
1e2
,
epv
*
1e2
,
vel
*
1e2
,
vn
*
1e2
,
ve
*
1e2
,
vd
*
1e2
,
course
*
1e2
,
satellites
);
mavlink_msg_hil_gps_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
time_us
,
fix_type
,
lat
*
1e7
,
lon
*
1e7
,
alt
*
1e3
,
eph
*
1e2
,
epv
*
1e2
,
vel
*
1e2
,
vn
*
1e2
,
ve
*
1e2
,
vd
*
1e2
,
course
*
1e2
,
satellites
);
lastSendTimeGPS
=
QGC
::
groundTimeMilliseconds
();
_vehicle
->
sendMessageOn
PriorityLink
(
msg
);
_vehicle
->
sendMessageOn
Link
(
_vehicle
->
priorityLink
(),
msg
);
}
else
{
...
...
@@ -1931,19 +1971,20 @@ void UAS::sendMapRCToParam(QString param_id, float scale, float value0, quint8 p
}
}
mavlink_msg_param_map_rc_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
message
,
this
->
uasId
,
_vehicle
->
defaultComponentId
(),
param_id_cstr
,
-
1
,
param_rc_channel_index
,
value0
,
scale
,
valueMin
,
valueMax
);
_vehicle
->
sendMessageOnPriorityLink
(
message
);
mavlink_msg_param_map_rc_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
message
,
this
->
uasId
,
_vehicle
->
defaultComponentId
(),
param_id_cstr
,
-
1
,
param_rc_channel_index
,
value0
,
scale
,
valueMin
,
valueMax
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
message
);
//qDebug() << "Mavlink message sent";
}
...
...
@@ -1957,19 +1998,20 @@ void UAS::unsetRCToParameterMap()
for
(
int
i
=
0
;
i
<
3
;
i
++
)
{
mavlink_message_t
message
;
mavlink_msg_param_map_rc_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
message
,
this
->
uasId
,
_vehicle
->
defaultComponentId
(),
param_id_cstr
,
-
2
,
i
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
);
_vehicle
->
sendMessageOnPriorityLink
(
message
);
mavlink_msg_param_map_rc_pack_chan
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
message
,
this
->
uasId
,
_vehicle
->
defaultComponentId
(),
param_id_cstr
,
-
2
,
i
,
0.0
f
,
0.0
f
,
0.0
f
,
0.0
f
);
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
message
);
}
}
...
...
src/ui/QGCMAVLinkInspector.cc
View file @
abc118d0
...
...
@@ -37,16 +37,6 @@ QGCMAVLinkInspector::QGCMAVLinkInspector(const QString& title, QAction* action,
header
<<
tr
(
"Type"
);
ui
->
treeWidget
->
setHeaderLabels
(
header
);
// Set up the column headers for the rate listing
QStringList
rateHeader
;
rateHeader
<<
tr
(
"Name"
);
rateHeader
<<
tr
(
"#ID"
);
rateHeader
<<
tr
(
"Rate"
);
ui
->
rateTreeWidget
->
setHeaderLabels
(
rateHeader
);
connect
(
ui
->
rateTreeWidget
,
&
QTreeWidget
::
itemChanged
,
this
,
&
QGCMAVLinkInspector
::
rateTreeItemChanged
);
ui
->
rateTreeWidget
->
hide
();
// Connect the UI
connect
(
ui
->
systemComboBox
,
static_cast
<
void
(
QComboBox
::*
)(
int
)
>
(
&
QComboBox
::
currentIndexChanged
),
this
,
&
QGCMAVLinkInspector
::
selectDropDownMenuSystem
);
...
...
@@ -78,23 +68,11 @@ void QGCMAVLinkInspector::selectDropDownMenuSystem(int dropdownid)
{
selectedSystemID
=
ui
->
systemComboBox
->
itemData
(
dropdownid
).
toInt
();
rebuildComponentList
();
if
(
selectedSystemID
!=
0
&&
selectedComponentID
!=
0
)
{
ui
->
rateTreeWidget
->
show
();
}
else
{
ui
->
rateTreeWidget
->
hide
();
}
}
void
QGCMAVLinkInspector
::
selectDropDownMenuComponent
(
int
dropdownid
)
{
selectedComponentID
=
ui
->
componentComboBox
->
itemData
(
dropdownid
).
toInt
();
if
(
selectedSystemID
!=
0
&&
selectedComponentID
!=
0
)
{
ui
->
rateTreeWidget
->
show
();
}
else
{
ui
->
rateTreeWidget
->
hide
();
}
}
void
QGCMAVLinkInspector
::
rebuildComponentList
()
...
...
@@ -195,8 +173,6 @@ void QGCMAVLinkInspector::clearView()
onboardMessageInterval
.
clear
();
ui
->
treeWidget
->
clear
();
ui
->
rateTreeWidget
->
clear
();
}
void
QGCMAVLinkInspector
::
refreshView
()
...
...
@@ -311,25 +287,6 @@ void QGCMAVLinkInspector::refreshView()
if
(
!
strcmp
(
msgname
,
"EMPTY"
))
{
continue
;
}
// Update the tree view
QString
messageName
(
"%1"
);
messageName
=
messageName
.
arg
(
msgname
);
if
(
!
rateTreeWidgetItems
.
contains
(
i
))
{
QStringList
fields
;
fields
<<
messageName
;
fields
<<
QString
(
"%1"
).
arg
(
i
);
fields
<<
"OFF / --- Hz"
;
QTreeWidgetItem
*
widget
=
new
QTreeWidgetItem
(
fields
);
widget
->
setFlags
(
widget
->
flags
()
|
Qt
::
ItemIsEditable
);
rateTreeWidgetItems
.
insert
(
i
,
widget
);
ui
->
rateTreeWidget
->
addTopLevelItem
(
widget
);
}
// Set Hz
//QTreeWidgetItem* message = rateTreeWidgetItems.value(i);
//message->setData(0, Qt::DisplayRole, QVariant(messageName));
}
}
...
...
@@ -476,43 +433,6 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m
}
}
void
QGCMAVLinkInspector
::
changeStreamInterval
(
int
msgid
,
int
interval
)
{
//REQUEST_DATA_STREAM
if
(
selectedSystemID
==
0
||
selectedComponentID
==
0
)
{
return
;
}
mavlink_request_data_stream_t
stream
;
stream
.
target_system
=
selectedSystemID
;
stream
.
target_component
=
selectedComponentID
;
stream
.
req_stream_id
=
msgid
;
stream
.
req_message_rate
=
interval
;
stream
.
start_stop
=
(
interval
>
0
);
mavlink_message_t
msg
;
mavlink_msg_request_data_stream_encode
(
_protocol
->
getSystemId
(),
_protocol
->
getComponentId
(),
&
msg
,
&
stream
);
#if 0
// FIXME: Is this really used?
_protocol->sendMessage(msg);
#endif
}
void
QGCMAVLinkInspector
::
rateTreeItemChanged
(
QTreeWidgetItem
*
paramItem
,
int
column
)
{
if
(
paramItem
&&
column
>
0
)
{
int
key
=
paramItem
->
data
(
1
,
Qt
::
DisplayRole
).
toInt
();
QVariant
value
=
paramItem
->
data
(
2
,
Qt
::
DisplayRole
);
float
interval
=
1000
/
value
.
toFloat
();
qDebug
()
<<
"Stream "
<<
key
<<
"interval"
<<
interval
;
changeStreamInterval
(
key
,
interval
);
}
}
QGCMAVLinkInspector
::~
QGCMAVLinkInspector
()
{
clearView
();
...
...
src/ui/QGCMAVLinkInspector.h
View file @
abc118d0
...
...
@@ -36,8 +36,6 @@ public slots:
/** @Brief Select a component through the drop down menu */
void
selectDropDownMenuComponent
(
int
dropdownid
);
void
rateTreeItemChanged
(
QTreeWidgetItem
*
paramItem
,
int
column
);
protected:
MAVLinkProtocol
*
_protocol
;
///< MAVLink instance
int
selectedSystemID
;
///< Currently selected system
...
...
@@ -45,7 +43,6 @@ protected:
QMap
<
int
,
int
>
systems
;
///< Already observed systems
QMap
<
int
,
int
>
components
;
///< Already observed components
QMap
<
int
,
float
>
onboardMessageInterval
;
///< Stores the onboard selected data rate
QMap
<
int
,
QTreeWidgetItem
*>
rateTreeWidgetItems
;
///< Available rate tree widget items
QTimer
updateTimer
;
///< Only update at 1 Hz to not overload the GUI
mavlink_message_info_t
messageInfo
[
256
];
// Store the metadata for all available MAVLink messages.
...
...
@@ -63,8 +60,6 @@ protected:
void
updateField
(
int
sysid
,
int
msgid
,
int
fieldid
,
QTreeWidgetItem
*
item
);
/** @brief Rebuild the list of components */
void
rebuildComponentList
();
/** @brief Change the stream interval */
void
changeStreamInterval
(
int
msgid
,
int
interval
);
/* @brief Create a new tree for a new UAS */
void
addUAStoTree
(
int
sysId
);
...
...
src/ui/QGCMAVLinkInspector.ui
View file @
abc118d0
...
...
@@ -13,7 +13,7 @@
<property
name=
"windowTitle"
>
<string>
MAVLink Inspector
</string>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
columnstretch=
"2,
8,2,8,3
"
>
<layout
class=
"QGridLayout"
name=
"gridLayout"
columnstretch=
"2,
0,0,0,0
"
>
<property
name=
"leftMargin"
>
<number>
6
</number>
</property>
...
...
@@ -26,13 +26,25 @@
<property
name=
"bottomMargin"
>
<number>
6
</number>
</property>
<item
row=
"0"
column=
"4"
>
<widget
class=
"QPushButton"
name=
"clearButton"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label"
>
<property
name=
"maximumSize"
>
<size>
<width>
100
</width>
<height>
16777215
</height>
</size>
</property>
<property
name=
"text"
>
<string>
Clear
</string>
<string>
System
</string>
</property>
</widget>
</item>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QComboBox"
name=
"systemComboBox"
/>
</item>
<item
row=
"0"
column=
"3"
>
<widget
class=
"QComboBox"
name=
"componentComboBox"
/>
</item>
<item
row=
"0"
column=
"2"
>
<widget
class=
"QLabel"
name=
"label_2"
>
<property
name=
"text"
>
...
...
@@ -40,10 +52,10 @@
</property>
</widget>
</item>
<item
row=
"0"
column=
"
0
"
>
<widget
class=
"Q
Label"
name=
"label
"
>
<item
row=
"0"
column=
"
4
"
>
<widget
class=
"Q
PushButton"
name=
"clearButton
"
>
<property
name=
"text"
>
<string>
System
</string>
<string>
Clear
</string>
</property>
</widget>
</item>
...
...
@@ -56,21 +68,6 @@
</column>
</widget>
</item>
<item
row=
"3"
column=
"0"
colspan=
"5"
>
<widget
class=
"QTreeWidget"
name=
"rateTreeWidget"
>
<column>
<property
name=
"text"
>
<string
notr=
"true"
>
1
</string>
</property>
</column>
</widget>
</item>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QComboBox"
name=
"systemComboBox"
/>
</item>
<item
row=
"0"
column=
"3"
>
<widget
class=
"QComboBox"
name=
"componentComboBox"
/>
</item>
</layout>
</widget>
<resources/>
...
...
src/ui/preferences/MavlinkSettings.qml
View file @
abc118d0
...
...
@@ -69,15 +69,6 @@ Rectangle {
}
}
//-----------------------------------------------------------------
//-- Mavlink Multiplexing
QGCCheckBox
{
text
:
qsTr
(
"
Enable multiplexing (forward packets to all other links)
"
)
checked
:
QGroundControl
.
isMultiplexingEnabled
onClicked
:
{
QGroundControl
.
isMultiplexingEnabled
=
checked
}
}
//-----------------------------------------------------------------
//-- Mavlink Version Check
QGCCheckBox
{
text
:
qsTr
(
"
Only accept MAVs with same protocol version
"
)
...
...
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