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
f69b38e4
Commit
f69b38e4
authored
Oct 03, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Convert to pack/encode_chan apis
parent
e7979fd9
Changes
5
Show whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
198 additions
and
171 deletions
+198
-171
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+6
-6
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+3
-3
MockLink.cc
src/comm/MockLink.cc
+151
-135
MockLinkFileServer.cc
src/comm/MockLinkFileServer.cc
+8
-7
MockLinkMissionItemHandler.cc
src/comm/MockLinkMissionItemHandler.cc
+30
-20
No files found.
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
f69b38e4
...
...
@@ -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
);
...
...
@@ -301,7 +301,7 @@ void APMFirmwarePlugin::_handleOutgoingParamSet(Vehicle* vehicle, LinkInterface*
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
;
...
...
@@ -410,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
;
...
...
@@ -439,12 +439,12 @@ 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
;
}
...
...
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
f69b38e4
...
...
@@ -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
_handleIncomingParamValue
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
bool
_handleIncomingStatusText
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handleIncomingHeartbeat
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handleOutgoingParamSet
(
Vehicle
*
vehicle
,
LinkInterface
*
outgoingLink
,
mavlink_message_t
*
message
);
bool
_handleStatusText
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_handleHeartbeat
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
_soloVideoHandshake
(
Vehicle
*
vehicle
);
bool
_textSeverityAdjustmentNeeded
;
...
...
src/comm/MockLink.cc
View file @
f69b38e4
...
...
@@ -260,8 +260,9 @@ void MockLink::_sendHeartBeat(void)
{
mavlink_message_t
msg
;
mavlink_msg_heartbeat_pack
(
_vehicleSystemId
,
mavlink_msg_heartbeat_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
_vehicleType
,
// MAV_TYPE
_firmwareType
,
// MAV_AUTOPILOT
...
...
@@ -276,8 +277,9 @@ void MockLink::_sendVibration(void)
{
mavlink_message_t
msg
;
mavlink_msg_vibration_pack
(
_vehicleSystemId
,
mavlink_msg_vibration_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
0
,
// time_usec
50.5
,
// vibration_x,
...
...
@@ -603,8 +605,9 @@ void MockLink::_paramRequestListWorker(void)
qCDebug
(
MockLinkLog
)
<<
"Sending msg_param_value"
<<
componentId
<<
paramId
<<
paramType
<<
_mapParamName2Value
[
componentId
][
paramId
];
mavlink_msg_param_value_pack
(
_vehicleSystemId
,
mavlink_msg_param_value_pack
_chan
(
_vehicleSystemId
,
componentId
,
// component id
mavlinkChannel
(),
&
responseMsg
,
// Outgoing message
paramId
,
// Parameter name
_floatUnionForParam
(
componentId
,
paramName
),
// Parameter value
...
...
@@ -650,8 +653,9 @@ 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
,
mavlink_msg_param_value_pack
_chan
(
_vehicleSystemId
,
componentId
,
// component id
mavlinkChannel
(),
&
responseMsg
,
// Outgoing message
paramId
,
// Parameter name
request
.
param_value
,
// Send same value back
...
...
@@ -676,8 +680,9 @@ 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
,
mavlink_msg_param_value_pack
_chan
(
_vehicleSystemId
,
componentId
,
mavlinkChannel
(),
&
responseMsg
,
request
.
param_id
,
valueUnion
.
param_float
,
...
...
@@ -717,8 +722,9 @@ void MockLink::_handleParamRequestRead(const mavlink_message_t& msg)
return
;
}
mavlink_msg_param_value_pack
(
_vehicleSystemId
,
mavlink_msg_param_value_pack
_chan
(
_vehicleSystemId
,
componentId
,
// component id
mavlinkChannel
(),
&
responseMsg
,
// Outgoing message
paramId
,
// Parameter name
_floatUnionForParam
(
componentId
,
paramId
),
// Parameter value
...
...
@@ -738,8 +744,9 @@ void MockLink::emitRemoteControlChannelRawChanged(int channel, uint16_t raw)
chanRaw
[
channel
]
=
raw
;
mavlink_message_t
responseMsg
;
mavlink_msg_rc_channels_pack
(
_vehicleSystemId
,
mavlink_msg_rc_channels_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
responseMsg
,
// Outgoing message
0
,
// time since boot, ignored
18
,
// channel count
...
...
@@ -801,8 +808,9 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg)
}
mavlink_message_t
commandAck
;
mavlink_msg_command_ack_pack
(
_vehicleSystemId
,
mavlink_msg_command_ack_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
commandAck
,
request
.
command
,
commandResult
);
...
...
@@ -827,8 +835,9 @@ void MockLink::_respondWithAutopilotVersion(void)
flightVersion
|=
FIRMWARE_VERSION_TYPE_DEV
<<
(
8
*
0
);
}
mavlink_msg_autopilot_version_pack
(
_vehicleSystemId
,
mavlink_msg_autopilot_version_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
0
,
// capabilities,
flightVersion
,
// flight_sw_version,
...
...
@@ -859,8 +868,9 @@ void MockLink::_sendHomePosition(void)
bogus
[
2
]
=
0.0
f
;
bogus
[
3
]
=
0.0
f
;
mavlink_msg_home_position_pack
(
_vehicleSystemId
,
mavlink_msg_home_position_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
(
int32_t
)(
_vehicleLatitude
*
1E7
),
(
int32_t
)(
_vehicleLongitude
*
1E7
),
...
...
@@ -876,8 +886,9 @@ void MockLink::_sendGpsRawInt(void)
static
uint64_t
timeTick
=
0
;
mavlink_message_t
msg
;
mavlink_msg_gps_raw_int_pack
(
_vehicleSystemId
,
mavlink_msg_gps_raw_int_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
timeTick
++
,
// time since boot
3
,
// 3D fix
...
...
@@ -914,8 +925,9 @@ void MockLink::_sendStatusTextMessages(void)
mavlink_message_t
msg
;
const
struct
StatusMessage
*
status
=
&
rgMessages
[
i
];
mavlink_msg_statustext_pack
(
_vehicleSystemId
,
mavlink_msg_statustext_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
status
->
severity
,
status
->
msg
);
...
...
@@ -1065,8 +1077,9 @@ void MockLink::_sendRCChannels(void)
{
mavlink_message_t
msg
;
mavlink_msg_rc_channels_pack
(
_vehicleSystemId
,
mavlink_msg_rc_channels_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
0
,
// time_boot_ms
8
,
// chancount
...
...
@@ -1106,8 +1119,9 @@ void MockLink::_handlePreFlightCalibration(const mavlink_command_long_t& request
}
mavlink_message_t
msg
;
mavlink_msg_statustext_pack
(
_vehicleSystemId
,
mavlink_msg_statustext_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
msg
,
MAV_SEVERITY_INFO
,
pCalMessage
);
...
...
@@ -1126,8 +1140,9 @@ void MockLink::_handleLogRequestList(const mavlink_message_t& msg)
}
mavlink_message_t
responseMsg
;
mavlink_msg_log_entry_pack
(
_vehicleSystemId
,
mavlink_msg_log_entry_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
responseMsg
,
_logDownloadLogId
,
// log id
1
,
// num_logs
...
...
@@ -1181,8 +1196,9 @@ void MockLink::_logDownloadWorker(void)
qDebug
()
<<
"MockLink::_logDownloadWorker"
<<
_logDownloadCurrentOffset
<<
_logDownloadBytesRemaining
;
mavlink_message_t
responseMsg
;
mavlink_msg_log_data_pack
(
_vehicleSystemId
,
mavlink_msg_log_data_pack
_chan
(
_vehicleSystemId
,
_vehicleComponentId
,
mavlinkChannel
(),
&
responseMsg
,
_logDownloadLogId
,
_logDownloadCurrentOffset
,
...
...
src/comm/MockLinkFileServer.cc
View file @
f69b38e4
...
...
@@ -365,8 +365,9 @@ void MockLinkFileServer::_sendResponse(uint8_t targetSystemId, uint8_t targetCom
request
->
hdr
.
seqNumber
=
seqNumber
;
mavlink_msg_file_transfer_protocol_pack
(
_systemIdServer
,
// System ID
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
,
...
...
src/comm/MockLinkMissionItemHandler.cc
View file @
f69b38e4
...
...
@@ -96,8 +96,9 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message
mavlink_message_t
responseMsg
;
mavlink_msg_mission_count_pack
(
_mockLink
->
vehicleId
(),
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
...
...
@@ -149,8 +150,9 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
item
=
_missionItems
[
request
.
seq
];
}
mavlink_msg_mission_item_pack
(
_mockLink
->
vehicleId
(),
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
...
...
@@ -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
);
}
...
...
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