mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager: Add a helper to report if a serial link should have it's MAVLink data forwarded
This commit is contained in:
parent
1fef30eef1
commit
2cdaf421d8
|
@ -551,6 +551,15 @@ bool AP_SerialManager::get_mavlink_channel(enum SerialProtocol protocol, uint8_t
|
|||
return false;
|
||||
}
|
||||
|
||||
// should_forward_mavlink_telemetry - returns true if this port should forward telemetry
|
||||
bool AP_SerialManager::should_forward_mavlink_telemetry(enum SerialProtocol protocol, uint8_t instance) const
|
||||
{
|
||||
const struct UARTState *_state = find_protocol_instance(protocol, instance);
|
||||
if (_state == nullptr) {
|
||||
return true;
|
||||
}
|
||||
return (_state->options & AP_HAL::UARTDriver::OPTION_MAVLINK_NO_FORWARD) != AP_HAL::UARTDriver::OPTION_MAVLINK_NO_FORWARD;
|
||||
}
|
||||
|
||||
// get_mavlink_protocol - provides the specific MAVLink protocol for a
|
||||
// given channel, or SerialProtocol_None if not found
|
||||
|
|
|
@ -167,6 +167,9 @@ public:
|
|||
// returns true if a channel is found, false if not
|
||||
bool get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const;
|
||||
|
||||
// should_forward_mavlink_telemetry - returns true if this port should forward telemetry
|
||||
bool should_forward_mavlink_telemetry(enum SerialProtocol protocol, uint8_t instance) const;
|
||||
|
||||
// get_mavlink_protocol - provides the specific MAVLink protocol for a
|
||||
// given channel, or SerialProtocol_None if not found
|
||||
SerialProtocol get_mavlink_protocol(mavlink_channel_t mav_chan) const;
|
||||
|
|
Loading…
Reference in New Issue