Commit e03fb849 authored by Don Gagne's avatar Don Gagne

Allow FirmwarePlugin to drop incoming messages

parent 3b00e145
...@@ -93,11 +93,12 @@ int FirmwarePlugin::manualControlReservedButtonCount(void) ...@@ -93,11 +93,12 @@ int FirmwarePlugin::manualControlReservedButtonCount(void)
return -1; return -1;
} }
void FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) bool FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{ {
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
Q_UNUSED(message); Q_UNUSED(message);
// Generic plugin does no message adjustment // Generic plugin does no message adjustment
return true;
} }
void FirmwarePlugin::adjustOutgoingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) void FirmwarePlugin::adjustOutgoingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
......
...@@ -120,7 +120,8 @@ public: ...@@ -120,7 +120,8 @@ public:
/// spec implementations such that the base code can remain mavlink generic. /// spec implementations such that the base code can remain mavlink generic.
/// @param vehicle Vehicle message came from /// @param vehicle Vehicle message came from
/// @param message[in,out] Mavlink message to adjust if needed. /// @param message[in,out] Mavlink message to adjust if needed.
virtual void adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message); /// @return false: skip message, true: process message
virtual bool adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
/// Called before any mavlink message is sent to the Vehicle so plugin can adjust any message characteristics. /// Called before any mavlink message is sent to the Vehicle so plugin can adjust any message characteristics.
/// 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
......
...@@ -377,7 +377,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes ...@@ -377,7 +377,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
} }
// Give the plugin a change to adjust the message contents // Give the plugin a change to adjust the message contents
_firmwarePlugin->adjustIncomingMavlinkMessage(this, &message); if (!_firmwarePlugin->adjustIncomingMavlinkMessage(this, &message)) {
return;
}
switch (message.msgid) { switch (message.msgid) {
case MAVLINK_MSG_ID_HOME_POSITION: case MAVLINK_MSG_ID_HOME_POSITION:
......
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