diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 098c23a9d6..3673b92471 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -717,19 +717,19 @@ then tone_alarm error fi - # Boot is complete, inform MAVLink app(s) that the system is now fully up and running - mavlink boot_complete - - if [ $EXIT_ON_END == yes ] - then - echo "Exit from nsh" - exit - fi - unset EXIT_ON_END - # End of autostart fi +# Boot is complete, inform MAVLink app(s) that the system is now fully up and running +mavlink boot_complete + +if [ $EXIT_ON_END == yes ] +then + echo "Exit from nsh" + exit +fi +unset EXIT_ON_END + # There is no further processing, so we can free some RAM # XXX potentially unset all script variables. unset TUNE_ERR diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index bb310dbff5..4b436072ba 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -80,10 +80,6 @@ # to the directory 'build' under the directory containing the # parent Makefile. # -# ROMFS_ROOT: -# If set to the path to a directory, a ROMFS image will be generated -# containing the files under the directory and linked into the final -# image. # # MODULE_SEARCH_DIRS: # Extra directories to search first for MODULES before looking in the diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 88191c5975..478bb85b73 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1355,10 +1355,15 @@ int commander_thread_main(int argc, char *argv[]) orb_copy(telemetry_status_orb_id[i], telemetry_subs[i], &telemetry); /* perform system checks when new telemetry link connected */ - if (mavlink_fd && - telemetry_last_heartbeat[i] == 0 && + if ( + /* we actually have a way to talk to the user */ + mavlink_fd && + /* we first connect a link or re-connect a link after loosing it */ + (telemetry_last_heartbeat[i] == 0 || (hrt_elapsed_time(&telemetry_last_heartbeat[i]) > 3 * 1000 * 1000)) && + /* and this link has a communication partner */ telemetry.heartbeat_time > 0 && - hrt_elapsed_time(&telemetry.heartbeat_time) < datalink_loss_timeout * 1e6) { + /* and the system is not already armed (and potentially flying) */ + !armed.armed) { bool chAirspeed = false; /* Perform airspeed check only if circuit breaker is not @@ -1830,7 +1835,7 @@ int commander_thread_main(int argc, char *argv[]) } else { if (status.rc_signal_lost) { - mavlink_log_critical(mavlink_fd, "RC SIGNAL REGAINED after %llums", + mavlink_log_info(mavlink_fd, "RC SIGNAL REGAINED after %llums", (hrt_absolute_time() - status.rc_signal_lost_timestamp) / 1000); status_changed = true; } @@ -1957,7 +1962,7 @@ int commander_thread_main(int argc, char *argv[]) /* only report a regain */ if (telemetry_last_dl_loss[i] > 0) { - mavlink_and_console_log_critical(mavlink_fd, "data link #%i regained", i); + mavlink_and_console_log_info(mavlink_fd, "data link #%i regained", i); } telemetry_lost[i] = false; @@ -1975,7 +1980,7 @@ int commander_thread_main(int argc, char *argv[]) /* only reset the timestamp to a different time on state change */ telemetry_last_dl_loss[i] = hrt_absolute_time(); - mavlink_and_console_log_critical(mavlink_fd, "data link #%i lost", i); + mavlink_and_console_log_info(mavlink_fd, "data link #%i lost", i); telemetry_lost[i] = true; } } @@ -1990,7 +1995,9 @@ int commander_thread_main(int argc, char *argv[]) } else { if (!status.data_link_lost) { - mavlink_and_console_log_critical(mavlink_fd, "ALL DATA LINKS LOST"); + if (armed.armed) { + mavlink_and_console_log_critical(mavlink_fd, "ALL DATA LINKS LOST"); + } status.data_link_lost = true; status.data_link_lost_counter++; status_changed = true; @@ -2986,6 +2993,21 @@ void *commander_low_prio_loop(void *arg) mavlink_log_critical(mavlink_fd, "ERROR: %s", strerror(ret)); } + answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_FAILED); + } + } else if (((int)(cmd.param1)) == 2) { + + /* reset parameters and save empty file */ + param_reset_all(); + int ret = param_save_default(); + + if (ret == OK) { + /* do not spam MAVLink, but provide the answer / green led mechanism */ + mavlink_log_critical(mavlink_fd, "onboard parameters reset"); + answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED); + + } else { + mavlink_log_critical(mavlink_fd, "param reset error"); answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_FAILED); } } diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 8901dd0672..dd8951dae8 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1389,6 +1389,9 @@ Mavlink::update_rate_mult() /* limit to a max multiplier of 1 */ hardware_mult = fminf(1.0f, hardware_mult); } + } else { + /* no limitation, set hardware to 1 */ + hardware_mult = 1.0f; } _last_hw_rate_timestamp = tstatus.timestamp; diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c index 5690815322..11176728e7 100644 --- a/src/systemcmds/nshterm/nshterm.c +++ b/src/systemcmds/nshterm/nshterm.c @@ -68,8 +68,8 @@ nshterm_main(int argc, char *argv[]) int armed_fd = orb_subscribe(ORB_ID(actuator_armed)); struct actuator_armed_s armed; - /* back off 800 ms to avoid running into the USB setup timing */ - while (hrt_absolute_time() < 800U * 1000U) { + /* back off 1500 ms to avoid running into the USB setup timing */ + while (hrt_absolute_time() < 1500U * 1000U) { usleep(50000); }