mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
mavlink: enable 6 instead of 4 instance
This commit is contained in:
parent
a16939f47e
commit
2a0ddf9f44
@ -55,6 +55,12 @@
|
||||
#define MAVLINK_GET_CHANNEL_BUFFER mavlink_get_channel_buffer
|
||||
#define MAVLINK_GET_CHANNEL_STATUS mavlink_get_channel_status
|
||||
|
||||
#if defined(__PX4_POSIX)
|
||||
#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)
|
||||
#endif
|
||||
|
||||
#include <v2.0/mavlink_types.h>
|
||||
#include <unistd.h>
|
||||
|
||||
|
||||
@ -151,7 +151,7 @@ void MavlinkCommandSender::check_timeout(mavlink_channel_t channel)
|
||||
// as some channels might be lagging behind and will end up putting the same command into the buffer.
|
||||
bool dropped_command = false;
|
||||
|
||||
for (unsigned i = 0; i < MAX_MAVLINK_CHANNEL; ++i) {
|
||||
for (unsigned i = 0; i < MAVLINK_COMM_NUM_BUFFERS; ++i) {
|
||||
if (item->num_sent_per_channel[i] == -2) {
|
||||
_commands.drop_current();
|
||||
dropped_command = true;
|
||||
@ -176,7 +176,7 @@ void MavlinkCommandSender::check_timeout(mavlink_channel_t channel)
|
||||
int8_t max_sent = 0;
|
||||
int8_t min_sent = INT8_MAX;
|
||||
|
||||
for (unsigned i = 0; i < MAX_MAVLINK_CHANNEL; ++i) {
|
||||
for (unsigned i = 0; i < MAVLINK_COMM_NUM_BUFFERS; ++i) {
|
||||
if (item->num_sent_per_channel[i] > max_sent) {
|
||||
max_sent = item->num_sent_per_channel[i];
|
||||
}
|
||||
|
||||
@ -102,14 +102,19 @@ private:
|
||||
static MavlinkCommandSender *_instance;
|
||||
static px4_sem_t _lock;
|
||||
|
||||
// There are MAVLINK_COMM_0 to MAVLINK_COMM_3, so it should be 4.
|
||||
static const unsigned MAX_MAVLINK_CHANNEL = 4;
|
||||
|
||||
struct command_item_s {
|
||||
mavlink_command_long_t command = {};
|
||||
hrt_abstime timestamp_us = 0;
|
||||
hrt_abstime last_time_sent_us = 0;
|
||||
int8_t num_sent_per_channel[MAX_MAVLINK_CHANNEL] = {-1, -1, -1, -1}; // -1: channel did not request this command to be sent, -2: channel got an ack for this command
|
||||
// -1: channel did not request this command to be sent, -2: channel got an ack for this command
|
||||
#if MAVLINK_COMM_NUM_BUFFERS == 4
|
||||
int8_t num_sent_per_channel[MAVLINK_COMM_NUM_BUFFERS] = {-1, -1, -1, -1};
|
||||
#elif MAVLINK_COMM_NUM_BUFFERS == 6
|
||||
int8_t num_sent_per_channel[MAVLINK_COMM_NUM_BUFFERS] = {-1, -1, -1, -1, -1, -1};
|
||||
#else
|
||||
#error Unknown number of MAVLINK_COMM_NUM_BUFFERS
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
TimestampedList<command_item_s> _commands{3};
|
||||
|
||||
@ -41,7 +41,7 @@
|
||||
#include <time.h>
|
||||
#include <stdio.h>
|
||||
#include <cstdbool>
|
||||
#include <v2.0/mavlink_types.h>
|
||||
#include "mavlink_bridge_header.h"
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
class Mavlink;
|
||||
|
||||
@ -278,7 +278,7 @@ Mavlink::set_channel()
|
||||
#endif
|
||||
|
||||
default:
|
||||
PX4_WARN("instance ID is out of range");
|
||||
PX4_WARN("instance ID %d is out of range", _instance_id);
|
||||
px4_task_exit(1);
|
||||
break;
|
||||
}
|
||||
|
||||
@ -540,7 +540,7 @@ private:
|
||||
|
||||
bool _task_running{true};
|
||||
static bool _boot_complete;
|
||||
static constexpr int MAVLINK_MAX_INSTANCES{4};
|
||||
static constexpr int MAVLINK_MAX_INSTANCES{6};
|
||||
static constexpr int MAVLINK_MIN_INTERVAL{1500};
|
||||
static constexpr int MAVLINK_MAX_INTERVAL{10000};
|
||||
static constexpr float MAVLINK_MIN_MULTIPLIER{0.0005f};
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user