From bbbcf82f9edd4f910f8a036fd3515caf7ca60084 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 4 Mar 2021 12:05:57 +0100 Subject: [PATCH 1/3] Small docs update --- docs/Settings.md | 16 ++++++++-------- src/main/fc/settings.yaml | 18 ++++++++++++++++-- 2 files changed, 24 insertions(+), 10 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 0662d982ec0..dbcd3dc48de 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -82,7 +82,7 @@ | eleres_signature | | | | eleres_telemetry_en | | | | eleres_telemetry_power | | | -| esc_sensor_listen_only | | | +| esc_sensor_listen_only | OFF | Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case | | failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | | failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb | | failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll | @@ -145,7 +145,7 @@ | gyro_dyn_lpf_curve_expo | 5 | Expo value for the throttle-to-frequency mapping for Dynamic LPF | | gyro_dyn_lpf_max_hz | 500 | Maximum frequency of the gyro Dynamic LPF | | gyro_dyn_lpf_min_hz | 200 | Minimum frequency of the gyro Dynamic LPF | -| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. | +| gyro_hardware_lpf | 256HZ | Hardware lowpass filter for gyro. Do value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first. | | gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | | gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | | gyro_notch_cutoff | | | @@ -247,7 +247,7 @@ | motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | | motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] | | motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | -| motor_poles | | | +| motor_poles | 14 | The number of motor poles. Required to compute motor RPM | | motor_pwm_protocol | ONESHOT125 | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | | motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. | | msp_override_channels | 0 | Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode. | @@ -302,7 +302,7 @@ | nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | | nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | | nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | -| nav_max_terrain_follow_alt | | | +| nav_max_terrain_follow_alt | 100 | Max allowed above the ground altitude for terrain following mode | | nav_mc_auto_disarm_delay | 2000 | Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s) | | nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | | nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode | @@ -411,10 +411,10 @@ | pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | | pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | | pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | -| pinio_box1 | | | -| pinio_box2 | | | -| pinio_box3 | | | -| pinio_box4 | | | +| pinio_box1 | target specific | Mode assignment for PINIO#1 | +| pinio_box2 | target specific | Mode assignment for PINIO#1 | +| pinio_box3 | target specific | Mode assignment for PINIO#1 | +| pinio_box4 | target specific | Mode assignment for PINIO#1 | | pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | | pitot_hardware | NONE | Selection of pitot hardware. | | pitot_lpf_milli_hz | | | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index d462d72cc8d..8dd7b3388f6 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -182,8 +182,8 @@ groups: type: uint8_t table: alignment - name: gyro_hardware_lpf - description: "Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first." - default_value: "42HZ" + description: "Hardware lowpass filter for gyro. Do value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first." + default_value: "256HZ" field: gyro_lpf table: gyro_lpf - name: gyro_lpf_hz @@ -718,6 +718,8 @@ groups: max: 30 - name: motor_poles field: motorPoleCount + description: "The number of motor poles. Required to compute motor RPM" + default_value: "14" min: 4 max: 255 @@ -2183,6 +2185,8 @@ groups: max: 65000 - name: nav_max_terrain_follow_alt field: general.max_terrain_follow_altitude + default_value: "100" + description: "Max allowed above the ground altitude for terrain following mode" max: 1000 - name: nav_rth_altitude description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)" @@ -3194,21 +3198,29 @@ groups: members: - name: pinio_box1 field: permanentId[0] + description: "Mode assignment for PINIO#1" + default_value: "target specific" min: 0 max: 255 type: uint8_t - name: pinio_box2 field: permanentId[1] + default_value: "target specific" + description: "Mode assignment for PINIO#1" min: 0 max: 255 type: uint8_t - name: pinio_box3 field: permanentId[2] + default_value: "target specific" + description: "Mode assignment for PINIO#1" min: 0 max: 255 type: uint8_t - name: pinio_box4 field: permanentId[3] + default_value: "target specific" + description: "Mode assignment for PINIO#1" min: 0 max: 255 type: uint8_t @@ -3236,6 +3248,8 @@ groups: condition: USE_ESC_SENSOR members: - name: esc_sensor_listen_only + default_value: "OFF" + description: "Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case" field: listenOnly type: bool From efbb4126fff546ba4648e80c0ae2b4e00e1cb1a8 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 4 Mar 2021 12:10:08 +0100 Subject: [PATCH 2/3] Typo fix --- src/main/fc/settings.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 8dd7b3388f6..546cd46e8e2 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -182,7 +182,7 @@ groups: type: uint8_t table: alignment - name: gyro_hardware_lpf - description: "Hardware lowpass filter for gyro. Do value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first." + description: "Hardware lowpass filter for gyro. This value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first." default_value: "256HZ" field: gyro_lpf table: gyro_lpf From 86229f823e4e0afbc8a66a0b2b2487791cd882fb Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 4 Mar 2021 12:21:30 +0100 Subject: [PATCH 3/3] Regenerate docs --- docs/Settings.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Settings.md b/docs/Settings.md index dbcd3dc48de..d704df6aca2 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -145,7 +145,7 @@ | gyro_dyn_lpf_curve_expo | 5 | Expo value for the throttle-to-frequency mapping for Dynamic LPF | | gyro_dyn_lpf_max_hz | 500 | Maximum frequency of the gyro Dynamic LPF | | gyro_dyn_lpf_min_hz | 200 | Minimum frequency of the gyro Dynamic LPF | -| gyro_hardware_lpf | 256HZ | Hardware lowpass filter for gyro. Do value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first. | +| gyro_hardware_lpf | 256HZ | Hardware lowpass filter for gyro. This value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first. | | gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | | gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | | gyro_notch_cutoff | | |