aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_main.cpp
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-03-21 10:44:31 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-03-21 10:44:31 +0100
commit2988136e7eaa1f55c41376b74b58766af9f8fcb9 (patch)
treefc70f4da004976adb9323cc0a527a7172f32c32b /src/modules/mavlink/mavlink_main.cpp
parent055e45935534b409cd3ed68c837399461e448b3e (diff)
downloadpx4-firmware-2988136e7eaa1f55c41376b74b58766af9f8fcb9.tar.gz
px4-firmware-2988136e7eaa1f55c41376b74b58766af9f8fcb9.tar.bz2
px4-firmware-2988136e7eaa1f55c41376b74b58766af9f8fcb9.zip
Implemented last missing messages, added stream config for USB, made stream config fails for non-existing mavlink links non-fatal
Diffstat (limited to 'src/modules/mavlink/mavlink_main.cpp')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp21
1 files changed, 17 insertions, 4 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index c9f4835ba..00d906dcd 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -588,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");
}
}
@@ -1762,6 +1762,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;
default:
@@ -1951,8 +1952,17 @@ Mavlink::start(int argc, char *argv[])
// the only path to create a new instance,
// this is effectively a lock on concurrent
// instance starting. XXX do a real lock.
- while (ic == Mavlink::instance_count()) {
- ::usleep(500);
+
+ // 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;
@@ -2008,7 +2018,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 {