Merge remote-tracking branch 'px4/beta_mavlink2' into beta_mavlink2_camera

Conflicts:
	src/modules/mavlink/mavlink_messages.cpp
This commit is contained in:
Julian Oes
2014-03-21 11:19:26 +01:00
32 changed files with 550 additions and 317 deletions

View File

@@ -254,7 +254,6 @@ Mavlink::Mavlink() :
break;
}
LL_APPEND(_mavlink_instances, this);
}
Mavlink::~Mavlink()
@@ -589,7 +588,7 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios *
/* setup output flow control */
if (enable_flow_control(true)) {
warnx("ERR FLOW CTRL EN");
warnx("hardware flow control not supported");
}
}
@@ -1769,6 +1768,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("GLOBAL_POSITION_INT", 3.0f * rate_mult);
configure_stream("LOCAL_POSITION_NED", 3.0f * rate_mult);
configure_stream("RC_CHANNELS_RAW", 1.0f * rate_mult);
configure_stream("NAMED_VALUE_FLOAT", 1.0f * rate_mult);
break;
case MAVLINK_MODE_CAMERA:
@@ -1791,6 +1791,9 @@ Mavlink::task_main(int argc, char *argv[])
/* set main loop delay depending on data rate to minimize CPU overhead */
_main_loop_delay = MAIN_LOOP_DELAY / rate_mult;
/* now the instance is fully initialized and we can bump the instance count */
LL_APPEND(_mavlink_instances, this);
while (!_task_should_exit) {
/* main loop */
usleep(_main_loop_delay);
@@ -1937,10 +1940,18 @@ int Mavlink::start_helper(int argc, char *argv[])
int
Mavlink::start(int argc, char *argv[])
{
// Wait for the instance count to go up one
// before returning to the shell
int ic = Mavlink::instance_count();
// Instantiate thread
char buf[24];
sprintf(buf, "mavlink_if%d", Mavlink::instance_count());
sprintf(buf, "mavlink_if%d", ic);
// This is where the control flow splits
// between the starting task and the spawned
// task - start_helper() only returns
// when the started task exits.
task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
@@ -1948,6 +1959,25 @@ Mavlink::start(int argc, char *argv[])
(main_t)&Mavlink::start_helper,
(const char **)argv);
// Ensure that this shell command
// does not return before the instance
// is fully initialized. As this is also
// the only path to create a new instance,
// this is effectively a lock on concurrent
// instance starting. XXX do a real lock.
// Sleep 500 us between each attempt
const unsigned sleeptime = 500;
// Wait 100 ms max for the startup.
const unsigned limit = 100 * 1000 / sleeptime;
unsigned count = 0;
while (ic == Mavlink::instance_count() && count < limit) {
::usleep(sleeptime);
count++;
}
return OK;
}
@@ -2001,7 +2031,10 @@ Mavlink::stream(int argc, char *argv[])
inst->configure_stream_threadsafe(stream_name, rate);
} else {
errx(1, "mavlink for device %s is not running", device_name);
// If the link is not running we should complain, but not fall over
// because this is so easy to get wrong and not fatal. Warning is sufficient.
errx(0, "mavlink for device %s is not running", device_name);
}
} else {