mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
refactor(sensors): convert params.c to module.yaml
Convert 7 parameter file(s) from legacy C format to YAML module configuration.
This commit is contained in:
parent
139279747e
commit
c09976f99b
@ -74,6 +74,9 @@ px4_add_module(
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
vehicle_gps_position/module.yaml
|
||||
sensor_params.yaml
|
||||
sensor_params_flow.yaml
|
||||
sensor_params_mag.yaml
|
||||
DEPENDS
|
||||
conversion
|
||||
data_validator
|
||||
|
||||
@ -1,258 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2019 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Airspeed sensor compensation model for the SDP3x
|
||||
*
|
||||
* Model with Pitot
|
||||
* CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.
|
||||
* CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.
|
||||
* Model without Pitot (1.5 mm tubes)
|
||||
* CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.
|
||||
* CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.
|
||||
* Tube Pressure Drop
|
||||
* CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter.
|
||||
* CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.
|
||||
*
|
||||
* @value 0 Model with Pitot
|
||||
* @value 1 Model without Pitot (1.5 mm tubes)
|
||||
* @value 2 Tube Pressure Drop
|
||||
*
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_AIR_CMODEL, 0);
|
||||
|
||||
/**
|
||||
* Airspeed sensor tube length.
|
||||
*
|
||||
* See the CAL_AIR_CMODEL explanation on how this parameter should be set.
|
||||
*
|
||||
* @min 0.01
|
||||
* @max 2.00
|
||||
* @unit m
|
||||
*
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_AIR_TUBELEN, 0.2f);
|
||||
|
||||
/**
|
||||
* Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation.
|
||||
*
|
||||
* @min 1.5
|
||||
* @max 100
|
||||
* @unit mm
|
||||
*
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAL_AIR_TUBED_MM, 1.5f);
|
||||
|
||||
/**
|
||||
* Differential pressure sensor offset
|
||||
*
|
||||
* The offset (zero-reading) in Pascal
|
||||
*
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
* @volatile
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Reverse differential pressure sensor readings
|
||||
*
|
||||
* Reverse the raw measurements of all differential pressure sensors.
|
||||
* This can be enabled if the sensors have static and dynamic ports swapped.
|
||||
*
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
* @boolean
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_DPRES_REV, 0);
|
||||
|
||||
/**
|
||||
* Differential pressure sensor analog scaling
|
||||
*
|
||||
* Pick the appropriate scaling from the datasheet.
|
||||
* this number defines the (linear) conversion from voltage
|
||||
* to Pascal (pa). For the MPXV7002DP this is 1000.
|
||||
*
|
||||
* NOTE: If the sensor always registers zero, try switching
|
||||
* the static and dynamic tubes.
|
||||
*
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_DPRES_ANSC, 0);
|
||||
|
||||
/**
|
||||
* Board rotation
|
||||
*
|
||||
* This parameter defines the rotation of the FMU board relative to the platform.
|
||||
*
|
||||
* @value 0 No rotation
|
||||
* @value 1 Yaw 45°
|
||||
* @value 2 Yaw 90°
|
||||
* @value 3 Yaw 135°
|
||||
* @value 4 Yaw 180°
|
||||
* @value 5 Yaw 225°
|
||||
* @value 6 Yaw 270°
|
||||
* @value 7 Yaw 315°
|
||||
* @value 8 Roll 180°
|
||||
* @value 9 Roll 180°, Yaw 45°
|
||||
* @value 10 Roll 180°, Yaw 90°
|
||||
* @value 11 Roll 180°, Yaw 135°
|
||||
* @value 12 Pitch 180°
|
||||
* @value 13 Roll 180°, Yaw 225°
|
||||
* @value 14 Roll 180°, Yaw 270°
|
||||
* @value 15 Roll 180°, Yaw 315°
|
||||
* @value 16 Roll 90°
|
||||
* @value 17 Roll 90°, Yaw 45°
|
||||
* @value 18 Roll 90°, Yaw 90°
|
||||
* @value 19 Roll 90°, Yaw 135°
|
||||
* @value 20 Roll 270°
|
||||
* @value 21 Roll 270°, Yaw 45°
|
||||
* @value 22 Roll 270°, Yaw 90°
|
||||
* @value 23 Roll 270°, Yaw 135°
|
||||
* @value 24 Pitch 90°
|
||||
* @value 25 Pitch 270°
|
||||
* @value 26 Pitch 180°, Yaw 90°
|
||||
* @value 27 Pitch 180°, Yaw 270°
|
||||
* @value 28 Roll 90°, Pitch 90°
|
||||
* @value 29 Roll 180°, Pitch 90°
|
||||
* @value 30 Roll 270°, Pitch 90°
|
||||
* @value 31 Roll 90°, Pitch 180°
|
||||
* @value 32 Roll 270°, Pitch 180°
|
||||
* @value 33 Roll 90°, Pitch 270°
|
||||
* @value 34 Roll 180°, Pitch 270°
|
||||
* @value 35 Roll 270°, Pitch 270°
|
||||
* @value 36 Roll 90°, Pitch 180°, Yaw 90°
|
||||
* @value 37 Roll 90°, Yaw 270°
|
||||
* @value 38 Roll 90°, Pitch 68°, Yaw 293°
|
||||
* @value 39 Pitch 315°
|
||||
* @value 40 Roll 90°, Pitch 315°
|
||||
*
|
||||
* @min -1
|
||||
* @max 40
|
||||
* @reboot_required true
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0);
|
||||
|
||||
/**
|
||||
* Board rotation Y (pitch) offset
|
||||
*
|
||||
* Rotation from flight controller board to vehicle body frame.
|
||||
* This parameter gets set during the "level horizon" calibration or can be
|
||||
* set manually.
|
||||
*
|
||||
* @min -45.0
|
||||
* @max 45.0
|
||||
* @decimal 1
|
||||
* @unit deg
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_BOARD_Y_OFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Board rotation X (roll) offset
|
||||
*
|
||||
* Rotation from flight controller board to vehicle body frame.
|
||||
* This parameter gets set during the "level horizon" calibration or can be
|
||||
* set manually.
|
||||
*
|
||||
* @unit deg
|
||||
* @min -45.0
|
||||
* @max 45.0
|
||||
* @decimal 1
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_BOARD_X_OFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Board rotation Z (yaw) offset
|
||||
*
|
||||
* Rotation from flight controller board to vehicle body frame.
|
||||
* Has to be set manually (not set by any calibration).
|
||||
*
|
||||
* @min -45.0
|
||||
* @max 45.0
|
||||
* @decimal 1
|
||||
* @unit deg
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_BOARD_Z_OFF, 0.0f);
|
||||
|
||||
/**
|
||||
* Thermal control of sensor temperature
|
||||
*
|
||||
* @value -1 Thermal control unavailable
|
||||
* @value 0 Thermal control off
|
||||
* @value 1 Thermal control enabled
|
||||
* @category system
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_EN_THERMAL, -1);
|
||||
|
||||
/**
|
||||
* External I2C probe.
|
||||
*
|
||||
* Probe for optional external I2C devices.
|
||||
*
|
||||
* @boolean
|
||||
* @category system
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_EXT_I2C_PRB, 1);
|
||||
|
||||
/**
|
||||
* Sensors hub IMU mode
|
||||
*
|
||||
* @value 0 Disabled
|
||||
* @value 1 Publish primary IMU selection
|
||||
*
|
||||
* @category system
|
||||
* @reboot_required true
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_IMU_MODE, 1);
|
||||
|
||||
/**
|
||||
* Enable internal barometers
|
||||
*
|
||||
* For systems with an external barometer, this should be set to false to make sure that the external is used.
|
||||
*
|
||||
* @boolean
|
||||
* @reboot_required true
|
||||
* @category system
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_INT_BARO_EN, 1);
|
||||
199
src/modules/sensors/sensor_params.yaml
Normal file
199
src/modules/sensors/sensor_params.yaml
Normal file
@ -0,0 +1,199 @@
|
||||
module_name: sensors
|
||||
parameters:
|
||||
- group: Sensor Calibration
|
||||
definitions:
|
||||
SENS_DPRES_OFF:
|
||||
description:
|
||||
short: Differential pressure sensor offset
|
||||
long: The offset (zero-reading) in Pascal
|
||||
category: System
|
||||
type: float
|
||||
default: 0.0
|
||||
volatile: true
|
||||
SENS_DPRES_REV:
|
||||
description:
|
||||
short: Reverse differential pressure sensor readings
|
||||
long: |-
|
||||
Reverse the raw measurements of all differential pressure sensors.
|
||||
This can be enabled if the sensors have static and dynamic ports swapped.
|
||||
category: System
|
||||
type: boolean
|
||||
default: 0
|
||||
SENS_DPRES_ANSC:
|
||||
description:
|
||||
short: Differential pressure sensor analog scaling
|
||||
long: |-
|
||||
Pick the appropriate scaling from the datasheet.
|
||||
this number defines the (linear) conversion from voltage
|
||||
to Pascal (pa). For the MPXV7002DP this is 1000.
|
||||
|
||||
NOTE: If the sensor always registers zero, try switching
|
||||
the static and dynamic tubes.
|
||||
type: float
|
||||
default: 0
|
||||
- group: Sensors
|
||||
definitions:
|
||||
CAL_AIR_CMODEL:
|
||||
description:
|
||||
short: Airspeed sensor compensation model for the SDP3x
|
||||
long: |-
|
||||
Model with Pitot
|
||||
CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.
|
||||
CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.
|
||||
Model without Pitot (1.5 mm tubes)
|
||||
CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.
|
||||
CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.
|
||||
Tube Pressure Drop
|
||||
CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter.
|
||||
CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.
|
||||
type: enum
|
||||
values:
|
||||
0: Model with Pitot
|
||||
1: Model without Pitot (1.5 mm tubes)
|
||||
2: Tube Pressure Drop
|
||||
default: 0
|
||||
CAL_AIR_TUBELEN:
|
||||
description:
|
||||
short: Airspeed sensor tube length
|
||||
long: See the CAL_AIR_CMODEL explanation on how this parameter should be set.
|
||||
type: float
|
||||
default: 0.2
|
||||
min: 0.01
|
||||
max: 2.0
|
||||
unit: m
|
||||
CAL_AIR_TUBED_MM:
|
||||
description:
|
||||
short: Airspeed sensor tube diameter
|
||||
long: Airspeed sensor tube diameter. Only used for the Tube Pressure Drop
|
||||
Compensation
|
||||
type: float
|
||||
default: 1.5
|
||||
min: 1.5
|
||||
max: 100
|
||||
unit: mm
|
||||
SENS_BOARD_ROT:
|
||||
description:
|
||||
short: Board rotation
|
||||
long: This parameter defines the rotation of the FMU board relative to the
|
||||
platform.
|
||||
type: enum
|
||||
values:
|
||||
0: No rotation
|
||||
1: "Yaw 45\xB0"
|
||||
2: "Yaw 90\xB0"
|
||||
3: "Yaw 135\xB0"
|
||||
4: "Yaw 180\xB0"
|
||||
5: "Yaw 225\xB0"
|
||||
6: "Yaw 270\xB0"
|
||||
7: "Yaw 315\xB0"
|
||||
8: "Roll 180\xB0"
|
||||
9: "Roll 180\xB0, Yaw 45\xB0"
|
||||
10: "Roll 180\xB0, Yaw 90\xB0"
|
||||
11: "Roll 180\xB0, Yaw 135\xB0"
|
||||
12: "Pitch 180\xB0"
|
||||
13: "Roll 180\xB0, Yaw 225\xB0"
|
||||
14: "Roll 180\xB0, Yaw 270\xB0"
|
||||
15: "Roll 180\xB0, Yaw 315\xB0"
|
||||
16: "Roll 90\xB0"
|
||||
17: "Roll 90\xB0, Yaw 45\xB0"
|
||||
18: "Roll 90\xB0, Yaw 90\xB0"
|
||||
19: "Roll 90\xB0, Yaw 135\xB0"
|
||||
20: "Roll 270\xB0"
|
||||
21: "Roll 270\xB0, Yaw 45\xB0"
|
||||
22: "Roll 270\xB0, Yaw 90\xB0"
|
||||
23: "Roll 270\xB0, Yaw 135\xB0"
|
||||
24: "Pitch 90\xB0"
|
||||
25: "Pitch 270\xB0"
|
||||
26: "Pitch 180\xB0, Yaw 90\xB0"
|
||||
27: "Pitch 180\xB0, Yaw 270\xB0"
|
||||
28: "Roll 90\xB0, Pitch 90\xB0"
|
||||
29: "Roll 180\xB0, Pitch 90\xB0"
|
||||
30: "Roll 270\xB0, Pitch 90\xB0"
|
||||
31: "Roll 90\xB0, Pitch 180\xB0"
|
||||
32: "Roll 270\xB0, Pitch 180\xB0"
|
||||
33: "Roll 90\xB0, Pitch 270\xB0"
|
||||
34: "Roll 180\xB0, Pitch 270\xB0"
|
||||
35: "Roll 270\xB0, Pitch 270\xB0"
|
||||
36: "Roll 90\xB0, Pitch 180\xB0, Yaw 90\xB0"
|
||||
37: "Roll 90\xB0, Yaw 270\xB0"
|
||||
38: "Roll 90\xB0, Pitch 68\xB0, Yaw 293\xB0"
|
||||
39: "Pitch 315\xB0"
|
||||
40: "Roll 90\xB0, Pitch 315\xB0"
|
||||
default: 0
|
||||
min: -1
|
||||
max: 40
|
||||
reboot_required: true
|
||||
SENS_BOARD_Y_OFF:
|
||||
description:
|
||||
short: Board rotation Y (pitch) offset
|
||||
long: |-
|
||||
Rotation from flight controller board to vehicle body frame.
|
||||
This parameter gets set during the "level horizon" calibration or can be
|
||||
set manually.
|
||||
type: float
|
||||
default: 0.0
|
||||
min: -45.0
|
||||
max: 45.0
|
||||
decimal: 1
|
||||
unit: deg
|
||||
SENS_BOARD_X_OFF:
|
||||
description:
|
||||
short: Board rotation X (roll) offset
|
||||
long: |-
|
||||
Rotation from flight controller board to vehicle body frame.
|
||||
This parameter gets set during the "level horizon" calibration or can be
|
||||
set manually.
|
||||
type: float
|
||||
default: 0.0
|
||||
unit: deg
|
||||
min: -45.0
|
||||
max: 45.0
|
||||
decimal: 1
|
||||
SENS_BOARD_Z_OFF:
|
||||
description:
|
||||
short: Board rotation Z (yaw) offset
|
||||
long: |-
|
||||
Rotation from flight controller board to vehicle body frame.
|
||||
Has to be set manually (not set by any calibration).
|
||||
type: float
|
||||
default: 0.0
|
||||
min: -45.0
|
||||
max: 45.0
|
||||
decimal: 1
|
||||
unit: deg
|
||||
SENS_EN_THERMAL:
|
||||
description:
|
||||
short: Thermal control of sensor temperature
|
||||
category: System
|
||||
type: enum
|
||||
values:
|
||||
-1: Thermal control unavailable
|
||||
0: Thermal control off
|
||||
1: Thermal control enabled
|
||||
default: -1
|
||||
SENS_EXT_I2C_PRB:
|
||||
description:
|
||||
short: External I2C probe
|
||||
long: Probe for optional external I2C devices.
|
||||
category: System
|
||||
type: boolean
|
||||
default: 1
|
||||
SENS_IMU_MODE:
|
||||
description:
|
||||
short: Sensors hub IMU mode
|
||||
category: System
|
||||
type: enum
|
||||
values:
|
||||
0: Disabled
|
||||
1: Publish primary IMU selection
|
||||
default: 1
|
||||
reboot_required: true
|
||||
SENS_INT_BARO_EN:
|
||||
description:
|
||||
short: Enable internal barometers
|
||||
long: For systems with an external barometer, this should be set to false
|
||||
to make sure that the external is used.
|
||||
category: System
|
||||
type: boolean
|
||||
default: 1
|
||||
reboot_required: true
|
||||
@ -1,123 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2022 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Optical flow rotation
|
||||
*
|
||||
* This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame.
|
||||
* Zero rotation is defined as X on flow board pointing towards front of vehicle.
|
||||
*
|
||||
* @value 0 No rotation
|
||||
* @value 1 Yaw 45°
|
||||
* @value 2 Yaw 90°
|
||||
* @value 3 Yaw 135°
|
||||
* @value 4 Yaw 180°
|
||||
* @value 5 Yaw 225°
|
||||
* @value 6 Yaw 270°
|
||||
* @value 7 Yaw 315°
|
||||
*
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_FLOW_ROT, 0);
|
||||
|
||||
/**
|
||||
* Minimum height above ground when reliant on optical flow.
|
||||
*
|
||||
* This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably.
|
||||
* The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.
|
||||
*
|
||||
* @unit m
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @increment 0.1
|
||||
* @decimal 2
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_FLOW_MINHGT, 0.08f);
|
||||
|
||||
/**
|
||||
* Maximum height above ground when reliant on optical flow.
|
||||
*
|
||||
* This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably.
|
||||
* The height setpoint will be limited to be no greater than this value when the navigation system
|
||||
* is completely reliant on optical flow data and the height above ground estimate is valid.
|
||||
* The sensor may be usable above this height, but accuracy will progressively degrade.
|
||||
*
|
||||
* @unit m
|
||||
* @min 1.0
|
||||
* @max 100.0
|
||||
* @increment 0.1
|
||||
* @decimal 2
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_FLOW_MAXHGT, 100.f);
|
||||
|
||||
/**
|
||||
* Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor.
|
||||
*
|
||||
* Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and
|
||||
* control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground
|
||||
* is less than 50% of this value.
|
||||
*
|
||||
* @unit rad/s
|
||||
* @min 1.0
|
||||
* @decimal 2
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_FLOW_MAXR, 8.f);
|
||||
|
||||
/**
|
||||
* Optical flow max rate.
|
||||
*
|
||||
* Optical flow data maximum publication rate. This is an upper bound,
|
||||
* actual optical flow data rate is still dependent on the sensor.
|
||||
*
|
||||
* @min 1
|
||||
* @max 200
|
||||
* @group Sensors
|
||||
* @unit Hz
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_FLOW_RATE, 70.0f);
|
||||
|
||||
/**
|
||||
* Optical flow scale factor
|
||||
*
|
||||
* @min 0.5
|
||||
* @max 1.5
|
||||
* @decimal 2
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_FLOW_SCALE, 1.f);
|
||||
85
src/modules/sensors/sensor_params_flow.yaml
Normal file
85
src/modules/sensors/sensor_params_flow.yaml
Normal file
@ -0,0 +1,85 @@
|
||||
module_name: sensors
|
||||
parameters:
|
||||
- group: Sensor Calibration
|
||||
definitions:
|
||||
SENS_FLOW_MINHGT:
|
||||
description:
|
||||
short: Minimum height above ground when reliant on optical flow
|
||||
long: |-
|
||||
This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably.
|
||||
The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.
|
||||
type: float
|
||||
default: 0.08
|
||||
unit: m
|
||||
min: 0.0
|
||||
max: 1.0
|
||||
increment: 0.1
|
||||
decimal: 2
|
||||
SENS_FLOW_MAXHGT:
|
||||
description:
|
||||
short: Maximum height above ground when reliant on optical flow
|
||||
long: |-
|
||||
This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably.
|
||||
The height setpoint will be limited to be no greater than this value when the navigation system
|
||||
is completely reliant on optical flow data and the height above ground estimate is valid.
|
||||
The sensor may be usable above this height, but accuracy will progressively degrade.
|
||||
type: float
|
||||
default: 100.0
|
||||
unit: m
|
||||
min: 1.0
|
||||
max: 100.0
|
||||
increment: 0.1
|
||||
decimal: 2
|
||||
SENS_FLOW_MAXR:
|
||||
description:
|
||||
short: Max angular flow rate measurable by sensor
|
||||
long: |-
|
||||
Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor
|
||||
|
||||
Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and
|
||||
control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground
|
||||
is less than 50% of this value.
|
||||
type: float
|
||||
default: 8.0
|
||||
unit: rad/s
|
||||
min: 1.0
|
||||
decimal: 2
|
||||
- group: Sensors
|
||||
definitions:
|
||||
SENS_FLOW_ROT:
|
||||
description:
|
||||
short: Optical flow rotation
|
||||
long: |-
|
||||
This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame.
|
||||
Zero rotation is defined as X on flow board pointing towards front of vehicle.
|
||||
type: enum
|
||||
values:
|
||||
0: No rotation
|
||||
1: "Yaw 45\xB0"
|
||||
2: "Yaw 90\xB0"
|
||||
3: "Yaw 135\xB0"
|
||||
4: "Yaw 180\xB0"
|
||||
5: "Yaw 225\xB0"
|
||||
6: "Yaw 270\xB0"
|
||||
7: "Yaw 315\xB0"
|
||||
default: 0
|
||||
SENS_FLOW_RATE:
|
||||
description:
|
||||
short: Optical flow max rate
|
||||
long: |-
|
||||
Optical flow data maximum publication rate. This is an upper bound,
|
||||
actual optical flow data rate is still dependent on the sensor.
|
||||
type: float
|
||||
default: 70.0
|
||||
min: 1
|
||||
max: 200
|
||||
unit: Hz
|
||||
reboot_required: true
|
||||
SENS_FLOW_SCALE:
|
||||
description:
|
||||
short: Optical flow scale factor
|
||||
type: float
|
||||
default: 1.0
|
||||
min: 0.5
|
||||
max: 1.5
|
||||
decimal: 2
|
||||
@ -1,129 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2020 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Bitfield selecting mag sides for calibration
|
||||
*
|
||||
* If set to two side calibration, only the offsets are estimated, the scale
|
||||
* calibration is left unchanged. Thus an initial six side calibration is
|
||||
* recommended.
|
||||
*
|
||||
* Bits:
|
||||
* ORIENTATION_TAIL_DOWN = 1
|
||||
* ORIENTATION_NOSE_DOWN = 2
|
||||
* ORIENTATION_LEFT = 4
|
||||
* ORIENTATION_RIGHT = 8
|
||||
* ORIENTATION_UPSIDE_DOWN = 16
|
||||
* ORIENTATION_RIGHTSIDE_UP = 32
|
||||
*
|
||||
* @min 34
|
||||
* @max 63
|
||||
* @value 34 Two side calibration
|
||||
* @value 38 Three side calibration
|
||||
* @value 63 Six side calibration
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_MAG_SIDES, 63);
|
||||
|
||||
/**
|
||||
* For legacy QGC support only
|
||||
*
|
||||
* Use SENS_MAG_SIDES instead
|
||||
*
|
||||
* @group Sensors
|
||||
* @category Developer
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG_SIDES, 63);
|
||||
|
||||
/**
|
||||
* Type of magnetometer compensation
|
||||
*
|
||||
* @value 0 Disabled
|
||||
* @value 1 Throttle-based compensation
|
||||
* @value 2 Current-based compensation (battery_status instance 0)
|
||||
* @value 3 Current-based compensation (battery_status instance 1)
|
||||
*
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG_COMP_TYP, 0);
|
||||
|
||||
/**
|
||||
* Automatically set external rotations.
|
||||
*
|
||||
* During calibration attempt to automatically determine the rotation of external magnetometers.
|
||||
*
|
||||
* @boolean
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_MAG_AUTOROT, 1);
|
||||
|
||||
/**
|
||||
* Magnetometer max rate.
|
||||
*
|
||||
* Magnetometer data maximum publication rate. This is an upper bound,
|
||||
* actual magnetometer data rate is still dependent on the sensor.
|
||||
*
|
||||
* @min 1
|
||||
* @max 200
|
||||
* @group Sensors
|
||||
* @unit Hz
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_MAG_RATE, 15.0f);
|
||||
|
||||
/**
|
||||
* Sensors hub mag mode
|
||||
*
|
||||
* @value 0 Publish all magnetometers
|
||||
* @value 1 Publish primary magnetometer
|
||||
*
|
||||
* @category system
|
||||
* @reboot_required true
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_MAG_MODE, 1);
|
||||
|
||||
/**
|
||||
* Magnetometer auto calibration
|
||||
*
|
||||
* Automatically initialize magnetometer calibration from bias estimate if available.
|
||||
*
|
||||
* @boolean
|
||||
*
|
||||
* @category system
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_MAG_AUTOCAL, 1);
|
||||
84
src/modules/sensors/sensor_params_mag.yaml
Normal file
84
src/modules/sensors/sensor_params_mag.yaml
Normal file
@ -0,0 +1,84 @@
|
||||
module_name: sensors
|
||||
parameters:
|
||||
- group: Sensor Calibration
|
||||
definitions:
|
||||
CAL_MAG_COMP_TYP:
|
||||
description:
|
||||
short: Type of magnetometer compensation
|
||||
category: System
|
||||
type: enum
|
||||
values:
|
||||
0: Disabled
|
||||
1: Throttle-based compensation
|
||||
2: Current-based compensation (battery_status instance 0)
|
||||
3: Current-based compensation (battery_status instance 1)
|
||||
default: 0
|
||||
- group: Sensors
|
||||
definitions:
|
||||
SENS_MAG_SIDES:
|
||||
description:
|
||||
short: Bitfield selecting mag sides for calibration
|
||||
long: |-
|
||||
If set to two side calibration, only the offsets are estimated, the scale
|
||||
calibration is left unchanged. Thus an initial six side calibration is
|
||||
recommended.
|
||||
|
||||
Bits:
|
||||
ORIENTATION_TAIL_DOWN = 1
|
||||
ORIENTATION_NOSE_DOWN = 2
|
||||
ORIENTATION_LEFT = 4
|
||||
ORIENTATION_RIGHT = 8
|
||||
ORIENTATION_UPSIDE_DOWN = 16
|
||||
ORIENTATION_RIGHTSIDE_UP = 32
|
||||
type: enum
|
||||
values:
|
||||
34: Two side calibration
|
||||
38: Three side calibration
|
||||
63: Six side calibration
|
||||
default: 63
|
||||
min: 34
|
||||
max: 63
|
||||
CAL_MAG_SIDES:
|
||||
description:
|
||||
short: For legacy QGC support only
|
||||
long: Use SENS_MAG_SIDES instead
|
||||
category: Developer
|
||||
type: int32
|
||||
default: 63
|
||||
SENS_MAG_AUTOROT:
|
||||
description:
|
||||
short: Automatically set external rotations
|
||||
long: During calibration attempt to automatically determine the rotation of
|
||||
external magnetometers.
|
||||
type: boolean
|
||||
default: 1
|
||||
SENS_MAG_RATE:
|
||||
description:
|
||||
short: Magnetometer max rate
|
||||
long: |-
|
||||
Magnetometer data maximum publication rate. This is an upper bound,
|
||||
actual magnetometer data rate is still dependent on the sensor.
|
||||
type: float
|
||||
default: 15.0
|
||||
min: 1
|
||||
max: 200
|
||||
unit: Hz
|
||||
reboot_required: true
|
||||
SENS_MAG_MODE:
|
||||
description:
|
||||
short: Sensors hub mag mode
|
||||
category: System
|
||||
type: enum
|
||||
values:
|
||||
0: Publish all magnetometers
|
||||
1: Publish primary magnetometer
|
||||
default: 1
|
||||
reboot_required: true
|
||||
SENS_MAG_AUTOCAL:
|
||||
description:
|
||||
short: Magnetometer auto calibration
|
||||
long: Automatically initialize magnetometer calibration from bias estimate
|
||||
if available.
|
||||
category: System
|
||||
type: boolean
|
||||
default: 1
|
||||
@ -1,46 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Low pass filter cutoff frequency for accel
|
||||
*
|
||||
* The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer.
|
||||
* This only affects the signal sent to the controllers, not the estimators. 0 disables the filter.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1000
|
||||
* @unit Hz
|
||||
* @reboot_required true
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(IMU_ACCEL_CUTOFF, 30.0f);
|
||||
@ -1,67 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2022 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* QNH for barometer
|
||||
*
|
||||
* @min 500
|
||||
* @max 1500
|
||||
* @group Sensors
|
||||
* @unit hPa
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_BARO_QNH, 1013.25f);
|
||||
|
||||
/**
|
||||
* Baro max rate.
|
||||
*
|
||||
* Barometric air data maximum publication rate. This is an upper bound,
|
||||
* actual barometric data rate is still dependent on the sensor.
|
||||
*
|
||||
* @min 1
|
||||
* @max 200
|
||||
* @group Sensors
|
||||
* @unit Hz
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(SENS_BARO_RATE, 20.0f);
|
||||
|
||||
/**
|
||||
* Barometer auto calibration
|
||||
*
|
||||
* Automatically calibrate barometer based on the GNSS height
|
||||
*
|
||||
* @boolean
|
||||
*
|
||||
* @category system
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_BAR_AUTOCAL, 1);
|
||||
@ -1,222 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Notch filter frequency for gyro
|
||||
*
|
||||
* The center frequency for the 2nd order notch filter on the primary gyro.
|
||||
* This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency.
|
||||
* This only affects the signal sent to the controllers, not the estimators.
|
||||
* Applies to both angular velocity and angular acceleration sent to the controllers.
|
||||
* See "IMU_GYRO_NF0_BW" to set the bandwidth of the filter.
|
||||
*
|
||||
* A value of 0 disables the filter.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1000
|
||||
* @unit Hz
|
||||
* @increment 0.1
|
||||
* @decimal 1
|
||||
* @reboot_required false
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(IMU_GYRO_NF0_FRQ, 0.0f);
|
||||
|
||||
/**
|
||||
* Notch filter bandwidth for gyro
|
||||
*
|
||||
* The frequency width of the stop band for the 2nd order notch filter on the primary gyro.
|
||||
* See "IMU_GYRO_NF0_FRQ" to activate the filter and to set the notch frequency.
|
||||
* Applies to both angular velocity and angular acceleration sent to the controllers.
|
||||
*
|
||||
* @min 0
|
||||
* @max 100
|
||||
* @unit Hz
|
||||
* @increment 0.1
|
||||
* @decimal 1
|
||||
* @reboot_required false
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(IMU_GYRO_NF0_BW, 20.0f);
|
||||
|
||||
/**
|
||||
* Notch filter 2 frequency for gyro
|
||||
*
|
||||
* The center frequency for the 2nd order notch filter on the primary gyro.
|
||||
* This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency.
|
||||
* This only affects the signal sent to the controllers, not the estimators.
|
||||
* Applies to both angular velocity and angular acceleration sent to the controllers.
|
||||
* See "IMU_GYRO_NF1_BW" to set the bandwidth of the filter.
|
||||
*
|
||||
* A value of 0 disables the filter.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1000
|
||||
* @unit Hz
|
||||
* @increment 0.1
|
||||
* @decimal 1
|
||||
* @reboot_required false
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(IMU_GYRO_NF1_FRQ, 0.0f);
|
||||
|
||||
/**
|
||||
* Notch filter 1 bandwidth for gyro
|
||||
*
|
||||
* The frequency width of the stop band for the 2nd order notch filter on the primary gyro.
|
||||
* See "IMU_GYRO_NF1_FRQ" to activate the filter and to set the notch frequency.
|
||||
* Applies to both angular velocity and angular acceleration sent to the controllers.
|
||||
*
|
||||
* @min 0
|
||||
* @max 100
|
||||
* @unit Hz
|
||||
* @increment 0.1
|
||||
* @decimal 1
|
||||
* @reboot_required false
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(IMU_GYRO_NF1_BW, 20.0f);
|
||||
|
||||
|
||||
/**
|
||||
* Low pass filter cutoff frequency for gyro
|
||||
*
|
||||
* The cutoff frequency for the 2nd order butterworth filter on the primary gyro.
|
||||
* This only affects the angular velocity sent to the controllers, not the estimators.
|
||||
* It applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF.
|
||||
*
|
||||
* A value of 0 disables the filter.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1000
|
||||
* @unit Hz
|
||||
* @increment 0.1
|
||||
* @decimal 1
|
||||
* @reboot_required false
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(IMU_GYRO_CUTOFF, 40.0f);
|
||||
|
||||
/**
|
||||
* Gyro control data maximum publication rate (inner loop rate)
|
||||
*
|
||||
* The maximum rate the gyro control data (vehicle_angular_velocity) will be
|
||||
* allowed to publish at. This is the loop rate for the rate controller and outputs.
|
||||
*
|
||||
* Note: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting.
|
||||
*
|
||||
* @min 100
|
||||
* @max 2000
|
||||
* @value 100 100 Hz
|
||||
* @value 250 250 Hz
|
||||
* @value 400 400 Hz
|
||||
* @value 800 800 Hz
|
||||
* @value 1000 1000 Hz
|
||||
* @value 2000 2000 Hz
|
||||
* @unit Hz
|
||||
* @reboot_required true
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(IMU_GYRO_RATEMAX, 400);
|
||||
|
||||
/**
|
||||
* Cutoff frequency for angular acceleration (D-Term filter)
|
||||
*
|
||||
* The cutoff frequency for the 2nd order butterworth filter used on
|
||||
* the time derivative of the measured angular velocity, also known as
|
||||
* the D-term filter in the rate controller. The D-term uses the derivative of
|
||||
* the rate and thus is the most susceptible to noise. Therefore, using
|
||||
* a D-term filter allows to increase IMU_GYRO_CUTOFF, which
|
||||
* leads to reduced control latency and permits to increase the P gains.
|
||||
*
|
||||
* A value of 0 disables the filter.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1000
|
||||
* @unit Hz
|
||||
* @increment 0.1
|
||||
* @decimal 1
|
||||
* @reboot_required false
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(IMU_DGYRO_CUTOFF, 20.0f);
|
||||
|
||||
/**
|
||||
* IMU gyro dynamic notch filtering
|
||||
*
|
||||
* Enable bank of dynamically updating notch filters.
|
||||
* Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN).
|
||||
* @group Sensors
|
||||
* @min 0
|
||||
* @max 3
|
||||
* @bit 0 ESC RPM
|
||||
* @bit 1 FFT
|
||||
*/
|
||||
PARAM_DEFINE_INT32(IMU_GYRO_DNF_EN, 0);
|
||||
|
||||
/**
|
||||
* IMU gyro ESC notch filter bandwidth
|
||||
*
|
||||
* Bandwidth per notch filter when using dynamic notch filtering with ESC RPM.
|
||||
*
|
||||
* @group Sensors
|
||||
* @unit Hz
|
||||
* @increment 0.1
|
||||
* @decimal 1
|
||||
* @min 5
|
||||
* @max 30
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(IMU_GYRO_DNF_BW, 15.f);
|
||||
|
||||
/**
|
||||
* IMU gyro dynamic notch filter harmonics
|
||||
*
|
||||
* ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering.
|
||||
*
|
||||
* @group Sensors
|
||||
* @min 1
|
||||
* @max 7
|
||||
*/
|
||||
PARAM_DEFINE_INT32(IMU_GYRO_DNF_HMC, 3);
|
||||
|
||||
/**
|
||||
* IMU gyro dynamic notch filter minimum frequency
|
||||
*
|
||||
* Minimum notch filter frequency in Hz.
|
||||
*
|
||||
* @group Sensors
|
||||
* @unit Hz
|
||||
* @increment 0.1
|
||||
* @decimal 1
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(IMU_GYRO_DNF_MIN, 25.f);
|
||||
@ -1,74 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* IMU integration rate.
|
||||
*
|
||||
* The rate at which raw IMU data is integrated to produce delta angles and delta velocities.
|
||||
* Recommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2).
|
||||
*
|
||||
* @min 100
|
||||
* @max 1000
|
||||
* @value 100 100 Hz
|
||||
* @value 200 200 Hz
|
||||
* @value 250 250 Hz
|
||||
* @value 400 400 Hz
|
||||
* @unit Hz
|
||||
* @reboot_required true
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(IMU_INTEG_RATE, 200);
|
||||
|
||||
/**
|
||||
* IMU auto calibration
|
||||
*
|
||||
* Automatically initialize IMU (accel/gyro) calibration from bias estimates if available.
|
||||
*
|
||||
* @boolean
|
||||
*
|
||||
* @category system
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_IMU_AUTOCAL, 1);
|
||||
|
||||
/**
|
||||
* IMU notify clipping
|
||||
*
|
||||
* Notify the user if the IMU is clipping
|
||||
*
|
||||
* @boolean
|
||||
*
|
||||
* @category system
|
||||
* @group Sensors
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_IMU_CLPNOTI, 1);
|
||||
Loading…
x
Reference in New Issue
Block a user