Startup scripts: Start the commander early and let it try to open the mavlink_fd with 20Hz

This commit is contained in:
Julian Oes 2013-11-05 19:56:33 +01:00
parent 857c3d2efd
commit 4502c285eb
4 changed files with 12 additions and 20 deletions

View File

@ -3,11 +3,6 @@
# Standard everything needed for fixedwing except mixer, actuator output and mavlink # Standard everything needed for fixedwing except mixer, actuator output and mavlink
# #
#
# Start the Commander
#
commander start
# #
# Start the sensors and test them. # Start the sensors and test them.
# #

View File

@ -3,11 +3,6 @@
# Standard everything needed for multirotors except mixer, actuator output and mavlink # Standard everything needed for multirotors except mixer, actuator output and mavlink
# #
#
# Start the Commander
#
commander start
# #
# Start the sensors and test them. # Start the sensors and test them.
# #

View File

@ -106,6 +106,11 @@ then
fi fi
fi fi
#
# Start the Commander (needs to be this early for in-air-restarts)
#
commander start
if param compare SYS_AUTOSTART 1000 if param compare SYS_AUTOSTART 1000
then then
sh /etc/init.d/1000_rc_fw_easystar.hil sh /etc/init.d/1000_rc_fw_easystar.hil

View File

@ -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 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 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_ON_OFF_LIMIT 0.75f
#define STICK_THRUST_RANGE 1.0f #define STICK_THRUST_RANGE 1.0f
#define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000 #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); 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 */ /* Main state machine */
/* make sure we are in preflight state */ /* make sure we are in preflight state */
memset(&status, 0, sizeof(status)); memset(&status, 0, sizeof(status));
@ -770,6 +762,11 @@ int commander_thread_main(int argc, char *argv[])
while (!thread_should_exit) { 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 */ /* update parameters */
orb_check(param_changed_sub, &updated); orb_check(param_changed_sub, &updated);