mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 16:33:58 -04:00
MAVLink: use a smaller maximum payload to reduce memory
this limits the sizes of the MAVLink buffers. It doesn't make a big difference now, but it will matter when we update to the latest mavlink code which has some very large packets
This commit is contained in:
parent
5e77119377
commit
15abc784ec
@ -14,8 +14,10 @@
|
|||||||
|
|
||||||
#include "include/mavlink/v1.0/ardupilotmega/version.h"
|
#include "include/mavlink/v1.0/ardupilotmega/version.h"
|
||||||
|
|
||||||
// this allows us to make mavlink_message_t much smaller
|
// this allows us to make mavlink_message_t much smaller. It means we
|
||||||
#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE
|
// can't support the largest messages in common.xml, but we don't need
|
||||||
|
// those for APM
|
||||||
|
#define MAVLINK_MAX_PAYLOAD_LEN 96
|
||||||
|
|
||||||
#define MAVLINK_COMM_NUM_BUFFERS 2
|
#define MAVLINK_COMM_NUM_BUFFERS 2
|
||||||
#include "include/mavlink/v1.0/mavlink_types.h"
|
#include "include/mavlink/v1.0/mavlink_types.h"
|
||||||
|
Loading…
Reference in New Issue
Block a user