mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 14:47:44 +08:00
mavlink: limit mavlink channels based on memory
This commit is contained in:
@@ -55,7 +55,7 @@
|
||||
#define MAVLINK_GET_CHANNEL_BUFFER mavlink_get_channel_buffer
|
||||
#define MAVLINK_GET_CHANNEL_STATUS mavlink_get_channel_status
|
||||
|
||||
#if defined(__PX4_POSIX)
|
||||
#if !defined(CONSTRAINED_MEMORY)
|
||||
#define MAVLINK_COMM_NUM_BUFFERS 6
|
||||
#define MAVLINK_COMM_4 static_cast<mavlink_channel_t>(4)
|
||||
#define MAVLINK_COMM_5 static_cast<mavlink_channel_t>(5)
|
||||
|
||||
@@ -543,7 +543,7 @@ private:
|
||||
|
||||
bool _task_running{true};
|
||||
static bool _boot_complete;
|
||||
static constexpr int MAVLINK_MAX_INSTANCES{6};
|
||||
static constexpr int MAVLINK_MAX_INSTANCES{MAVLINK_COMM_NUM_BUFFERS};
|
||||
static constexpr int MAVLINK_MIN_INTERVAL{1500};
|
||||
static constexpr int MAVLINK_MAX_INTERVAL{10000};
|
||||
static constexpr float MAVLINK_MIN_MULTIPLIER{0.0005f};
|
||||
|
||||
Reference in New Issue
Block a user