diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index 9751c13f86..257f3bf85e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -147,7 +147,7 @@ param set-default MPC_Z_VEL_P 0.27 # gimbal configuration -param set-default MNT_MODE_IN 1 +param set-default MNT_MODE_IN 0 param set-default MNT_MODE_OUT 1 param set-default MNT_MAN_PITCH 2 param set-default MNT_RC_IN_MODE 1 diff --git a/src/modules/vmount/output_mavlink.cpp b/src/modules/vmount/output_mavlink.cpp index 73a303759f..7bdbcae4e0 100644 --- a/src/modules/vmount/output_mavlink.cpp +++ b/src/modules/vmount/output_mavlink.cpp @@ -168,7 +168,6 @@ void OutputMavlinkV2::update(const ControlData &control_data, bool new_setpoints void OutputMavlinkV2::_request_gimbal_device_information() { - printf("request gimbal device\n"); vehicle_command_s vehicle_cmd{}; vehicle_cmd.timestamp = hrt_absolute_time(); vehicle_cmd.command = vehicle_command_s::VEHICLE_CMD_REQUEST_MESSAGE; diff --git a/src/modules/vmount/vmount.cpp b/src/modules/vmount/vmount.cpp index b51ef6de93..ef92fd6b76 100644 --- a/src/modules/vmount/vmount.cpp +++ b/src/modules/vmount/vmount.cpp @@ -222,7 +222,9 @@ static int vmount_thread_main(int argc, char *argv[]) for (int i = 0; i < thread_data.input_objs_len; ++i) { const bool already_active = (thread_data.last_input_active == i); - const unsigned int poll_timeout = already_active ? 20 : 0; // poll only on active input to reduce latency + // poll only on active input to reduce latency, or on all if none is active + const unsigned int poll_timeout = + (already_active || thread_data.last_input_active == -1) ? 20 : 0; update_result = thread_data.input_objs[i]->update(poll_timeout, control_data, already_active); @@ -282,9 +284,6 @@ static int vmount_thread_main(int argc, char *argv[]) g_thread_data = nullptr; - delete thread_data.test_input; - thread_data.test_input = nullptr; - for (int i = 0; i < input_objs_len_max; ++i) { if (thread_data.input_objs[i]) { delete (thread_data.input_objs[i]); @@ -318,6 +317,8 @@ int vmount_main(int argc, char *argv[]) return 1; } + thread_should_exit.store(false); + int vmount_task = px4_task_spawn_cmd("vmount", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT,