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 70f9c0d5f9..b98f0ece89 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -145,9 +145,10 @@ param set-default MPC_Z_VEL_P 0.27 # gimbal configuration param set-default MNT_MODE_IN 1 -param set-default MNT_MODE_OUT 2 +param set-default MNT_MODE_OUT 1 param set-default MNT_MAN_PITCH 1 - +param set-default MNT_RC_IN_MODE 1 +param set-default MNT_RATE_PITCH 30 # RC param set-default RC_CHAN_CNT 12 diff --git a/boards/atl/mantis-edu/src/board_config.h b/boards/atl/mantis-edu/src/board_config.h index 48ff51e1bc..adb7f54d66 100644 --- a/boards/atl/mantis-edu/src/board_config.h +++ b/boards/atl/mantis-edu/src/board_config.h @@ -61,6 +61,9 @@ #define FLASH_BASED_PARAMS #define RAM_BASED_MISSIONS +// Hacks for MAVLink RC button input +#define ATL_MANTIS_RC_INPUT_HACKS + /* * ADC channels * diff --git a/src/modules/vmount/output_mavlink.cpp b/src/modules/vmount/output_mavlink.cpp index 38732cab9f..5698c63481 100644 --- a/src/modules/vmount/output_mavlink.cpp +++ b/src/modules/vmount/output_mavlink.cpp @@ -66,6 +66,9 @@ int OutputMavlinkV1::update(const ControlData *control_data) //got new command _set_angle_setpoints(control_data); +#if !defined(ALT_MANTIS_GIMBAL_HACKS) + // Don't send this command to ATL Mantis as it just spams the vehicle_command queue and the + // Mantis ignores it anyway. vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_MOUNT_CONFIGURE; vehicle_command.timestamp = hrt_absolute_time(); @@ -89,6 +92,7 @@ int OutputMavlinkV1::update(const ControlData *control_data) vehicle_command.param4 = _stabilize[2] ? 1.0f : 0.0f; _vehicle_command_pub.publish(vehicle_command); +#endif } _handle_position_update(); diff --git a/src/systemcmds/tune_control/tune_control.cpp b/src/systemcmds/tune_control/tune_control.cpp index c3a2753d06..a3c0884067 100644 --- a/src/systemcmds/tune_control/tune_control.cpp +++ b/src/systemcmds/tune_control/tune_control.cpp @@ -184,6 +184,7 @@ extern "C" __EXPORT int tune_control_main(int argc, char *argv[]) PX4_DEBUG("Publishing standard tune %d", tune_control.tune_id); publish_tune_control(tune_control); + } else { PX4_WARN("Missing argument"); usage();