diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index f3761200a1..e305713377 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -97,6 +97,12 @@ then fi fi +# This is a FMUv2+ thing +if ver hwcmp PX4FMU_V1 +then + set MIXER_AUX none +fi + if [ $MIXER_AUX != none ] then # diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 69d9e158dc..ff1a8092be 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -110,11 +110,6 @@ else fi fi -# Check for flow sensor -if px4flow start & -then -fi - # # Start sensors # diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 74aef41601..efee9d3e5c 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -726,16 +726,22 @@ then # End of autostart fi +# There is no further script processing, so we can free some RAM +# XXX potentially unset all script variables. +unset TUNE_ERR + # Boot is complete, inform MAVLink app(s) that the system is now fully up and running mavlink boot_complete +if ver hwcmp PX4FMU_V2 +then + # Check for flow sensor - as it is a background task, launch it last + px4flow start & +fi + 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/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index 645a0e1b1e..d23a551e10 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 645a0e1b1eb09efeeaa14cc18d2474628a31ab53 +Subproject commit d23a551e108d92c7a49a66d162cb9d542bbe6be1 diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index 9ed1cbc53e..874615d3b2 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -261,7 +261,7 @@ CONFIG_STM32_USART=y # U[S]ART Configuration # # Hot fix for lost data -CONFIG_STM32_RXDMA_BUFFER_SIZE_OVERRIDE=256 +CONFIG_STM32_RXDMA_BUFFER_SIZE_OVERRIDE=64 # CONFIG_USART1_RS485 is not set # CONFIG_USART1_RXDMA is not set # CONFIG_USART2_RS485 is not set diff --git a/src/drivers/px4flow/module.mk b/src/drivers/px4flow/module.mk index ecd3e804a1..8d6964d103 100644 --- a/src/drivers/px4flow/module.mk +++ b/src/drivers/px4flow/module.mk @@ -41,4 +41,6 @@ SRCS = px4flow.cpp MAXOPTIMIZATION = -Os +MODULE_STACKSIZE = 1200 + EXTRACXXFLAGS = -Wno-attributes diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index a247c2596e..1259daceb1 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1116,25 +1116,42 @@ PX4IO::task_main() (void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_REVERSE, pwm_invert_mask); float trim_val; - param_t trim_parm; + param_t parm_handle; - trim_parm = param_find("TRIM_ROLL"); - if (trim_parm != PARAM_INVALID) { - param_get(trim_parm, &trim_val); + parm_handle = param_find("TRIM_ROLL"); + if (parm_handle != PARAM_INVALID) { + param_get(parm_handle, &trim_val); (void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_TRIM_ROLL, FLOAT_TO_REG(trim_val)); } - trim_parm = param_find("TRIM_PITCH"); - if (trim_parm != PARAM_INVALID) { - param_get(trim_parm, &trim_val); + parm_handle = param_find("TRIM_PITCH"); + if (parm_handle != PARAM_INVALID) { + param_get(parm_handle, &trim_val); (void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_TRIM_PITCH, FLOAT_TO_REG(trim_val)); } - trim_parm = param_find("TRIM_YAW"); - if (trim_parm != PARAM_INVALID) { - param_get(trim_parm, &trim_val); + parm_handle = param_find("TRIM_YAW"); + if (parm_handle != PARAM_INVALID) { + param_get(parm_handle, &trim_val); (void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_TRIM_YAW, FLOAT_TO_REG(trim_val)); } + + /* S.BUS output */ + int sbus_mode; + parm_handle = param_find("PWM_SBUS_MODE"); + if (parm_handle != PARAM_INVALID) { + param_get(parm_handle, &sbus_mode); + if (sbus_mode == 1) { + /* enable S.BUS 1 */ + (void)io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES, 0, PX4IO_P_SETUP_FEATURES_SBUS1_OUT); + } else if (sbus_mode == 2) { + /* enable S.BUS 2 */ + (void)io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES, 0, PX4IO_P_SETUP_FEATURES_SBUS2_OUT); + } else { + /* disable S.BUS */ + (void)io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES, (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | PX4IO_P_SETUP_FEATURES_SBUS2_OUT), 0); + } + } } } diff --git a/src/drivers/px4io/px4io_params.c b/src/drivers/px4io/px4io_params.c index 057bcaf150..51d39e97ba 100644 --- a/src/drivers/px4io/px4io_params.c +++ b/src/drivers/px4io/px4io_params.c @@ -129,3 +129,14 @@ PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0); * @group PWM Outputs */ PARAM_DEFINE_INT32(PWM_MAIN_REV8, 0); + +/** + * Enable S.BUS out + * + * Set to 1 to enable S.BUS version 1 output instead of RSSI. + * + * @min 0 + * @max 1 + * @group PWM Outputs + */ +PARAM_DEFINE_INT32(PWM_SBUS_MODE, 0); diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index e91d69051e..138a8c7e5c 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -203,7 +203,7 @@ int AttitudeEstimatorQ::start() { _control_task = px4_task_spawn_cmd("attitude_estimator_q", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, - 2500, + 2000, (px4_main_t)&AttitudeEstimatorQ::task_main_trampoline, nullptr); diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 478bb85b73..38939b2b83 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -281,7 +281,7 @@ int commander_main(int argc, char *argv[]) if (!strcmp(argv[1], "start")) { if (thread_running) { - warnx("commander already running"); + warnx("already running"); /* this is not an error */ return 0; } @@ -294,11 +294,18 @@ int commander_main(int argc, char *argv[]) commander_thread_main, (argv) ? (char * const *)&argv[2] : (char * const *)NULL); - while (!thread_running) { - usleep(200); + unsigned constexpr max_wait_us = 1000000; + unsigned constexpr max_wait_steps = 2000; + + unsigned i; + for (i = 0; i < max_wait_steps; i++) { + usleep(max_wait_us / max_wait_steps); + if (thread_running) { + break; + } } - return 0; + return !(i < max_wait_steps); } if (!strcmp(argv[1], "stop")) { diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 0e9c7b8eb3..298f44d767 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1960,6 +1960,12 @@ Mavlink::start(int argc, char *argv[]) // before returning to the shell int ic = Mavlink::instance_count(); + if (ic == MAVLINK_COMM_NUM_BUFFERS) { + warnx("Maximum MAVLink instance count of %d reached.", + (int)MAVLINK_COMM_NUM_BUFFERS); + return 1; + } + // Instantiate thread char buf[24]; sprintf(buf, "mavlink_if%d", ic); diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk index 7b2905f6b7..f197ebb7c9 100644 --- a/src/modules/mavlink/module.mk +++ b/src/modules/mavlink/module.mk @@ -54,6 +54,6 @@ MAXOPTIMIZATION = -Os MODULE_STACKSIZE = 1200 -EXTRACXXFLAGS = -Weffc++ -Wno-attributes -Wno-packed +EXTRACXXFLAGS = -Weffc++ -Wno-attributes -Wno-packed -DMAVLINK_COMM_NUM_BUFFERS=3 -EXTRACFLAGS = -Wno-packed +EXTRACFLAGS = -Wno-packed -DMAVLINK_COMM_NUM_BUFFERS=3 diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 10a07323c6..db7a5ee364 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -346,7 +346,20 @@ int sdlog2_main(int argc, char *argv[]) 3000, sdlog2_thread_main, (char * const *)argv); - return 0; + + /* wait for the task to launch */ + unsigned const max_wait_us = 1000000; + unsigned const max_wait_steps = 2000; + + unsigned i; + for (i = 0; i < max_wait_steps; i++) { + usleep(max_wait_us / max_wait_steps); + if (thread_running) { + break; + } + } + + return !(i < max_wait_steps); } if (!strcmp(argv[1], "stop")) { @@ -1236,8 +1249,6 @@ int sdlog2_thread_main(int argc, char *argv[]) /* close stdout */ close(1); - thread_running = true; - /* initialize thread synchronization */ pthread_mutex_init(&logbuffer_mutex, NULL); pthread_cond_init(&logbuffer_cond, NULL); @@ -1271,6 +1282,9 @@ int sdlog2_thread_main(int argc, char *argv[]) sdlog2_start_log(); } + /* running, report */ + thread_running = true; + while (!main_thread_should_exit) { usleep(sleep_delay); diff --git a/src/modules/systemlib/cpuload.c b/src/modules/systemlib/cpuload.c index fe08da71fd..77743bdd8c 100644 --- a/src/modules/systemlib/cpuload.c +++ b/src/modules/systemlib/cpuload.c @@ -80,8 +80,6 @@ void cpuload_initialize_once() system_load.tasks[i].valid = false; } - uint64_t now = hrt_absolute_time(); - int static_tasks_count = 2; // there are at least 2 threads that should be initialized statically - "idle" and "init" #ifdef CONFIG_PAGING @@ -96,7 +94,6 @@ void cpuload_initialize_once() // perform static initialization of "system" threads for (system_load.total_count = 0; system_load.total_count < static_tasks_count; system_load.total_count++) { - system_load.tasks[system_load.total_count].start_time = now; system_load.tasks[system_load.total_count].total_runtime = 0; system_load.tasks[system_load.total_count].curr_start_time = 0; system_load.tasks[system_load.total_count].tcb = sched_gettcb( @@ -113,7 +110,6 @@ void sched_note_start(FAR struct tcb_s *tcb) for (i = 1; i < CONFIG_MAX_TASKS; i++) { if (!system_load.tasks[i].valid) { /* slot is available */ - system_load.tasks[i].start_time = hrt_absolute_time(); system_load.tasks[i].total_runtime = 0; system_load.tasks[i].curr_start_time = 0; system_load.tasks[i].tcb = tcb; diff --git a/src/modules/systemlib/cpuload.h b/src/modules/systemlib/cpuload.h index dc173baa79..e997bb3d9a 100644 --- a/src/modules/systemlib/cpuload.h +++ b/src/modules/systemlib/cpuload.h @@ -42,7 +42,6 @@ __BEGIN_DECLS struct system_load_taskinfo_s { uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load uint64_t curr_start_time; ///< Start time of the current scheduling slot - uint64_t start_time; ///< FIRST start time of task #ifdef __PX4_NUTTX FAR struct tcb_s *tcb; ///< #endif