Commit e7979fd9 authored by Don Gagne's avatar Don Gagne

Must use pack_chan and encode_chan due to mav 2.0 problem

_finalize methods need information which is not available if all you
have is a mavlink_message_t
parent 01c4ef3c
...@@ -468,9 +468,13 @@ void APMSensorsComponentController::nextClicked(void) ...@@ -468,9 +468,13 @@ void APMSensorsComponentController::nextClicked(void)
ack.command = 0; ack.command = 0;
ack.result = 1; 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->sendMessageOnPriorityLink(msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
if (_compassMotCalInProgress) { if (_compassMotCalInProgress) {
_stopCalibration(StopCalibrationSuccess); _stopCalibration(StopCalibrationSuccess);
......
...@@ -318,9 +318,11 @@ void ...@@ -318,9 +318,11 @@ void
ESP8266ComponentController::_reboot() ESP8266ComponentController::_reboot()
{ {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_command_long_pack(
mavlink_msg_command_long_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg, &msg,
_vehicle->id(), _vehicle->id(),
MAV_COMP_ID_UDP_BRIDGE, MAV_COMP_ID_UDP_BRIDGE,
...@@ -339,9 +341,10 @@ void ...@@ -339,9 +341,10 @@ void
ESP8266ComponentController::_restoreDefaults() ESP8266ComponentController::_restoreDefaults()
{ {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_command_long_pack( mavlink_msg_command_long_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg, &msg,
_vehicle->id(), _vehicle->id(),
MAV_COMP_ID_UDP_BRIDGE, MAV_COMP_ID_UDP_BRIDGE,
......
...@@ -395,7 +395,12 @@ void ParameterManager::refreshAllParameters(uint8_t componentID) ...@@ -395,7 +395,12 @@ void ParameterManager::refreshAllParameters(uint8_t componentID)
Q_ASSERT(mavlink); Q_ASSERT(mavlink);
mavlink_message_t msg; 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); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
QString what = (componentID == MAV_COMP_ID_ALL) ? "MAV_COMP_ID_ALL" : QString::number(componentID); 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 ...@@ -618,13 +623,14 @@ void ParameterManager::_readParameterRaw(int componentId, const QString& paramNa
char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN]; char fixedParamName[MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN];
strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName)); strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName));
mavlink_msg_param_request_read_pack(_mavlink->getSystemId(), // Our system id mavlink_msg_param_request_read_pack_chan(_mavlink->getSystemId(), // QGC system id
_mavlink->getComponentId(), // Our component id _mavlink->getComponentId(), // QGC component id
&msg, // Pack into this mavlink_message_t _vehicle->priorityLink()->mavlinkChannel(),
_vehicle->id(), // Target system id &msg, // Pack into this mavlink_message_t
componentId, // Target component id _vehicle->id(), // Target system id
fixedParamName, // Named parameter being requested componentId, // Target component id
paramIndex); // Parameter index being requested, -1 for named fixedParamName, // Named parameter being requested
paramIndex); // Parameter index being requested, -1 for named
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
...@@ -677,7 +683,11 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN ...@@ -677,7 +683,11 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN
strncpy(p.param_id, paramName.toStdString().c_str(), sizeof(p.param_id)); strncpy(p.param_id, paramName.toStdString().c_str(), sizeof(p.param_id));
mavlink_message_t msg; 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); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
...@@ -756,7 +766,11 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian ...@@ -756,7 +766,11 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian
p.target_system = (uint8_t)_vehicle->id(); p.target_system = (uint8_t)_vehicle->id();
p.target_component = (uint8_t)componentId; p.target_component = (uint8_t)componentId;
mavlink_message_t msg; 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); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
// Give the user some feedback things loaded properly // Give the user some feedback things loaded properly
...@@ -787,7 +801,13 @@ void ParameterManager::_saveToEEPROM(void) ...@@ -787,7 +801,13 @@ void ParameterManager::_saveToEEPROM(void)
_saveRequired = false; _saveRequired = false;
if (_vehicle->firmwarePlugin()->isCapable(_vehicle, FirmwarePlugin::MavCmdPreflightStorageCapability)) { if (_vehicle->firmwarePlugin()->isCapable(_vehicle, FirmwarePlugin::MavCmdPreflightStorageCapability)) {
mavlink_message_t msg; 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); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
qCDebug(ParameterManagerLog) << "_saveToEEPROM"; qCDebug(ParameterManagerLog) << "_saveToEEPROM";
} else { } else {
...@@ -1409,17 +1429,18 @@ void ParameterManager::resetAllParametersToDefaults(void) ...@@ -1409,17 +1429,18 @@ void ParameterManager::resetAllParametersToDefaults(void)
mavlink_message_t msg; mavlink_message_t msg;
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink_msg_command_long_pack_chan(mavlink->getSystemId(),
mavlink->getComponentId(), mavlink->getComponentId(),
&msg, _vehicle->priorityLink()->mavlinkChannel(),
_vehicle->id(), // Target systeem &msg,
_vehicle->defaultComponentId(), // Target component _vehicle->id(), // Target systeem
MAV_CMD_PREFLIGHT_STORAGE, _vehicle->defaultComponentId(), // Target component
0, // Confirmation MAV_CMD_PREFLIGHT_STORAGE,
2, // 2 = Reset params to default 0, // Confirmation
-1, // -1 = No change to mission storage 2, // 2 = Reset params to default
0, // 0 = Ignore -1, // -1 = No change to mission storage
0, 0, 0, 0); // Unused 0, // 0 = Ignore
_vehicle->sendMessageOnPriorityLink(msg); 0, 0, 0, 0); // Unused
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
...@@ -251,10 +251,14 @@ void APMFirmwarePlugin::_handleParamValue(Vehicle* vehicle, mavlink_message_t* m ...@@ -251,10 +251,14 @@ void APMFirmwarePlugin::_handleParamValue(Vehicle* vehicle, mavlink_message_t* m
paramValue.param_value = paramUnion.param_float; 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::_handleParamSet(Vehicle* vehicle, mavlink_message_t* message) void APMFirmwarePlugin::_handleOutgoingParamSet(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message)
{ {
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
...@@ -294,7 +298,7 @@ void APMFirmwarePlugin::_handleParamSet(Vehicle* vehicle, mavlink_message_t* mes ...@@ -294,7 +298,7 @@ void APMFirmwarePlugin::_handleParamSet(Vehicle* vehicle, mavlink_message_t* mes
qCCritical(APMFirmwarePluginLog) << "Invalid/Unsupported data type used in parameter:" << paramSet.param_type; 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::_handleStatusText(Vehicle* vehicle, mavlink_message_t* message)
...@@ -447,7 +451,7 @@ bool APMFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_m ...@@ -447,7 +451,7 @@ bool APMFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_m
return true; 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 //-- Don't process messages to/from UDP Bridge. It doesn't suffer from these issues
if (message->compid == MAV_COMP_ID_UDP_BRIDGE) { if (message->compid == MAV_COMP_ID_UDP_BRIDGE) {
...@@ -456,7 +460,7 @@ void APMFirmwarePlugin::adjustOutgoingMavlinkMessage(Vehicle* vehicle, mavlink_m ...@@ -456,7 +460,7 @@ void APMFirmwarePlugin::adjustOutgoingMavlinkMessage(Vehicle* vehicle, mavlink_m
switch (message->msgid) { switch (message->msgid) {
case MAVLINK_MSG_ID_PARAM_SET: case MAVLINK_MSG_ID_PARAM_SET:
_handleParamSet(vehicle, message); _handleOutgoingParamSet(vehicle, outgoingLink, message);
break; break;
} }
} }
...@@ -518,7 +522,10 @@ void APMFirmwarePlugin::_adjustSeverity(mavlink_message_t* message) const ...@@ -518,7 +522,10 @@ void APMFirmwarePlugin::_adjustSeverity(mavlink_message_t* message) const
break; 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 void APMFirmwarePlugin::_setInfoSeverity(mavlink_message_t* message) const
...@@ -527,7 +534,10 @@ 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); mavlink_msg_statustext_decode(message, &statusText);
statusText.severity = MAV_SEVERITY_INFO; 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 void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(mavlink_message_t* message) const
......
...@@ -83,7 +83,7 @@ public: ...@@ -83,7 +83,7 @@ public:
void pauseVehicle (Vehicle* vehicle); void pauseVehicle (Vehicle* vehicle);
int manualControlReservedButtonCount(void); int manualControlReservedButtonCount(void);
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) final; 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; void initializeVehicle (Vehicle* vehicle) final;
bool sendHomePositionToVehicle (void) final; bool sendHomePositionToVehicle (void) final;
void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final; void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
...@@ -115,7 +115,7 @@ private: ...@@ -115,7 +115,7 @@ private:
void _setInfoSeverity(mavlink_message_t* message) const; void _setInfoSeverity(mavlink_message_t* message) const;
QString _getMessageText(mavlink_message_t* message) const; QString _getMessageText(mavlink_message_t* message) const;
void _handleParamValue(Vehicle* vehicle, mavlink_message_t* message); void _handleParamValue(Vehicle* vehicle, mavlink_message_t* message);
void _handleParamSet(Vehicle* vehicle, mavlink_message_t* message); void _handleOutgoingParamSet(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message);
bool _handleStatusText(Vehicle* vehicle, mavlink_message_t* message); bool _handleStatusText(Vehicle* vehicle, mavlink_message_t* message);
void _handleHeartbeat(Vehicle* vehicle, mavlink_message_t* message); void _handleHeartbeat(Vehicle* vehicle, mavlink_message_t* message);
void _soloVideoHandshake(Vehicle* vehicle); void _soloVideoHandshake(Vehicle* vehicle);
......
...@@ -178,13 +178,14 @@ void APMGeoFenceManager::_requestFencePoint(uint8_t pointIndex) ...@@ -178,13 +178,14 @@ void APMGeoFenceManager::_requestFencePoint(uint8_t pointIndex)
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::_requestFencePoint" << pointIndex; qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::_requestFencePoint" << pointIndex;
mavlink_msg_fence_fetch_point_pack(mavlink->getSystemId(), mavlink_msg_fence_fetch_point_pack_chan(mavlink->getSystemId(),
mavlink->getComponentId(), mavlink->getComponentId(),
&msg, _vehicle->priorityLink()->mavlinkChannel(),
_vehicle->id(), &msg,
_vehicle->defaultComponentId(), _vehicle->id(),
pointIndex); _vehicle->defaultComponentId(),
_vehicle->sendMessageOnPriorityLink(msg); pointIndex);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
void APMGeoFenceManager::_sendFencePoint(uint8_t pointIndex) void APMGeoFenceManager::_sendFencePoint(uint8_t pointIndex)
...@@ -206,16 +207,17 @@ 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 // Total point count, +1 polygon close in last index, +1 for breach in index 0
uint8_t totalPointCount = _polygon.count() + 1 + 1; uint8_t totalPointCount = _polygon.count() + 1 + 1;
mavlink_msg_fence_point_pack(mavlink->getSystemId(), mavlink_msg_fence_point_pack_chan(mavlink->getSystemId(),
mavlink->getComponentId(), mavlink->getComponentId(),
&msg, _vehicle->priorityLink()->mavlinkChannel(),
_vehicle->id(), &msg,
_vehicle->defaultComponentId(), _vehicle->id(),
pointIndex, // Index of point to set _vehicle->defaultComponentId(),
totalPointCount, pointIndex, // Index of point to set
fenceCoord.latitude(), totalPointCount,
fenceCoord.longitude()); fenceCoord.latitude(),
_vehicle->sendMessageOnPriorityLink(msg); fenceCoord.longitude());
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
bool APMGeoFenceManager::inProgress(void) const bool APMGeoFenceManager::inProgress(void) const
......
...@@ -109,13 +109,14 @@ void APMRallyPointManager::_requestRallyPoint(uint8_t pointIndex) ...@@ -109,13 +109,14 @@ void APMRallyPointManager::_requestRallyPoint(uint8_t pointIndex)
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
qCDebug(RallyPointManagerLog) << "APMRallyPointManager::_requestRallyPoint" << pointIndex; qCDebug(RallyPointManagerLog) << "APMRallyPointManager::_requestRallyPoint" << pointIndex;
mavlink_msg_rally_fetch_point_pack(mavlink->getSystemId(), mavlink_msg_rally_fetch_point_pack_chan(mavlink->getSystemId(),
mavlink->getComponentId(), mavlink->getComponentId(),
&msg, _vehicle->priorityLink()->mavlinkChannel(),
_vehicle->id(), &msg,
_vehicle->defaultComponentId(), _vehicle->id(),
pointIndex); _vehicle->defaultComponentId(),
_vehicle->sendMessageOnPriorityLink(msg); pointIndex);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
void APMRallyPointManager::_sendRallyPoint(uint8_t pointIndex) void APMRallyPointManager::_sendRallyPoint(uint8_t pointIndex)
...@@ -124,18 +125,19 @@ void APMRallyPointManager::_sendRallyPoint(uint8_t pointIndex) ...@@ -124,18 +125,19 @@ void APMRallyPointManager::_sendRallyPoint(uint8_t pointIndex)
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
QGeoCoordinate point = _rgPoints[pointIndex]; QGeoCoordinate point = _rgPoints[pointIndex];
mavlink_msg_rally_point_pack(mavlink->getSystemId(), mavlink_msg_rally_point_pack_chan(mavlink->getSystemId(),
mavlink->getComponentId(), mavlink->getComponentId(),
&msg, _vehicle->priorityLink()->mavlinkChannel(),
_vehicle->id(), &msg,
_vehicle->defaultComponentId(), _vehicle->id(),
pointIndex, _vehicle->defaultComponentId(),
_rgPoints.count(), pointIndex,
point.latitude() * 1e7, _rgPoints.count(),
point.longitude() * 1e7, point.latitude() * 1e7,
point.altitude(), point.longitude() * 1e7,
0, 0, 0); // break_alt, land_dir, flags point.altitude(),
_vehicle->sendMessageOnPriorityLink(msg); 0, 0, 0); // break_alt, land_dir, flags
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
bool APMRallyPointManager::inProgress(void) const bool APMRallyPointManager::inProgress(void) const
......
...@@ -141,9 +141,13 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitu ...@@ -141,9 +141,13 @@ void ArduCopterFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitu
cmd.target_component = vehicle->defaultComponentId(); cmd.target_component = vehicle->defaultComponentId();
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); 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->sendMessageOnPriorityLink(msg); vehicle->sendMessageOnLink(vehicle->priorityLink(), msg);
} }
void ArduCopterFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) void ArduCopterFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
...@@ -179,9 +183,13 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double ...@@ -179,9 +183,13 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double
cmd.z = -(altitudeRel - vehicle->altitudeRelative()->rawValue().toDouble()); cmd.z = -(altitudeRel - vehicle->altitudeRelative()->rawValue().toDouble());
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); 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->sendMessageOnPriorityLink(msg); vehicle->sendMessageOnLink(vehicle->priorityLink(), msg);
} }
bool ArduCopterFirmwarePlugin::isPaused(const Vehicle* vehicle) const bool ArduCopterFirmwarePlugin::isPaused(const Vehicle* vehicle) const
......
...@@ -112,9 +112,10 @@ bool FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_mess ...@@ -112,9 +112,10 @@ bool FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_mess
return true; 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(vehicle);
Q_UNUSED(outgoingLink);
Q_UNUSED(message); Q_UNUSED(message);
// Generic plugin does no message adjustment // Generic plugin does no message adjustment
} }
......
...@@ -159,8 +159,9 @@ public: ...@@ -159,8 +159,9 @@ public:
/// This is handy to adjust or differences in mavlink spec implementations such that the base code can remain /// This is handy to adjust or differences in mavlink spec implementations such that the base code can remain
/// mavlink generic. /// mavlink generic.
/// @param vehicle Vehicle message came from /// @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. /// @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 /// Determines how to handle the first item of the mission item list. Internally to QGC the first item
/// is always the home position. /// is always the home position.
......
...@@ -283,9 +283,13 @@ void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle) ...@@ -283,9 +283,13 @@ void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
cmd.target_component = vehicle->defaultComponentId(); cmd.target_component = vehicle->defaultComponentId();
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); 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->sendMessageOnPriorityLink(msg); vehicle->sendMessageOnLink(vehicle->priorityLink(), msg);
} }
void PX4FirmwarePlugin::guidedModeRTL(Vehicle* vehicle) void PX4FirmwarePlugin::guidedModeRTL(Vehicle* vehicle)
...@@ -317,8 +321,12 @@ void PX4FirmwarePlugin::guidedModeOrbit(Vehicle* vehicle, const QGeoCoordinate& ...@@ -317,8 +321,12 @@ void PX4FirmwarePlugin::guidedModeOrbit(Vehicle* vehicle, const QGeoCoordinate&
cmd.param7 = centerCoord.isValid() ? centerCoord.altitude() : NAN; cmd.param7 = centerCoord.isValid() ? centerCoord.altitude() : NAN;
cmd.target_system = vehicle->id(); cmd.target_system = vehicle->id();
cmd.target_component = vehicle->defaultComponentId(); cmd.target_component = vehicle->defaultComponentId();
mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd); mavlink_msg_command_long_encode_chan(mavlink->getSystemId(),
vehicle->sendMessageOnPriorityLink(msg); mavlink->getComponentId(),
vehicle->priorityLink()->mavlinkChannel(),
&msg,
&cmd);
vehicle->sendMessageOnLink(vehicle->priorityLink(), msg);
} }
void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitudeRel) void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitudeRel)
...@@ -347,8 +355,12 @@ 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_system = vehicle->id();
cmd.target_component = vehicle->defaultComponentId(); cmd.target_component = vehicle->defaultComponentId();
mavlink_msg_command_long_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &cmd); mavlink_msg_command_long_encode_chan(mavlink->getSystemId(),
vehicle->sendMessageOnPriorityLink(msg); mavlink->getComponentId(),
vehicle->priorityLink()->mavlinkChannel(),
&msg,
&cmd);
vehicle->sendMessageOnLink(vehicle->priorityLink(), msg);
} }
void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord) void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
...@@ -374,9 +386,13 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord ...@@ -374,9 +386,13 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
cmd.target_component = vehicle->defaultComponentId(); cmd.target_component = vehicle->defaultComponentId();
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); 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->sendMessageOnPriorityLink(msg); vehicle->sendMessageOnLink(vehicle->priorityLink(), msg);
} }
void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel) void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel)
...@@ -402,9 +418,13 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu ...@@ -402,9 +418,13 @@ void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
cmd.target_component = vehicle->defaultComponentId(); cmd.target_component = vehicle->defaultComponentId();
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); 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->sendMessageOnPriorityLink(msg); vehicle->sendMessageOnLink(vehicle->priorityLink(), msg);
} }
void PX4FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode) void PX4FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
......
...@@ -140,11 +140,12 @@ void FollowMe::_sendGCSMotionReport(void) ...@@ -140,11 +140,12 @@ void FollowMe::_sendGCSMotionReport(void)
Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]); Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]);
if(vehicle->flightMode().compare(PX4FirmwarePlugin::followMeFlightMode, Qt::CaseInsensitive) == 0) { if(vehicle->flightMode().compare(PX4FirmwarePlugin::followMeFlightMode, Qt::CaseInsensitive) == 0) {
mavlink_message_t message; mavlink_message_t message;
mavlink_msg_follow_target_encode(mavlinkProtocol->getSystemId(), mavlink_msg_follow_target_encode_chan(mavlinkProtocol->getSystemId(),
mavlinkProtocol->getComponentId(), mavlinkProtocol->getComponentId(),
&message, vehicle->priorityLink()->mavlinkChannel(),
&follow_target); &message,
vehicle->sendMessageOnPriorityLink(message); &follow_target);
vehicle->sendMessageOnLink(vehicle->priorityLink(), message);
} }
} }
} }
......
...@@ -61,8 +61,11 @@ void RTCMMavlink::sendMessageToVehicle(const mavlink_gps_rtcm_data_t& msg) ...@@ -61,8 +61,11 @@ void RTCMMavlink::sendMessageToVehicle(const mavlink_gps_rtcm_data_t& msg)
for (int i = 0; i < vehicles.count(); i++) { for (int i = 0; i < vehicles.count(); i++) {
Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]); Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]);
mavlink_message_t message; mavlink_message_t message;
mavlink_msg_gps_rtcm_data_encode(mavlinkProtocol->getSystemId(), mavlink_msg_gps_rtcm_data_encode_chan(mavlinkProtocol->getSystemId(),
mavlinkProtocol->getComponentId(), &message, &msg); mavlinkProtocol->getComponentId(),
vehicle->sendMessageOnPriorityLink(message); vehicle->priorityLink()->mavlinkChannel(),
&message,
&msg);
vehicle->sendMessageOnLink(vehicle->priorityLink(), message);
} }
} }
...@@ -90,9 +90,13 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems) ...@@ -90,9 +90,13 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER; missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionCount.count = _missionItems.count(); missionCount.count = _missionItems.count();
mavlink_msg_mission_count_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionCount);
_dedicatedLink = _vehicle->priorityLink(); _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); _vehicle->sendMessageOnLink(_dedicatedLink, message);
_startAckTimeout(AckMissionRequest); _startAckTimeout(AckMissionRequest);
emit inProgressChanged(true); emit inProgressChanged(true);
...@@ -125,9 +129,13 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC ...@@ -125,9 +129,13 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC
missionItem.current = altChangeOnly ? 3 : 2; missionItem.current = altChangeOnly ? 3 : 2;
missionItem.autocontinue = true; missionItem.autocontinue = true;
mavlink_msg_mission_item_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &messageOut, &missionItem);
_dedicatedLink = _vehicle->priorityLink(); _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); _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
_startAckTimeout(AckGuidedItem); _startAckTimeout(AckGuidedItem);
emit inProgressChanged(true); emit inProgressChanged(true);
...@@ -157,9 +165,13 @@ void MissionManager::requestMissionItems(void) ...@@ -157,9 +165,13 @@ void MissionManager::requestMissionItems(void)
request.target_system = _vehicle->id(); request.target_system = _vehicle->id();
request.target_component = MAV_COMP_ID_MISSIONPLANNER; 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(); _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); _vehicle->sendMessageOnLink(_dedicatedLink, message);
_startAckTimeout(AckMissionCount); _startAckTimeout(AckMissionCount);
emit inProgressChanged(true); emit inProgressChanged(true);
...@@ -223,7 +235,11 @@ void MissionManager::_readTransactionComplete(void) ...@@ -223,7 +235,11 @@ void MissionManager::_readTransactionComplete(void)
missionAck.target_component = MAV_COMP_ID_MISSIONPLANNER; missionAck.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionAck.type = MAV_MISSION_ACCEPTED; 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); _vehicle->sendMessageOnLink(_dedicatedLink, message);
...@@ -269,7 +285,11 @@ void MissionManager::_requestNextMissionItem(void) ...@@ -269,7 +285,11 @@ void MissionManager::_requestNextMissionItem(void)
missionRequest.target_component = MAV_COMP_ID_MISSIONPLANNER; missionRequest.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionRequest.seq = _itemIndicesToRead[0]; 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); _vehicle->sendMessageOnLink(_dedicatedLink, message);
_startAckTimeout(AckMissionItem); _startAckTimeout(AckMissionItem);
...@@ -377,7 +397,11 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message) ...@@ -377,7 +397,11 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message)
missionItem.current = missionRequest.seq == 0; missionItem.current = missionRequest.seq == 0;
missionItem.autocontinue = item->autoContinue(); 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); _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
_startAckTimeout(AckMissionRequest); _startAckTimeout(AckMissionRequest);
......
...@@ -188,12 +188,6 @@ void QGroundControlQmlGlobal::setIsSaveLogPromptNotArmed(bool prompt) ...@@ -188,12 +188,6 @@ void QGroundControlQmlGlobal::setIsSaveLogPromptNotArmed(bool prompt)
emit isSaveLogPromptNotArmedChanged(prompt); emit isSaveLogPromptNotArmedChanged(prompt);
} }
void QGroundControlQmlGlobal::setIsMultiplexingEnabled(bool enable)
{
qgcApp()->toolbox()->mavlinkProtocol()->enableMultiplexing(enable);
emit isMultiplexingEnabledChanged(enable);
}
void QGroundControlQmlGlobal::setIsVersionCheckEnabled(bool enable) void QGroundControlQmlGlobal::setIsVersionCheckEnabled(bool enable)
{ {
qgcApp()->toolbox()->mavlinkProtocol()->enableVersionCheck(enable); qgcApp()->toolbox()->mavlinkProtocol()->enableVersionCheck(enable);
......
...@@ -87,7 +87,6 @@ public: ...@@ -87,7 +87,6 @@ public:
Q_PROPERTY(qreal baseFontPointSize READ baseFontPointSize WRITE setBaseFontPointSize NOTIFY baseFontPointSizeChanged) Q_PROPERTY(qreal baseFontPointSize READ baseFontPointSize WRITE setBaseFontPointSize NOTIFY baseFontPointSizeChanged)
// MavLink Protocol // MavLink Protocol
Q_PROPERTY(bool isMultiplexingEnabled READ isMultiplexingEnabled WRITE setIsMultiplexingEnabled NOTIFY isMultiplexingEnabledChanged)
Q_PROPERTY(bool isVersionCheckEnabled READ isVersionCheckEnabled WRITE setIsVersionCheckEnabled NOTIFY isVersionCheckEnabledChanged) Q_PROPERTY(bool isVersionCheckEnabled READ isVersionCheckEnabled WRITE setIsVersionCheckEnabled NOTIFY isVersionCheckEnabledChanged)
Q_PROPERTY(int mavlinkSystemID READ mavlinkSystemID WRITE setMavlinkSystemID NOTIFY mavlinkSystemIDChanged) Q_PROPERTY(int mavlinkSystemID READ mavlinkSystemID WRITE setMavlinkSystemID NOTIFY mavlinkSystemIDChanged)
...@@ -179,7 +178,6 @@ public: ...@@ -179,7 +178,6 @@ public:
bool virtualTabletJoystick () { return _virtualTabletJoystick; } bool virtualTabletJoystick () { return _virtualTabletJoystick; }
qreal baseFontPointSize () { return _baseFontPointSize; } qreal baseFontPointSize () { return _baseFontPointSize; }
bool isMultiplexingEnabled () { return _toolbox->mavlinkProtocol()->multiplexingEnabled(); }
bool isVersionCheckEnabled () { return _toolbox->mavlinkProtocol()->versionCheckEnabled(); } bool isVersionCheckEnabled () { return _toolbox->mavlinkProtocol()->versionCheckEnabled(); }
int mavlinkSystemID () { return _toolbox->mavlinkProtocol()->getSystemId(); } int mavlinkSystemID () { return _toolbox->mavlinkProtocol()->getSystemId(); }
...@@ -204,7 +202,6 @@ public: ...@@ -204,7 +202,6 @@ public:
void setVirtualTabletJoystick (bool enabled); void setVirtualTabletJoystick (bool enabled);
void setBaseFontPointSize (qreal size); void setBaseFontPointSize (qreal size);
void setIsMultiplexingEnabled (bool enable);
void setIsVersionCheckEnabled (bool enable); void setIsVersionCheckEnabled (bool enable);
void setMavlinkSystemID (int id); void setMavlinkSystemID (int id);
......
...@@ -307,15 +307,16 @@ void MultiVehicleManager::_sendGCSHeartbeat(void) ...@@ -307,15 +307,16 @@ void MultiVehicleManager::_sendGCSHeartbeat(void)
Vehicle* vehicle = qobject_cast<Vehicle*>(_vehicles[i]); Vehicle* vehicle = qobject_cast<Vehicle*>(_vehicles[i]);
mavlink_message_t message; mavlink_message_t message;
mavlink_msg_heartbeat_pack(_mavlinkProtocol->getSystemId(), mavlink_msg_heartbeat_pack_chan(_mavlinkProtocol->getSystemId(),
_mavlinkProtocol->getComponentId(), _mavlinkProtocol->getComponentId(),
&message, vehicle->priorityLink()->mavlinkChannel(),
MAV_TYPE_GCS, // MAV_TYPE &message,
MAV_AUTOPILOT_INVALID, // MAV_AUTOPILOT MAV_TYPE_GCS, // MAV_TYPE
MAV_MODE_MANUAL_ARMED, // MAV_MODE MAV_AUTOPILOT_INVALID, // MAV_AUTOPILOT
0, // custom mode MAV_MODE_MANUAL_ARMED, // MAV_MODE
MAV_STATE_ACTIVE); // MAV_STATE 0, // custom mode
vehicle->sendMessageOnPriorityLink(message); MAV_STATE_ACTIVE); // MAV_STATE
vehicle->sendMessageOnLink(vehicle->priorityLink(), message);
} }
} }
......
...@@ -221,7 +221,11 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -221,7 +221,11 @@ Vehicle::Vehicle(LinkInterface* link,
versionCmd.param2 = versionCmd.param3 = versionCmd.param4 = versionCmd.param5 = versionCmd.param6 = versionCmd.param7 = 0; versionCmd.param2 = versionCmd.param3 = versionCmd.param4 = versionCmd.param5 = versionCmd.param6 = versionCmd.param7 = 0;
versionCmd.target_system = id(); versionCmd.target_system = id();
versionCmd.target_component = MAV_COMP_ID_ALL; 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); sendMessageMultiple(versionMsg);
_firmwarePlugin->initializeVehicle(this); _firmwarePlugin->initializeVehicle(this);
...@@ -874,10 +878,7 @@ void Vehicle::_sendMessageOnLink(LinkInterface* link, mavlink_message_t message) ...@@ -874,10 +878,7 @@ void Vehicle::_sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
} }
// Give the plugin a chance to adjust // Give the plugin a chance to adjust
_firmwarePlugin->adjustOutgoingMavlinkMessage(this, &message); _firmwarePlugin->adjustOutgoingMavlinkMessage(this, link, &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]);
// Write message into buffer, prepending start sign // Write message into buffer, prepending start sign
uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
...@@ -1277,9 +1278,13 @@ void Vehicle::setArmed(bool armed) ...@@ -1277,9 +1278,13 @@ void Vehicle::setArmed(bool armed)
cmd.target_system = id(); cmd.target_system = id();
cmd.target_component = defaultComponentId(); 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);
sendMessageOnPriorityLink(msg); sendMessageOnLink(priorityLink(), msg);
} }
bool Vehicle::flightModeSetAvailable(void) bool Vehicle::flightModeSetAvailable(void)
...@@ -1309,8 +1314,14 @@ void Vehicle::setFlightMode(const QString& flightMode) ...@@ -1309,8 +1314,14 @@ void Vehicle::setFlightMode(const QString& flightMode)
newBaseMode |= base_mode; newBaseMode |= base_mode;
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_set_mode_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), newBaseMode, custom_mode); mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(),
sendMessageOnPriorityLink(msg); _mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
id(),
newBaseMode,
custom_mode);
sendMessageOnLink(priorityLink(), msg);
} else { } else {
qWarning() << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode; qWarning() << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
} }
...@@ -1330,8 +1341,14 @@ void Vehicle::setHilMode(bool hilMode) ...@@ -1330,8 +1341,14 @@ void Vehicle::setHilMode(bool hilMode)
newBaseMode |= MAV_MODE_FLAG_HIL_ENABLED; newBaseMode |= MAV_MODE_FLAG_HIL_ENABLED;
} }
mavlink_msg_set_mode_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), newBaseMode, _custom_mode); mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(),
sendMessageOnPriorityLink(msg); _mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
id(),
newBaseMode,
_custom_mode);
sendMessageOnLink(priorityLink(), msg);
} }
void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple) 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 ...@@ -1345,13 +1362,17 @@ void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool send
dataStream.target_system = id(); dataStream.target_system = id();
dataStream.target_component = defaultComponentId(); 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) { if (sendMultiple) {
// We use sendMessageMultiple since we really want these to make it to the vehicle // We use sendMessageMultiple since we really want these to make it to the vehicle
sendMessageMultiple(msg); sendMessageMultiple(msg);
} else { } else {
sendMessageOnPriorityLink(msg); sendMessageOnLink(priorityLink(), msg);
} }
} }
...@@ -1360,7 +1381,7 @@ void Vehicle::_sendMessageMultipleNext(void) ...@@ -1360,7 +1381,7 @@ void Vehicle::_sendMessageMultipleNext(void)
if (_nextSendMessageMultipleIndex < _sendMessageMultipleList.count()) { if (_nextSendMessageMultipleIndex < _sendMessageMultipleList.count()) {
qCDebug(VehicleLog) << "_sendMessageMultipleNext:" << _sendMessageMultipleList[_nextSendMessageMultipleIndex].message.msgid; qCDebug(VehicleLog) << "_sendMessageMultipleNext:" << _sendMessageMultipleList[_nextSendMessageMultipleIndex].message.msgid;
sendMessageOnPriorityLink(_sendMessageMultipleList[_nextSendMessageMultipleIndex].message); sendMessageOnLink(priorityLink(), _sendMessageMultipleList[_nextSendMessageMultipleIndex].message);
if (--_sendMessageMultipleList[_nextSendMessageMultipleIndex].retryCount <= 0) { if (--_sendMessageMultipleList[_nextSendMessageMultipleIndex].retryCount <= 0) {
_sendMessageMultipleList.removeAt(_nextSendMessageMultipleIndex); _sendMessageMultipleList.removeAt(_nextSendMessageMultipleIndex);
...@@ -1764,9 +1785,13 @@ void Vehicle::emergencyStop(void) ...@@ -1764,9 +1785,13 @@ void Vehicle::emergencyStop(void)
cmd.param7 = 0.0f; cmd.param7 = 0.0f;
cmd.target_system = id(); cmd.target_system = id();
cmd.target_component = defaultComponentId(); 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);
sendMessageOnPriorityLink(msg); sendMessageOnLink(priorityLink(), msg);
} }
void Vehicle::setCurrentMissionSequence(int seq) void Vehicle::setCurrentMissionSequence(int seq)
...@@ -1775,8 +1800,14 @@ void Vehicle::setCurrentMissionSequence(int seq) ...@@ -1775,8 +1800,14 @@ void Vehicle::setCurrentMissionSequence(int seq)
seq--; seq--;
} }
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_mission_set_current_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, id(), _compID, seq); mavlink_msg_mission_set_current_pack_chan(_mavlink->getSystemId(),
sendMessageOnPriorityLink(msg); _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) 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 ...@@ -1795,9 +1826,13 @@ void Vehicle::doCommandLong(int component, MAV_CMD command, float param1, float
cmd.param7 = param7; cmd.param7 = param7;
cmd.target_system = id(); cmd.target_system = id();
cmd.target_component = component; 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);
sendMessageOnPriorityLink(msg); sendMessageOnLink(priorityLink(), msg);
} }
void Vehicle::setPrearmError(const QString& prearmError) void Vehicle::setPrearmError(const QString& prearmError)
......
...@@ -430,10 +430,6 @@ public: ...@@ -430,10 +430,6 @@ public:
/// @return true: message sent, false: Link no longer connected /// @return true: message sent, false: Link no longer connected
bool sendMessageOnLink(LinkInterface* link, mavlink_message_t message); 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 /// Sends the specified messages multiple times to the vehicle in order to attempt to
/// guarantee that it makes it to the vehicle. /// guarantee that it makes it to the vehicle.
void sendMessageMultiple(mavlink_message_t message); void sendMessageMultiple(mavlink_message_t message);
......
...@@ -458,12 +458,13 @@ LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t cou ...@@ -458,12 +458,13 @@ LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t cou
id += _apmOneBased; id += _apmOneBased;
qCDebug(LogDownloadLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << ")"; qCDebug(LogDownloadLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << ")";
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_log_request_data_pack( mavlink_msg_log_request_data_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
&msg, _vehicle->priorityLink()->mavlinkChannel(),
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId(), &msg,
id, offset, count); qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId(),
id, offset, count);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
} }
...@@ -485,14 +486,15 @@ LogDownloadController::_requestLogList(uint32_t start, uint32_t end) ...@@ -485,14 +486,15 @@ LogDownloadController::_requestLogList(uint32_t start, uint32_t end)
qCDebug(LogDownloadLog) << "Request log entry list (" << start << "through" << end << ")"; qCDebug(LogDownloadLog) << "Request log entry list (" << start << "through" << end << ")";
_setListing(true); _setListing(true);
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_log_request_list_pack( mavlink_msg_log_request_list_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
&msg, _vehicle->priorityLink()->mavlinkChannel(),
_vehicle->id(), &msg,
_vehicle->defaultComponentId(), _vehicle->id(),
start, _vehicle->defaultComponentId(),
end); start,
end);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
//-- Wait 5 seconds before bitching about not getting anything //-- Wait 5 seconds before bitching about not getting anything
_timer.start(5000); _timer.start(5000);
...@@ -650,11 +652,12 @@ LogDownloadController::eraseAll(void) ...@@ -650,11 +652,12 @@ LogDownloadController::eraseAll(void)
{ {
if(_vehicle && _uas) { if(_vehicle && _uas) {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_log_erase_pack( mavlink_msg_log_erase_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
&msg, _vehicle->priorityLink()->mavlinkChannel(),
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId()); &msg,
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId());
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
refresh(); refresh();
} }
......
...@@ -7,15 +7,6 @@ ...@@ -7,15 +7,6 @@
* *
****************************************************************************/ ****************************************************************************/
/**
* @file
* @brief Brief Description
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _LINKINTERFACE_H_ #ifndef _LINKINTERFACE_H_
#define _LINKINTERFACE_H_ #define _LINKINTERFACE_H_
...@@ -25,6 +16,7 @@ ...@@ -25,6 +16,7 @@
#include <QMutexLocker> #include <QMutexLocker>
#include <QMetaType> #include <QMetaType>
#include <QSharedPointer> #include <QSharedPointer>
#include <QDebug>
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
...@@ -124,7 +116,13 @@ public: ...@@ -124,7 +116,13 @@ public:
/// mavlink channel to use for this link, as used by mavlink_parse_char. The mavlink channel is only /// 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 /// 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 // 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. // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
......
...@@ -270,7 +270,7 @@ void LinkManager::_deleteLink(LinkInterface* link) ...@@ -270,7 +270,7 @@ void LinkManager::_deleteLink(LinkInterface* link)
} }
// Free up the mavlink channel associated with this link // Free up the mavlink channel associated with this link
_mavlinkChannelsUsedBitMask &= ~(1 << link->getMavlinkChannel()); _mavlinkChannelsUsedBitMask &= ~(1 << link->mavlinkChannel());
_links.removeOne(link); _links.removeOne(link);
delete link; delete link;
......
...@@ -167,7 +167,7 @@ quint64 LogReplayLink::_seekToNextMavlinkMessage(mavlink_message_t* nextMsg) ...@@ -167,7 +167,7 @@ quint64 LogReplayLink::_seekToNextMavlinkMessage(mavlink_message_t* nextMsg)
char nextByte; char nextByte;
mavlink_status_t comm; mavlink_status_t comm;
while (_logFile.getChar(&nextByte)) { // Loop over every byte while (_logFile.getChar(&nextByte)) { // Loop over every byte
bool messageFound = mavlink_parse_char(getMavlinkChannel(), nextByte, nextMsg, &comm); bool messageFound = mavlink_parse_char(mavlinkChannel(), nextByte, nextMsg, &comm);
// If we've found a message, jump back to the start of the message, grab the timestamp, // 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. // and go back to the end of this file.
......
...@@ -51,13 +51,7 @@ const char* MAVLinkProtocol::_logFileExtension = "mavlink"; ///< Ext ...@@ -51,13 +51,7 @@ const char* MAVLinkProtocol::_logFileExtension = "mavlink"; ///< Ext
*/ */
MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app) MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app)
: QGCTool(app) : QGCTool(app)
, m_multiplexingEnabled(false)
, m_enable_version_check(true) , m_enable_version_check(true)
, m_paramRetransmissionTimeout(350)
, m_paramRewriteTimeout(500)
, m_paramGuardEnabled(true)
, m_actionGuardEnabled(false)
, m_actionRetransmissionTimeout(100)
, versionMismatchIgnore(false) , versionMismatchIgnore(false)
, systemId(255) , systemId(255)
#ifndef __mobile__ #ifndef __mobile__
...@@ -124,7 +118,6 @@ void MAVLinkProtocol::loadSettings() ...@@ -124,7 +118,6 @@ void MAVLinkProtocol::loadSettings()
QSettings settings; QSettings settings;
settings.beginGroup("QGC_MAVLINK_PROTOCOL"); settings.beginGroup("QGC_MAVLINK_PROTOCOL");
enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool()); 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 // Only set system id if it was valid
int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt(); int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt();
...@@ -132,15 +125,6 @@ void MAVLinkProtocol::loadSettings() ...@@ -132,15 +125,6 @@ void MAVLinkProtocol::loadSettings()
{ {
systemId = temp; 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() void MAVLinkProtocol::storeSettings()
...@@ -149,18 +133,13 @@ void MAVLinkProtocol::storeSettings() ...@@ -149,18 +133,13 @@ void MAVLinkProtocol::storeSettings()
QSettings settings; QSettings settings;
settings.beginGroup("QGC_MAVLINK_PROTOCOL"); settings.beginGroup("QGC_MAVLINK_PROTOCOL");
settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check); settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
settings.setValue("GCS_SYSTEM_ID", systemId); settings.setValue("GCS_SYSTEM_ID", systemId);
// Parameter interface settings // 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) void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link)
{ {
int channel = link->getMavlinkChannel(); int channel = link->mavlinkChannel();
totalReceiveCounter[channel] = 0; totalReceiveCounter[channel] = 0;
totalLossCounter[channel] = 0; totalLossCounter[channel] = 0;
totalErrorCounter[channel] = 0; totalErrorCounter[channel] = 0;
...@@ -188,7 +167,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -188,7 +167,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
mavlink_message_t message; mavlink_message_t message;
mavlink_status_t status; mavlink_status_t status;
int mavlinkChannel = link->getMavlinkChannel(); int mavlinkChannel = link->mavlinkChannel();
static int mavlink09Count = 0; static int mavlink09Count = 0;
static int nonmavlinkCount = 0; static int nonmavlinkCount = 0;
...@@ -235,19 +214,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -235,19 +214,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{ {
decodedFirstPacket = true; 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) if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
{ {
// process telemetry status message // process telemetry status message
...@@ -375,19 +341,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -375,19 +341,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// kind of inefficient, but no issue for a groundstation pc. // kind of inefficient, but no issue for a groundstation pc.
// It buys as reentrancy for the whole code over all threads // It buys as reentrancy for the whole code over all threads
emit messageReceived(link, message); 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() ...@@ -417,110 +370,6 @@ int MAVLinkProtocol::getComponentId()
return 0; 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) void MAVLinkProtocol::enableVersionCheck(bool enabled)
{ {
m_enable_version_check = enabled; m_enable_version_check = enabled;
......
...@@ -64,54 +64,30 @@ public: ...@@ -64,54 +64,30 @@ public:
bool versionCheckEnabled() const { bool versionCheckEnabled() const {
return m_enable_version_check; return m_enable_version_check;
} }
/** @brief Get the multiplexing state */
bool multiplexingEnabled() const {
return m_multiplexingEnabled;
}
/** @brief Get the protocol version */ /** @brief Get the protocol version */
int getVersion() { int getVersion() {
return MAVLINK_VERSION; 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. * 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. * @returns -1 if this is not available for this protocol, # of packets otherwise.
*/ */
qint32 getReceivedPacketCount(const LinkInterface *link) const { qint32 getReceivedPacketCount(const LinkInterface *link) const {
return totalReceiveCounter[link->getMavlinkChannel()]; return totalReceiveCounter[link->mavlinkChannel()];
} }
/** /**
* Retrieve a total of all parsing errors for the specified link. * Retrieve a total of all parsing errors for the specified link.
* @returns -1 if this is not available for this protocol, # of errors otherwise. * @returns -1 if this is not available for this protocol, # of errors otherwise.
*/ */
qint32 getParsingErrorCount(const LinkInterface *link) const { qint32 getParsingErrorCount(const LinkInterface *link) const {
return totalErrorCounter[link->getMavlinkChannel()]; return totalErrorCounter[link->mavlinkChannel()];
} }
/** /**
* Retrieve a total of all dropped packets for the specified link. * Retrieve a total of all dropped packets for the specified link.
* @returns -1 if this is not available for this protocol, # of packets otherwise. * @returns -1 if this is not available for this protocol, # of packets otherwise.
*/ */
qint32 getDroppedPacketCount(const LinkInterface *link) const { qint32 getDroppedPacketCount(const LinkInterface *link) const {
return totalLossCounter[link->getMavlinkChannel()]; return totalLossCounter[link->mavlinkChannel()];
} }
/** /**
* Reset the counters for all metadata for this link. * Reset the counters for all metadata for this link.
...@@ -131,24 +107,6 @@ public slots: ...@@ -131,24 +107,6 @@ public slots:
/** @brief Set the system id of this application */ /** @brief Set the system id of this application */
void setSystemId(int id); 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 */ /** @brief Enable / disable version check */
void enableVersionCheck(bool enabled); void enableVersionCheck(bool enabled);
...@@ -166,13 +124,7 @@ public slots: ...@@ -166,13 +124,7 @@ public slots:
#endif #endif
protected: protected:
bool m_multiplexingEnabled; ///< Enable/disable packet multiplexing
bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC 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 QMutex receiveMutex; ///< Mutex to protect receiveBytes function
int lastIndex[256][256]; ///< Store the last received sequence ID for each system/componenet pair 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 int totalReceiveCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< The total number of successfully received messages
...@@ -189,24 +141,12 @@ signals: ...@@ -189,24 +141,12 @@ signals:
/** @brief Message received and directly copied via signal */ /** @brief Message received and directly copied via signal */
void messageReceived(LinkInterface* link, mavlink_message_t message); 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 */ /** @brief Emitted if version check is enabled / disabled */
void versionCheckChanged(bool enabled); void versionCheckChanged(bool enabled);
/** @brief Emitted if a message from the protocol should reach the user */ /** @brief Emitted if a message from the protocol should reach the user */
void protocolStatusMessage(const QString& title, const QString& message); void protocolStatusMessage(const QString& title, const QString& message);
/** @brief Emitted if a new system ID was set */ /** @brief Emitted if a new system ID was set */
void systemIdChanged(int systemId); 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 receiveLossPercentChanged(int uasId, float lossPercent);
void receiveLossTotalChanged(int uasId, int totalLoss); void receiveLossTotalChanged(int uasId, int totalLoss);
...@@ -232,10 +172,6 @@ private slots: ...@@ -232,10 +172,6 @@ private slots:
void _vehicleCountChanged(int count); void _vehicleCountChanged(int count);
private: 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__ #ifndef __mobile__
bool _closeLogFile(void); bool _closeLogFile(void);
void _startLogging(void); void _startLogging(void);
......
...@@ -346,7 +346,7 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes) ...@@ -346,7 +346,7 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
for (qint64 i=0; i<cBytes; i++) for (qint64 i=0; i<cBytes; i++)
{ {
if (!mavlink_parse_char(getMavlinkChannel(), bytes[i], &msg, &comm)) { if (!mavlink_parse_char(mavlinkChannel(), bytes[i], &msg, &comm)) {
continue; continue;
} }
......
...@@ -733,13 +733,14 @@ void FileManager::_sendRequest(Request* request) ...@@ -733,13 +733,14 @@ void FileManager::_sendRequest(Request* request)
} }
Q_ASSERT(_vehicle); Q_ASSERT(_vehicle);
mavlink_msg_file_transfer_protocol_pack(_systemIdQGC, // QGC System ID mavlink_msg_file_transfer_protocol_pack_chan(_systemIdQGC, // QGC System ID
0, // QGC Component ID 0, // QGC Component ID
&message, // Mavlink Message to pack into _dedicatedLink->mavlinkChannel(),
0, // Target network &message, // Mavlink Message to pack into
_systemIdServer, // Target system 0, // Target network
0, // Target component _systemIdServer, // Target system
(uint8_t*)request); // Payload 0, // Target component
(uint8_t*)request); // Payload
_vehicle->sendMessageOnLink(_dedicatedLink, message); _vehicle->sendMessageOnLink(_dedicatedLink, message);
} }
This diff is collapsed.
...@@ -37,16 +37,6 @@ QGCMAVLinkInspector::QGCMAVLinkInspector(const QString& title, QAction* action, ...@@ -37,16 +37,6 @@ QGCMAVLinkInspector::QGCMAVLinkInspector(const QString& title, QAction* action,
header << tr("Type"); header << tr("Type");
ui->treeWidget->setHeaderLabels(header); 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 the UI
connect(ui->systemComboBox, static_cast<void (QComboBox::*)(int)>(&QComboBox::currentIndexChanged), connect(ui->systemComboBox, static_cast<void (QComboBox::*)(int)>(&QComboBox::currentIndexChanged),
this, &QGCMAVLinkInspector::selectDropDownMenuSystem); this, &QGCMAVLinkInspector::selectDropDownMenuSystem);
...@@ -78,23 +68,11 @@ void QGCMAVLinkInspector::selectDropDownMenuSystem(int dropdownid) ...@@ -78,23 +68,11 @@ void QGCMAVLinkInspector::selectDropDownMenuSystem(int dropdownid)
{ {
selectedSystemID = ui->systemComboBox->itemData(dropdownid).toInt(); selectedSystemID = ui->systemComboBox->itemData(dropdownid).toInt();
rebuildComponentList(); rebuildComponentList();
if (selectedSystemID != 0 && selectedComponentID != 0) {
ui->rateTreeWidget->show();
} else {
ui->rateTreeWidget->hide();
}
} }
void QGCMAVLinkInspector::selectDropDownMenuComponent(int dropdownid) void QGCMAVLinkInspector::selectDropDownMenuComponent(int dropdownid)
{ {
selectedComponentID = ui->componentComboBox->itemData(dropdownid).toInt(); selectedComponentID = ui->componentComboBox->itemData(dropdownid).toInt();
if (selectedSystemID != 0 && selectedComponentID != 0) {
ui->rateTreeWidget->show();
} else {
ui->rateTreeWidget->hide();
}
} }
void QGCMAVLinkInspector::rebuildComponentList() void QGCMAVLinkInspector::rebuildComponentList()
...@@ -195,8 +173,6 @@ void QGCMAVLinkInspector::clearView() ...@@ -195,8 +173,6 @@ void QGCMAVLinkInspector::clearView()
onboardMessageInterval.clear(); onboardMessageInterval.clear();
ui->treeWidget->clear(); ui->treeWidget->clear();
ui->rateTreeWidget->clear();
} }
void QGCMAVLinkInspector::refreshView() void QGCMAVLinkInspector::refreshView()
...@@ -311,25 +287,6 @@ void QGCMAVLinkInspector::refreshView() ...@@ -311,25 +287,6 @@ void QGCMAVLinkInspector::refreshView()
if (!strcmp(msgname, "EMPTY")) { if (!strcmp(msgname, "EMPTY")) {
continue; 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 ...@@ -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() QGCMAVLinkInspector::~QGCMAVLinkInspector()
{ {
clearView(); clearView();
......
...@@ -36,8 +36,6 @@ public slots: ...@@ -36,8 +36,6 @@ public slots:
/** @Brief Select a component through the drop down menu */ /** @Brief Select a component through the drop down menu */
void selectDropDownMenuComponent(int dropdownid); void selectDropDownMenuComponent(int dropdownid);
void rateTreeItemChanged(QTreeWidgetItem* paramItem, int column);
protected: protected:
MAVLinkProtocol *_protocol; ///< MAVLink instance MAVLinkProtocol *_protocol; ///< MAVLink instance
int selectedSystemID; ///< Currently selected system int selectedSystemID; ///< Currently selected system
...@@ -45,7 +43,6 @@ protected: ...@@ -45,7 +43,6 @@ protected:
QMap<int, int> systems; ///< Already observed systems QMap<int, int> systems; ///< Already observed systems
QMap<int, int> components; ///< Already observed components QMap<int, int> components; ///< Already observed components
QMap<int, float> onboardMessageInterval; ///< Stores the onboard selected data rate 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 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. mavlink_message_info_t messageInfo[256]; // Store the metadata for all available MAVLink messages.
...@@ -63,8 +60,6 @@ protected: ...@@ -63,8 +60,6 @@ protected:
void updateField(int sysid, int msgid, int fieldid, QTreeWidgetItem* item); void updateField(int sysid, int msgid, int fieldid, QTreeWidgetItem* item);
/** @brief Rebuild the list of components */ /** @brief Rebuild the list of components */
void rebuildComponentList(); void rebuildComponentList();
/** @brief Change the stream interval */
void changeStreamInterval(int msgid, int interval);
/* @brief Create a new tree for a new UAS */ /* @brief Create a new tree for a new UAS */
void addUAStoTree(int sysId); void addUAStoTree(int sysId);
......
...@@ -13,7 +13,7 @@ ...@@ -13,7 +13,7 @@
<property name="windowTitle"> <property name="windowTitle">
<string>MAVLink Inspector</string> <string>MAVLink Inspector</string>
</property> </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"> <property name="leftMargin">
<number>6</number> <number>6</number>
</property> </property>
...@@ -26,13 +26,25 @@ ...@@ -26,13 +26,25 @@
<property name="bottomMargin"> <property name="bottomMargin">
<number>6</number> <number>6</number>
</property> </property>
<item row="0" column="4"> <item row="0" column="0">
<widget class="QPushButton" name="clearButton"> <widget class="QLabel" name="label">
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="text"> <property name="text">
<string>Clear</string> <string>System</string>
</property> </property>
</widget> </widget>
</item> </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"> <item row="0" column="2">
<widget class="QLabel" name="label_2"> <widget class="QLabel" name="label_2">
<property name="text"> <property name="text">
...@@ -40,10 +52,10 @@ ...@@ -40,10 +52,10 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="0"> <item row="0" column="4">
<widget class="QLabel" name="label"> <widget class="QPushButton" name="clearButton">
<property name="text"> <property name="text">
<string>System</string> <string>Clear</string>
</property> </property>
</widget> </widget>
</item> </item>
...@@ -56,21 +68,6 @@ ...@@ -56,21 +68,6 @@
</column> </column>
</widget> </widget>
</item> </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> </layout>
</widget> </widget>
<resources/> <resources/>
......
...@@ -69,15 +69,6 @@ Rectangle { ...@@ -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 //-- Mavlink Version Check
QGCCheckBox { QGCCheckBox {
text: qsTr("Only accept MAVs with same protocol version") text: qsTr("Only accept MAVs with same protocol version")
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment