Browse Source

MAVLink app: Allocate buffers only as they are needed

sbg
Lorenz Meier 9 years ago
parent
commit
1b2043b929
  1. 1
      src/modules/mavlink/CMakeLists.txt
  2. 22
      src/modules/mavlink/mavlink_main.cpp
  3. 13
      src/modules/mavlink/mavlink_main.h

1
src/modules/mavlink/CMakeLists.txt

@ -36,7 +36,6 @@ px4_add_module( @@ -36,7 +36,6 @@ px4_add_module(
STACK_MAIN 1200
STACK_MAX 1500
COMPILE_FLAGS
-DMAVLINK_COMM_NUM_BUFFERS=4
-Os
SRCS
mavlink.c

22
src/modules/mavlink/mavlink_main.cpp

@ -136,7 +136,12 @@ void mavlink_end_uart_send(mavlink_channel_t chan, int length) @@ -136,7 +136,12 @@ void mavlink_end_uart_send(mavlink_channel_t chan, int length)
*/
mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
{
return Mavlink::get_status_for_instance(channel);
Mavlink* m = Mavlink::get_instance((unsigned)channel);
if (m != nullptr) {
return m->get_status();
} else {
return nullptr;
}
}
/*
@ -144,15 +149,18 @@ mavlink_status_t *mavlink_get_channel_status(uint8_t channel) @@ -144,15 +149,18 @@ mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
*/
mavlink_message_t *mavlink_get_channel_buffer(uint8_t channel)
{
return Mavlink::get_buffer_for_instance(channel);
Mavlink* m = Mavlink::get_instance((unsigned)channel);
if (m != nullptr) {
return m->get_buffer();
} else {
return nullptr;
}
}
static void usage(void);
bool Mavlink::_boot_complete = false;
bool Mavlink::_config_link_on = false;
mavlink_message_t Mavlink::_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS] = {};
mavlink_status_t Mavlink::_mavlink_status[MAVLINK_COMM_NUM_BUFFERS] = {};
Mavlink::Mavlink() :
_device_name("/dev/ttyS1"),
@ -161,6 +169,8 @@ Mavlink::Mavlink() : @@ -161,6 +169,8 @@ Mavlink::Mavlink() :
_instance_id(0),
_mavlink_log_pub(nullptr),
_task_running(false),
_mavlink_buffer{},
_mavlink_status{},
_hil_enabled(false),
_generate_rc(false),
_use_hil_gps(false),
@ -2268,9 +2278,9 @@ Mavlink::start(int argc, char *argv[]) @@ -2268,9 +2278,9 @@ Mavlink::start(int argc, char *argv[])
// before returning to the shell
int ic = Mavlink::instance_count();
if (ic == MAVLINK_COMM_NUM_BUFFERS) {
if (ic == Mavlink::MAVLINK_MAX_INSTANCES) {
warnx("Maximum MAVLink instance count of %d reached.",
(int)MAVLINK_COMM_NUM_BUFFERS);
(int)Mavlink::MAVLINK_MAX_INSTANCES);
return 1;
}

13
src/modules/mavlink/mavlink_main.h

@ -114,13 +114,9 @@ public: @@ -114,13 +114,9 @@ public:
static Mavlink *get_instance_for_network_port(unsigned long port);
static mavlink_message_t *get_buffer_for_instance(unsigned instance) { return &_mavlink_buffer[instance]; }
mavlink_message_t *get_buffer() { return &_mavlink_buffer; }
mavlink_message_t *get_buffer() { return Mavlink::get_buffer_for_instance(_instance_id); }
static mavlink_status_t *get_status_for_instance(unsigned instance) { return &_mavlink_status[instance]; }
mavlink_status_t *get_status() { return Mavlink::get_status_for_instance(_instance_id); }
mavlink_status_t *get_status() { return &_mavlink_status; }
/**
* Set the MAVLink version
@ -404,8 +400,9 @@ private: @@ -404,8 +400,9 @@ private:
orb_advert_t _mavlink_log_pub;
bool _task_running;
static bool _boot_complete;
static mavlink_message_t _mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
static mavlink_status_t _mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
static const unsigned MAVLINK_MAX_INSTANCES = 4;
mavlink_message_t _mavlink_buffer;
mavlink_status_t _mavlink_status;
/* states */
bool _hil_enabled; /**< Hardware In the Loop mode */

Loading…
Cancel
Save