diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 156711c26d..b718f421f5 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -17,9 +17,9 @@ then param set FW_T_TIME_CONST 5 param set PE_VELNE_NOISE 0.3 - param set PE_VELD_NOISE 0.5 + param set PE_VELD_NOISE 0.35 param set PE_POSNE_NOISE 0.5 - param set PE_POSD_NOISE 0.5 + param set PE_POSD_NOISE 1.0 param set PE_GBIAS_PNOISE 0.000001 param set PE_ABIAS_PNOISE 0.0002 fi diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index fa3653e0d5..a5c326ebc6 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -5,9 +5,9 @@ set VEHICLE_TYPE mc if [ $AUTOCNF == yes ] then param set PE_VELNE_NOISE 0.5 - param set PE_VELD_NOISE 0.7 + param set PE_VELD_NOISE 0.35 param set PE_POSNE_NOISE 0.5 - param set PE_POSD_NOISE 1.0 + param set PE_POSD_NOISE 1.25 param set PE_GBIAS_PNOISE 0.000001 param set PE_ABIAS_PNOISE 0.0001 diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index 844d540bf0..c2340a7b16 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -34,9 +34,9 @@ then param set FW_RR_P 0.02 param set PE_VELNE_NOISE 0.5 - param set PE_VELD_NOISE 0.7 + param set PE_VELD_NOISE 0.3 param set PE_POSNE_NOISE 0.5 - param set PE_POSD_NOISE 1.0 + param set PE_POSD_NOISE 1.25 param set PE_GBIAS_PNOISE 0.000001 param set PE_ABIAS_PNOISE 0.0001 fi diff --git a/makefiles/upload.mk b/makefiles/upload.mk index dd7710bf72..2da09bd980 100644 --- a/makefiles/upload.mk +++ b/makefiles/upload.mk @@ -15,7 +15,7 @@ ifeq ($(SYSTYPE),Darwin) SERIAL_PORTS ?= "/dev/tty.usbmodemPX*,/dev/tty.usbmodem*" endif ifeq ($(SYSTYPE),Linux) -SERIAL_PORTS ?= "/dev/serial/by-id/usb-3D_Robotics*" +SERIAL_PORTS ?= "/dev/serial/by-id/usb-3D_Robotics*,/dev/serial/by-id/pci-3D_Robotics*" endif ifeq ($(SERIAL_PORTS),) SERIAL_PORTS = "COM32,COM31,COM30,COM29,COM28,COM27,COM26,COM25,COM24,COM23,COM22,COM21,COM20,COM19,COM18,COM17,COM16,COM15,COM14,COM13,COM12,COM11,COM10,COM9,COM8,COM7,COM6,COM5,COM4,COM3,COM2,COM1,COM0" diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index 82c18b5c14..a05d285f7b 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -179,6 +179,8 @@ static const int ERROR = -1; #define L3GD20_DEFAULT_FILTER_FREQ 30 #define L3GD20_TEMP_OFFSET_CELSIUS 40 +#define L3GD20_MAX_OFFSET 0.45f /**< max offset: 25 degrees/s */ + #ifdef PX4_SPI_BUS_EXT #define EXTERNAL_BUS PX4_SPI_BUS_EXT #else @@ -1102,18 +1104,18 @@ L3GD20::test_error() int L3GD20::self_test() { - /* evaluate gyro offsets, complain if offset -> zero or larger than 6 dps */ - if (fabsf(_gyro_scale.x_offset) > 0.1f || fabsf(_gyro_scale.x_offset) < 0.000001f) + /* evaluate gyro offsets, complain if offset -> zero or larger than 25 dps */ + if (fabsf(_gyro_scale.x_offset) > L3GD20_MAX_OFFSET || fabsf(_gyro_scale.x_offset) < 0.000001f) return 1; if (fabsf(_gyro_scale.x_scale - 1.0f) > 0.3f) return 1; - if (fabsf(_gyro_scale.y_offset) > 0.1f || fabsf(_gyro_scale.y_offset) < 0.000001f) + if (fabsf(_gyro_scale.y_offset) > L3GD20_MAX_OFFSET || fabsf(_gyro_scale.y_offset) < 0.000001f) return 1; if (fabsf(_gyro_scale.y_scale - 1.0f) > 0.3f) return 1; - if (fabsf(_gyro_scale.z_offset) > 0.1f || fabsf(_gyro_scale.z_offset) < 0.000001f) + if (fabsf(_gyro_scale.z_offset) > L3GD20_MAX_OFFSET || fabsf(_gyro_scale.z_offset) < 0.000001f) return 1; if (fabsf(_gyro_scale.z_scale - 1.0f) > 0.3f) return 1; diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index bc8f833aef..6e8e22b5cd 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -150,11 +150,12 @@ PARAM_DEFINE_FLOAT(COM_EF_THROT, 0.5f); /** * Engine Failure Current/Throttle Threshold * - * Engine failure triggers only below this current/throttle value + * Engine failure triggers only below this current value * * @group Commander * @min 0.0 - * @max 7.0 + * @max 30.0 + * @unit ampere */ PARAM_DEFINE_FLOAT(COM_EF_C2T, 5.0f); @@ -167,7 +168,7 @@ PARAM_DEFINE_FLOAT(COM_EF_C2T, 5.0f); * @group Commander * @unit second * @min 0.0 - * @max 7.0 + * @max 60.0 */ PARAM_DEFINE_FLOAT(COM_EF_TIME, 10.0f); diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c index f8cca6c0dd..357cc4c667 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c @@ -141,13 +141,13 @@ PARAM_DEFINE_FLOAT(PE_VELNE_NOISE, 0.3f); /** * Velocity noise in down (vertical) direction * - * Generic default: 0.5, multicopters: 0.7, ground vehicles: 0.7 + * Generic default: 0.3, multicopters: 0.4, ground vehicles: 0.7 * - * @min 0.05 - * @max 5.0 + * @min 0.2 + * @max 3.0 * @group Position Estimator */ -PARAM_DEFINE_FLOAT(PE_VELD_NOISE, 0.5f); +PARAM_DEFINE_FLOAT(PE_VELD_NOISE, 0.3f); /** * Position noise in north-east (horizontal) direction @@ -163,21 +163,21 @@ PARAM_DEFINE_FLOAT(PE_POSNE_NOISE, 0.5f); /** * Position noise in down (vertical) direction * - * Generic defaults: 0.5, multicopters: 1.0, ground vehicles: 1.0 + * Generic defaults: 1.25, multicopters: 1.0, ground vehicles: 1.0 * - * @min 0.1 - * @max 10.0 + * @min 0.5 + * @max 3.0 * @group Position Estimator */ -PARAM_DEFINE_FLOAT(PE_POSD_NOISE, 0.5f); +PARAM_DEFINE_FLOAT(PE_POSD_NOISE, 1.25f); /** * Magnetometer measurement noise * * Generic defaults: 0.05, multicopters: 0.05, ground vehicles: 0.05 * - * @min 0.1 - * @max 10.0 + * @min 0.01 + * @max 1.0 * @group Position Estimator */ PARAM_DEFINE_FLOAT(PE_MAG_NOISE, 0.05f); diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c index 30c2d2b956..460e84c235 100644 --- a/src/modules/mavlink/mavlink.c +++ b/src/modules/mavlink/mavlink.c @@ -59,15 +59,18 @@ PARAM_DEFINE_INT32(MAV_SYS_ID, 1); * MAVLink component ID * @group MAVLink * @min 1 - * @max 50 + * @max 250 */ PARAM_DEFINE_INT32(MAV_COMP_ID, 50); /** - * MAVLink type + * MAVLink airframe type + * + * + * @min 0 * @group MAVLink */ -PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING); +PARAM_DEFINE_INT32(MAV_TYPE, 1); /** * Use/Accept HIL GPS message (even if not in HIL mode) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index a333fb8529..0b6dfcab5f 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1767,6 +1767,10 @@ protected: msg.x = pos_sp.x; msg.y = pos_sp.y; msg.z = pos_sp.z; + msg.yaw = pos_sp.yaw; + msg.vx = pos_sp.vx; + msg.vy = pos_sp.vy; + msg.vz = pos_sp.vz; _mavlink->send_message(MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, &msg); } diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index ccae79c11d..ad1ba56652 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -1380,44 +1380,44 @@ MulticopterPositionControl::task_main() reset_int_xy = true; } - // generate attitude setpoint from manual controls + /* generate attitude setpoint from manual controls */ if(_control_mode.flag_control_manual_enabled && _control_mode.flag_control_attitude_enabled) { - // reset yaw setpoint to current position if needed + /* reset yaw setpoint to current position if needed */ if (reset_yaw_sp) { reset_yaw_sp = false; _att_sp.yaw_body = _att.yaw; } - // do not move yaw while arming + /* do not move yaw while arming */ else if (_manual.z > 0.1f) { - const float YAW_OFFSET_MAX = _params.man_yaw_max / _params.mc_att_yaw_p; + const float yaw_offset_max = _params.man_yaw_max / _params.mc_att_yaw_p; _att_sp.yaw_sp_move_rate = _manual.r * _params.man_yaw_max; - _att_sp.yaw_body = _wrap_pi(_att_sp.yaw_body + _att_sp.yaw_sp_move_rate * dt); - float yaw_offs = _wrap_pi(_att_sp.yaw_body - _att.yaw); - if (yaw_offs < - YAW_OFFSET_MAX) { - _att_sp.yaw_body = _wrap_pi(_att.yaw - YAW_OFFSET_MAX); + float yaw_target = _wrap_pi(_att_sp.yaw_body + _att_sp.yaw_sp_move_rate * dt); + float yaw_offs = _wrap_pi(yaw_target - _att.yaw); - } else if (yaw_offs > YAW_OFFSET_MAX) { - _att_sp.yaw_body = _wrap_pi(_att.yaw + YAW_OFFSET_MAX); + // If the yaw offset became too big for the system to track stop + // shifting it + if (fabsf(yaw_offs) < yaw_offset_max) { + _att_sp.yaw_body = yaw_target; } } - //Control roll and pitch directly if we no aiding velocity controller is active + /* control roll and pitch directly if we no aiding velocity controller is active */ if (!_control_mode.flag_control_velocity_enabled) { _att_sp.roll_body = _manual.y * _params.man_roll_max; _att_sp.pitch_body = -_manual.x * _params.man_pitch_max; } - //Control climb rate directly if no aiding altitude controller is active + /* control throttle directly if no climb rate controller is active */ if (!_control_mode.flag_control_climb_rate_enabled) { _att_sp.thrust = math::min(_manual.z, _params.thr_max); _att_sp.thrust = math::max(_att_sp.thrust, _params.thr_min); } - //Construct attitude setpoint rotation matrix + /* construct attitude setpoint rotation matrix */ math::Matrix<3,3> R_sp; R_sp.from_euler(_att_sp.roll_body,_att_sp.pitch_body,_att_sp.yaw_body); memcpy(&_att_sp.R_body[0], R_sp.data, sizeof(_att_sp.R_body)); diff --git a/src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp b/src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp index e0e086999d..37775711e0 100644 --- a/src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp +++ b/src/modules/mc_pos_control_multiplatform/mc_pos_control.cpp @@ -647,6 +647,21 @@ void MulticopterPositionControl::handle_vehicle_attitude(const px4_vehicle_atti _vel_sp = pos_err.emult(_params.pos_p) + _vel_ff; + /* make sure velocity setpoint is saturated in xy*/ + float vel_norm_xy = sqrtf(_vel_sp(0)*_vel_sp(0) + + _vel_sp(1)*_vel_sp(1)); + if (vel_norm_xy > _params.vel_max(0)) { + /* note assumes vel_max(0) == vel_max(1) */ + _vel_sp(0) = _vel_sp(0)*_params.vel_max(0)/vel_norm_xy; + _vel_sp(1) = _vel_sp(1)*_params.vel_max(1)/vel_norm_xy; + } + + /* make sure velocity setpoint is saturated in z*/ + float vel_norm_z = sqrtf(_vel_sp(2)*_vel_sp(2)); + if (vel_norm_z > _params.vel_max(2)) { + _vel_sp(2) = _vel_sp(2)*_params.vel_max(2)/vel_norm_z; + } + if (!_control_mode->data().flag_control_altitude_enabled) { _reset_alt_sp = true; _vel_sp(2) = 0.0f; diff --git a/src/modules/navigator/datalinkloss_params.c b/src/modules/navigator/datalinkloss_params.c index 9abc012cf2..6c2f04d7e2 100644 --- a/src/modules/navigator/datalinkloss_params.c +++ b/src/modules/navigator/datalinkloss_params.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2014 PX4 Development Team. All rights reserved. + * Copyright (c) 2014, 2015 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -64,7 +64,8 @@ PARAM_DEFINE_FLOAT(NAV_DLL_CH_T, 120.0f); * Latitude of comms hold waypoint * * @unit degrees * 1e7 - * @min 0 + * @min -90 + * @max 90 * @group Data Link Loss */ PARAM_DEFINE_INT32(NAV_DLL_CH_LAT, -266072120); @@ -75,7 +76,8 @@ PARAM_DEFINE_INT32(NAV_DLL_CH_LAT, -266072120); * Longitude of comms hold waypoint * * @unit degrees * 1e7 - * @min 0 + * @min -180 + * @max 180 * @group Data Link Loss */ PARAM_DEFINE_INT32(NAV_DLL_CH_LON, 1518453890); @@ -86,13 +88,14 @@ PARAM_DEFINE_INT32(NAV_DLL_CH_LON, 1518453890); * Altitude of comms hold waypoint * * @unit m - * @min 0.0 + * @min -50 + * @max 30000 * @group Data Link Loss */ PARAM_DEFINE_FLOAT(NAV_DLL_CH_ALT, 600.0f); /** - * Aifield hole wait time + * Airfield hole wait time * * The amount of time in seconds the system should wait at the airfield home waypoint * diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c index 7af3a355eb..e0d7844d95 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013, 2014 PX4 Development Team. All rights reserved. + * Copyright (c) 2013-2015 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -147,10 +147,9 @@ int position_estimator_inav_main(int argc, char *argv[]) verbose_mode = false; - if (argc > 1) - if (!strcmp(argv[2], "-v")) { - verbose_mode = true; - } + if (argc > 2 && !strcmp(argv[2], "-v")) { + verbose_mode = true; + } thread_should_exit = false; position_estimator_inav_task = task_spawn_cmd("position_estimator_inav", diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 72d139b113..8940f0b271 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -680,6 +680,7 @@ PARAM_DEFINE_INT32(SENS_FLOW_ROT, 0); * This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user * to fine tune the board offset in the event of misalignment. * + * @unit radians * @group Sensor Calibration */ PARAM_DEFINE_FLOAT(SENS_BOARD_Y_OFF, 0.0f); @@ -690,6 +691,7 @@ PARAM_DEFINE_FLOAT(SENS_BOARD_Y_OFF, 0.0f); * This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user * to fine tune the board offset in the event of misalignment. * + * @unit radians * @group Sensor Calibration */ PARAM_DEFINE_FLOAT(SENS_BOARD_X_OFF, 0.0f); @@ -700,6 +702,7 @@ PARAM_DEFINE_FLOAT(SENS_BOARD_X_OFF, 0.0f); * This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user * to fine tune the board offset in the event of misalignment. * + * @unit radians * @group Sensor Calibration */ PARAM_DEFINE_FLOAT(SENS_BOARD_Z_OFF, 0.0f); @@ -736,6 +739,7 @@ PARAM_DEFINE_INT32(SENS_EXT_MAG, 0); * * @min 800.0 * @max 1500.0 + * @unit us * @group Radio Calibration */ PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f); @@ -747,6 +751,7 @@ PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f); * * @min 800.0 * @max 2200.0 + * @unit us * @group Radio Calibration */ PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f); @@ -758,6 +763,7 @@ PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f); * * @min 1500.0 * @max 2200.0 + * @unit us * @group Radio Calibration */ PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f); @@ -780,6 +786,7 @@ PARAM_DEFINE_FLOAT(RC1_REV, 1.0f); * * @min 0.0 * @max 100.0 + * @unit us * @group Radio Calibration */ PARAM_DEFINE_FLOAT(RC1_DZ, 10.0f); @@ -787,10 +794,11 @@ PARAM_DEFINE_FLOAT(RC1_DZ, 10.0f); /** * RC Channel 2 Minimum * - * Minimum value for RC channel 2 + * Minimum value for this channel. * * @min 800.0 * @max 1500.0 + * @unit us * @group Radio Calibration */ PARAM_DEFINE_FLOAT(RC2_MIN, 1000.0f); @@ -798,27 +806,725 @@ PARAM_DEFINE_FLOAT(RC2_MIN, 1000.0f); /** * RC Channel 2 Trim * - * Mid point value (same as min for throttle) + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC2_TRIM, 1500.0f); + +/** + * RC Channel 2 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC2_MAX, 2000.0f); + +/** + * RC Channel 2 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC2_REV, 1.0f); + +/** + * RC Channel 2 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC2_DZ, 10.0f); + +/** + * RC Channel 3 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC3_MIN, 1000); + +/** + * RC Channel 3 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC3_TRIM, 1500); + +/** + * RC Channel 3 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC3_MAX, 2000); + +/** + * RC Channel 3 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC3_REV, 1.0f); +/** + * RC Channel 3 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC3_DZ, 10.0f); + +/** + * RC Channel 4 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC4_MIN, 1000); + +/** + * RC Channel 4 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC4_TRIM, 1500); + +/** + * RC Channel 4 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC4_MAX, 2000); + +/** + * RC Channel 4 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC4_REV, 1.0f); + +/** + * RC Channel 4 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC4_DZ, 10.0f); + +/** + * RC Channel 5 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC5_MIN, 1000); + +/** + * RC Channel 5 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC5_TRIM, 1500); + +/** + * RC Channel 5 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC5_MAX, 2000); + +/** + * RC Channel 5 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC5_REV, 1.0f); + +/** + * RC Channel 5 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC5_DZ, 10.0f); + +/** + * RC Channel 6 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC6_MIN, 1000); + +/** + * RC Channel 6 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC6_TRIM, 1500); + +/** + * RC Channel 6 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC6_MAX, 2000); + +/** + * RC Channel 6 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC6_REV, 1.0f); + +/** + * RC Channel 6 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC6_DZ, 10.0f); + +/** + * RC Channel 7 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC7_MIN, 1000); + +/** + * RC Channel 7 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC7_TRIM, 1500); + +/** + * RC Channel 7 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC7_MAX, 2000); + +/** + * RC Channel 7 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC7_REV, 1.0f); + +/** + * RC Channel 7 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC7_DZ, 10.0f); + +/** + * RC Channel 8 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC8_MIN, 1000); + +/** + * RC Channel 8 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC8_TRIM, 1500); + +/** + * RC Channel 8 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC8_MAX, 2000); + +/** + * RC Channel 8 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC8_REV, 1.0f); + +/** + * RC Channel 8 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC8_DZ, 10.0f); + +/** + * RC Channel 9 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC9_MIN, 1000); + +/** + * RC Channel 9 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC9_TRIM, 1500); + +/** + * RC Channel 9 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC9_MAX, 2000); + +/** + * RC Channel 9 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC9_REV, 1.0f); + +/** + * RC Channel 9 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC9_DZ, 0.0f); + +/** + * RC Channel 10 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC10_MIN, 1000); + +/** + * RC Channel 10 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC10_TRIM, 1500); + +/** + * RC Channel 10 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC10_MAX, 2000); + +/** + * RC Channel 10 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC10_REV, 1.0f); + +/** + * RC Channel 10 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC10_DZ, 0.0f); + +/** + * RC Channel 11 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC11_MIN, 1000); + +/** + * RC Channel 11 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC11_TRIM, 1500); + +/** + * RC Channel 11 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC11_MAX, 2000); + +/** + * RC Channel 11 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC11_REV, 1.0f); + +/** + * RC Channel 11 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC11_DZ, 0.0f); + +/** + * RC Channel 12 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC12_MIN, 1000); + +/** + * RC Channel 12 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC12_TRIM, 1500); + +/** + * RC Channel 12 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC12_MAX, 2000); + +/** + * RC Channel 12 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC12_REV, 1.0f); + +/** + * RC Channel 12 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC12_DZ, 0.0f); + +/** + * RC Channel 13 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC13_MIN, 1000); + +/** + * RC Channel 13 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC13_TRIM, 1500); + +/** + * RC Channel 13 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC13_MAX, 2000); + +/** + * RC Channel 13 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC13_REV, 1.0f); + +/** + * RC Channel 13 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC13_DZ, 0.0f); + +/** + * RC Channel 14 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC14_MIN, 1000); + +/** + * RC Channel 14 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). * * @min 800.0 * @max 2200.0 + * @unit us * @group Radio Calibration */ -PARAM_DEFINE_FLOAT(RC2_TRIM, 1500.0f); +PARAM_DEFINE_FLOAT(RC14_TRIM, 1500); /** - * RC Channel 2 Maximum + * RC Channel 14 Maximum * - * Maximum value for RC channel 2 + * Maximum value for this channel. * * @min 1500.0 * @max 2200.0 + * @unit us * @group Radio Calibration */ -PARAM_DEFINE_FLOAT(RC2_MAX, 2000.0f); +PARAM_DEFINE_FLOAT(RC14_MAX, 2000); /** - * RC Channel 2 Reverse + * RC Channel 14 Reverse * * Set to -1 to reverse channel. * @@ -826,10 +1532,10 @@ PARAM_DEFINE_FLOAT(RC2_MAX, 2000.0f); * @max 1.0 * @group Radio Calibration */ -PARAM_DEFINE_FLOAT(RC2_REV, 1.0f); +PARAM_DEFINE_FLOAT(RC14_REV, 1.0f); /** - * RC Channel 2 dead zone + * RC Channel 14 dead zone * * The +- range of this value around the trim value will be considered as zero. * @@ -837,105 +1543,248 @@ PARAM_DEFINE_FLOAT(RC2_REV, 1.0f); * @max 100.0 * @group Radio Calibration */ -PARAM_DEFINE_FLOAT(RC2_DZ, 10.0f); - -PARAM_DEFINE_FLOAT(RC3_MIN, 1000); -PARAM_DEFINE_FLOAT(RC3_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC3_MAX, 2000); -PARAM_DEFINE_FLOAT(RC3_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC3_DZ, 10.0f); - -PARAM_DEFINE_FLOAT(RC4_MIN, 1000); -PARAM_DEFINE_FLOAT(RC4_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC4_MAX, 2000); -PARAM_DEFINE_FLOAT(RC4_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC4_DZ, 10.0f); - -PARAM_DEFINE_FLOAT(RC5_MIN, 1000); -PARAM_DEFINE_FLOAT(RC5_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC5_MAX, 2000); -PARAM_DEFINE_FLOAT(RC5_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC5_DZ, 10.0f); - -PARAM_DEFINE_FLOAT(RC6_MIN, 1000); -PARAM_DEFINE_FLOAT(RC6_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC6_MAX, 2000); -PARAM_DEFINE_FLOAT(RC6_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC6_DZ, 10.0f); - -PARAM_DEFINE_FLOAT(RC7_MIN, 1000); -PARAM_DEFINE_FLOAT(RC7_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC7_MAX, 2000); -PARAM_DEFINE_FLOAT(RC7_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC7_DZ, 10.0f); - -PARAM_DEFINE_FLOAT(RC8_MIN, 1000); -PARAM_DEFINE_FLOAT(RC8_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC8_MAX, 2000); -PARAM_DEFINE_FLOAT(RC8_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC8_DZ, 10.0f); - -PARAM_DEFINE_FLOAT(RC9_MIN, 1000); -PARAM_DEFINE_FLOAT(RC9_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC9_MAX, 2000); -PARAM_DEFINE_FLOAT(RC9_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC9_DZ, 0.0f); - -PARAM_DEFINE_FLOAT(RC10_MIN, 1000); -PARAM_DEFINE_FLOAT(RC10_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC10_MAX, 2000); -PARAM_DEFINE_FLOAT(RC10_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC10_DZ, 0.0f); - -PARAM_DEFINE_FLOAT(RC11_MIN, 1000); -PARAM_DEFINE_FLOAT(RC11_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC11_MAX, 2000); -PARAM_DEFINE_FLOAT(RC11_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC11_DZ, 0.0f); - -PARAM_DEFINE_FLOAT(RC12_MIN, 1000); -PARAM_DEFINE_FLOAT(RC12_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC12_MAX, 2000); -PARAM_DEFINE_FLOAT(RC12_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC12_DZ, 0.0f); - -PARAM_DEFINE_FLOAT(RC13_MIN, 1000); -PARAM_DEFINE_FLOAT(RC13_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC13_MAX, 2000); -PARAM_DEFINE_FLOAT(RC13_REV, 1.0f); -PARAM_DEFINE_FLOAT(RC13_DZ, 0.0f); - -PARAM_DEFINE_FLOAT(RC14_MIN, 1000); -PARAM_DEFINE_FLOAT(RC14_TRIM, 1500); -PARAM_DEFINE_FLOAT(RC14_MAX, 2000); -PARAM_DEFINE_FLOAT(RC14_REV, 1.0f); PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f); +/** + * RC Channel 15 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC15_MIN, 1000); + +/** + * RC Channel 15 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC15_TRIM, 1500); + +/** + * RC Channel 15 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC15_MAX, 2000); + +/** + * RC Channel 15 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC15_REV, 1.0f); + +/** + * RC Channel 15 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC15_DZ, 0.0f); +/** + * RC Channel 16 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC16_MIN, 1000); + +/** + * RC Channel 16 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC16_TRIM, 1500); + +/** + * RC Channel 16 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC16_MAX, 2000); + +/** + * RC Channel 16 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC16_REV, 1.0f); + +/** + * RC Channel 16 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC16_DZ, 0.0f); +/** + * RC Channel 17 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC17_MIN, 1000); + +/** + * RC Channel 17 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC17_TRIM, 1500); + +/** + * RC Channel 17 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC17_MAX, 2000); + +/** + * RC Channel 17 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC17_REV, 1.0f); + +/** + * RC Channel 17 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC17_DZ, 0.0f); +/** + * RC Channel 18 Minimum + * + * Minimum value for this channel. + * + * @min 800.0 + * @max 1500.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC18_MIN, 1000); + +/** + * RC Channel 18 Trim + * + * Mid point value (has to be set to the same as min for throttle channel). + * + * @min 800.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC18_TRIM, 1500); + +/** + * RC Channel 18 Maximum + * + * Maximum value for this channel. + * + * @min 1500.0 + * @max 2200.0 + * @unit us + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC18_MAX, 2000); + +/** + * RC Channel 18 Reverse + * + * Set to -1 to reverse channel. + * + * @min -1.0 + * @max 1.0 + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC18_REV, 1.0f); + +/** + * RC Channel 18 dead zone + * + * The +- range of this value around the trim value will be considered as zero. + * + * @min 0.0 + * @max 100.0 + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC18_DZ, 0.0f); #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 +/** + * Enable relay control of relay 1 mapped to the Spektrum receiver power supply + * + * @min 0 + * @max 1 + * @group Radio Calibration + */ PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */ #endif @@ -952,6 +1801,8 @@ PARAM_DEFINE_INT32(RC_DSM_BIND, -1); /** * Scaling factor for battery voltage sensor on PX4IO. * + * @min 1 + * @max 100000 * @group Battery Calibration */ PARAM_DEFINE_INT32(BAT_V_SCALE_IO, 10000); @@ -1231,8 +2082,12 @@ PARAM_DEFINE_INT32(RC_MAP_PARAM3, 0); /** * Failsafe channel PWM threshold. * - * @min 800 + * Set to a value slightly above the PWM value assumed by throttle in a failsafe event, + * but ensure it is below the PWM value assumed by throttle during normal operation. + * + * @min 0 * @max 2200 + * @unit us * @group Radio Calibration */ PARAM_DEFINE_INT32(RC_FAILS_THR, 0); diff --git a/src/modules/vtol_att_control/vtol_att_control_params.c b/src/modules/vtol_att_control/vtol_att_control_params.c index f302314a23..33c095036c 100644 --- a/src/modules/vtol_att_control/vtol_att_control_params.c +++ b/src/modules/vtol_att_control/vtol_att_control_params.c @@ -43,10 +43,10 @@ /** * VTOL number of engines * - * @min 1 + * @min 0 * @group VTOL Attitude Control */ -PARAM_DEFINE_INT32(VT_MOT_COUNT,0); +PARAM_DEFINE_INT32(VT_MOT_COUNT, 0); /** * Idle speed of VTOL when in multicopter mode @@ -54,7 +54,7 @@ PARAM_DEFINE_INT32(VT_MOT_COUNT,0); * @min 900 * @group VTOL Attitude Control */ -PARAM_DEFINE_INT32(VT_IDLE_PWM_MC,900); +PARAM_DEFINE_INT32(VT_IDLE_PWM_MC, 900); /** * Minimum airspeed in multicopter mode @@ -64,7 +64,7 @@ PARAM_DEFINE_INT32(VT_IDLE_PWM_MC,900); * @min 0.0 * @group VTOL Attitude Control */ -PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MIN,10.0f); +PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MIN, 10.0f); /** * Maximum airspeed in multicopter mode @@ -74,7 +74,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MIN,10.0f); * @min 0.0 * @group VTOL Attitude Control */ -PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MAX,30.0f); +PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MAX, 30.0f); /** * Trim airspeed when in multicopter mode @@ -84,7 +84,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MAX,30.0f); * @min 0.0 * @group VTOL Attitude Control */ -PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM,10.0f); +PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM, 10.0f); /** * Permanent stabilization in fw mode @@ -96,7 +96,7 @@ PARAM_DEFINE_FLOAT(VT_MC_ARSPD_TRIM,10.0f); * @max 1 * @group VTOL Attitude Control */ -PARAM_DEFINE_INT32(VT_FW_PERM_STAB,0); +PARAM_DEFINE_INT32(VT_FW_PERM_STAB, 0); /** * Fixed wing pitch trim @@ -107,7 +107,7 @@ PARAM_DEFINE_INT32(VT_FW_PERM_STAB,0); * @max 1 * @group VTOL Attitude Control */ -PARAM_DEFINE_FLOAT(VT_FW_PITCH_TRIM,0.0f); +PARAM_DEFINE_FLOAT(VT_FW_PITCH_TRIM, 0.0f); /** * Motor max power @@ -118,18 +118,18 @@ PARAM_DEFINE_FLOAT(VT_FW_PITCH_TRIM,0.0f); * @min 1 * @group VTOL Attitude Control */ -PARAM_DEFINE_FLOAT(VT_POWER_MAX,120.0f); +PARAM_DEFINE_FLOAT(VT_POWER_MAX, 120.0f); /** * Propeller efficiency parameter * * Influences propeller efficiency at different power settings. Should be tuned beforehand. * - * @min 0.5 + * @min 0.0 * @max 0.9 * @group VTOL Attitude Control */ -PARAM_DEFINE_FLOAT(VT_PROP_EFF,0.0f); +PARAM_DEFINE_FLOAT(VT_PROP_EFF, 0.0f); /** * Total airspeed estimate low-pass filter gain @@ -140,7 +140,7 @@ PARAM_DEFINE_FLOAT(VT_PROP_EFF,0.0f); * @max 0.99 * @group VTOL Attitude Control */ -PARAM_DEFINE_FLOAT(VT_ARSP_LP_GAIN,0.3f); +PARAM_DEFINE_FLOAT(VT_ARSP_LP_GAIN, 0.3f); /** * VTOL Type (Tailsitter=0, Tiltrotor=1) @@ -160,4 +160,4 @@ PARAM_DEFINE_INT32(VT_TYPE, 0); * @max 1 * @group VTOL Attitude Control */ -PARAM_DEFINE_INT32(VT_ELEV_MC_LOCK,0); +PARAM_DEFINE_INT32(VT_ELEV_MC_LOCK, 0);