diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2013-11-06 16:18:46 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2013-11-06 16:18:46 +0100 |
commit | c29fa61143c4aad6a8607eeb8abd4679af2d9c42 (patch) | |
tree | 728e18103d2296c939aff37adea64cd83044ced7 /src/modules | |
parent | e62d08a8fb96d8ba5d551d482a8a647cd5f88a1b (diff) | |
parent | cd5bde21449d0f274c377acc6b23c9785da55126 (diff) | |
download | px4-firmware-c29fa61143c4aad6a8607eeb8abd4679af2d9c42.tar.gz px4-firmware-c29fa61143c4aad6a8607eeb8abd4679af2d9c42.tar.bz2 px4-firmware-c29fa61143c4aad6a8607eeb8abd4679af2d9c42.zip |
Merge remote-tracking branch 'upstream/master' into fw_autoland_att_tecs
Diffstat (limited to 'src/modules')
-rw-r--r-- | src/modules/commander/commander.cpp | 17 |
1 files changed, 7 insertions, 10 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index ed090271c..ace13bb78 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -116,6 +116,8 @@ extern struct system_load_s system_load; #define LOW_VOLTAGE_BATTERY_COUNTER_LIMIT (LOW_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC) #define CRITICAL_VOLTAGE_BATTERY_COUNTER_LIMIT (CRITICAL_VOLTAGE_BATTERY_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC) +#define MAVLINK_OPEN_INTERVAL 50000 + #define STICK_ON_OFF_LIMIT 0.75f #define STICK_THRUST_RANGE 1.0f #define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000 @@ -582,16 +584,6 @@ int commander_thread_main(int argc, char *argv[]) mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); - if (mavlink_fd < 0) { - /* try again later */ - usleep(20000); - mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); - - if (mavlink_fd < 0) { - warnx("ERROR: Failed to open MAVLink log stream again, start mavlink app first."); - } - } - /* Main state machine */ /* make sure we are in preflight state */ memset(&status, 0, sizeof(status)); @@ -770,6 +762,11 @@ int commander_thread_main(int argc, char *argv[]) while (!thread_should_exit) { + if (mavlink_fd < 0 && counter % (1000000 / MAVLINK_OPEN_INTERVAL) == 0) { + /* try to open the mavlink log device every once in a while */ + mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); + } + /* update parameters */ orb_check(param_changed_sub, &updated); |