forked from Archive/PX4-Autopilot
Startup scripts: Start the commander early and let it try to open the mavlink_fd with 20Hz
This commit is contained in:
parent
857c3d2efd
commit
4502c285eb
|
@ -3,11 +3,6 @@
|
|||
# Standard everything needed for fixedwing except mixer, actuator output and mavlink
|
||||
#
|
||||
|
||||
#
|
||||
# Start the Commander
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start the sensors and test them.
|
||||
#
|
||||
|
|
|
@ -3,11 +3,6 @@
|
|||
# Standard everything needed for multirotors except mixer, actuator output and mavlink
|
||||
#
|
||||
|
||||
#
|
||||
# Start the Commander
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start the sensors and test them.
|
||||
#
|
||||
|
|
|
@ -106,6 +106,11 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the Commander (needs to be this early for in-air-restarts)
|
||||
#
|
||||
commander start
|
||||
|
||||
if param compare SYS_AUTOSTART 1000
|
||||
then
|
||||
sh /etc/init.d/1000_rc_fw_easystar.hil
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
Loading…
Reference in New Issue