mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_HAL: add AP_MAVLINK_PACKETISE_ENABLE option
This commit is contained in:
parent
d6ab080060
commit
43615f22b7
@ -2,12 +2,11 @@
|
||||
support for sending UDP packets on MAVLink packet boundaries.
|
||||
*/
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
|
||||
#include "packetise.h"
|
||||
|
||||
#if AP_MAVLINK_PACKETISE_ENABLED
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
|
||||
/*
|
||||
return the number of bytes to send for a packetised connection
|
||||
*/
|
||||
@ -68,4 +67,4 @@ uint16_t mavlink_packetise(ByteBuffer &writebuf, uint16_t n)
|
||||
return n;
|
||||
}
|
||||
|
||||
#endif // HAL_GCS_ENABLED
|
||||
#endif // AP_MAVLINK_PACKETISE_ENABLED
|
||||
|
@ -1,4 +1,10 @@
|
||||
#pragma once
|
||||
#include "RingBuffer.h"
|
||||
#include <GCS_MAVLink/GCS_config.h>
|
||||
|
||||
#ifndef AP_MAVLINK_PACKETISE_ENABLED
|
||||
#define AP_MAVLINK_PACKETISE_ENABLED HAL_GCS_ENABLED
|
||||
#endif
|
||||
|
||||
/*
|
||||
return the number of bytes to send for a packetised connection
|
||||
|
Loading…
Reference in New Issue
Block a user