Browse Source

MAVLink: Limit use to 3 instances, which is what is realistically being used.

sbg
Lorenz Meier 10 years ago
parent
commit
05d752ae34
  1. 6
      src/modules/mavlink/mavlink_main.cpp
  2. 4
      src/modules/mavlink/module.mk

6
src/modules/mavlink/mavlink_main.cpp

@ -1789,6 +1789,12 @@ Mavlink::start(int argc, char *argv[]) @@ -1789,6 +1789,12 @@ Mavlink::start(int argc, char *argv[])
// before returning to the shell
int ic = Mavlink::instance_count();
if (ic == MAVLINK_COMM_NUM_BUFFERS) {
warnx("Maximum MAVLink instance count of %d reached.",
(int)MAVLINK_COMM_NUM_BUFFERS);
return 1;
}
// Instantiate thread
char buf[24];
sprintf(buf, "mavlink_if%d", ic);

4
src/modules/mavlink/module.mk

@ -53,6 +53,6 @@ MAXOPTIMIZATION = -Os @@ -53,6 +53,6 @@ MAXOPTIMIZATION = -Os
MODULE_STACKSIZE = 1200
EXTRACXXFLAGS = -Weffc++ -Wno-attributes -Wno-packed
EXTRACXXFLAGS = -Weffc++ -Wno-attributes -Wno-packed -DMAVLINK_COMM_NUM_BUFFERS=3
EXTRACFLAGS = -Wno-packed
EXTRACFLAGS = -Wno-packed -DMAVLINK_COMM_NUM_BUFFERS=3

Loading…
Cancel
Save