AP_Baro: renamed parameters and mark pressure and temperature readonly
this is ready for BARO parameter prefix
This commit is contained in:
parent
f543c483fc
commit
d099af87b2
@ -77,72 +77,72 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = {
|
|||||||
// NOTE: Index numbers 0 and 1 were for the old integer
|
// NOTE: Index numbers 0 and 1 were for the old integer
|
||||||
// ground temperature and pressure
|
// ground temperature and pressure
|
||||||
|
|
||||||
// @Param: ABS_PRESS
|
// @Param: 1_GND_PRESS
|
||||||
// @DisplayName: Absolute Pressure
|
// @DisplayName: Ground Pressure
|
||||||
// @Description: calibrated ground pressure in Pascals
|
// @Description: calibrated ground pressure in Pascals
|
||||||
// @Units: Pa
|
// @Units: Pa
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @ReadOnly: True
|
// @ReadOnly: True
|
||||||
// @Volatile: True
|
// @Volatile: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("ABS_PRESS", 2, AP_Baro, sensors[0].ground_pressure, 0),
|
AP_GROUPINFO_FLAGS("1_GND_PRESS", 2, AP_Baro, sensors[0].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
|
||||||
|
|
||||||
// @Param: TEMP
|
// @Param: _GND_TEMP
|
||||||
// @DisplayName: ground temperature
|
// @DisplayName: ground temperature
|
||||||
// @Description: User provided ambient ground temperature in degrees Celsius. This is used to improve the calculation of the altitude the vehicle is at. This parameter is not persistent and will be reset to 0 every time the vehicle is rebooted. A value of 0 means use the internal measurement ambient temperature.
|
// @Description: User provided ambient ground temperature in degrees Celsius. This is used to improve the calculation of the altitude the vehicle is at. This parameter is not persistent and will be reset to 0 every time the vehicle is rebooted. A value of 0 means use the internal measurement ambient temperature.
|
||||||
// @Units: degC
|
// @Units: degC
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @Volatile: True
|
// @Volatile: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("TEMP", 3, AP_Baro, _user_ground_temperature, 0),
|
AP_GROUPINFO("_GND_TEMP", 3, AP_Baro, _user_ground_temperature, 0),
|
||||||
|
|
||||||
// index 4 reserved for old AP_Int8 version in legacy FRAM
|
// index 4 reserved for old AP_Int8 version in legacy FRAM
|
||||||
//AP_GROUPINFO("ALT_OFFSET", 4, AP_Baro, _alt_offset, 0),
|
//AP_GROUPINFO("ALT_OFFSET", 4, AP_Baro, _alt_offset, 0),
|
||||||
|
|
||||||
// @Param: ALT_OFFSET
|
// @Param: _ALT_OFFSET
|
||||||
// @DisplayName: altitude offset
|
// @DisplayName: altitude offset
|
||||||
// @Description: altitude offset in meters added to barometric altitude. This is used to allow for automatic adjustment of the base barometric altitude by a ground station equipped with a barometer. The value is added to the barometric altitude read by the aircraft. It is automatically reset to 0 when the barometer is calibrated on each reboot or when a preflight calibration is performed.
|
// @Description: altitude offset in meters added to barometric altitude. This is used to allow for automatic adjustment of the base barometric altitude by a ground station equipped with a barometer. The value is added to the barometric altitude read by the aircraft. It is automatically reset to 0 when the barometer is calibrated on each reboot or when a preflight calibration is performed.
|
||||||
// @Units: m
|
// @Units: m
|
||||||
// @Increment: 0.1
|
// @Increment: 0.1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("ALT_OFFSET", 5, AP_Baro, _alt_offset, 0),
|
AP_GROUPINFO("_ALT_OFFSET", 5, AP_Baro, _alt_offset, 0),
|
||||||
|
|
||||||
// @Param: PRIMARY
|
// @Param: _PRIMARY
|
||||||
// @DisplayName: Primary barometer
|
// @DisplayName: Primary barometer
|
||||||
// @Description: This selects which barometer will be the primary if multiple barometers are found
|
// @Description: This selects which barometer will be the primary if multiple barometers are found
|
||||||
// @Values: 0:FirstBaro,1:2ndBaro,2:3rdBaro
|
// @Values: 0:FirstBaro,1:2ndBaro,2:3rdBaro
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("PRIMARY", 6, AP_Baro, _primary_baro, 0),
|
AP_GROUPINFO("_PRIMARY", 6, AP_Baro, _primary_baro, 0),
|
||||||
|
|
||||||
// @Param: EXT_BUS
|
// @Param: _EXT_BUS
|
||||||
// @DisplayName: External baro bus
|
// @DisplayName: External baro bus
|
||||||
// @Description: This selects the bus number for looking for an I2C barometer. When set to -1 it will probe all external i2c buses based on the GND_PROBE_EXT parameter.
|
// @Description: This selects the bus number for looking for an I2C barometer. When set to -1 it will probe all external i2c buses based on the GND_PROBE_EXT parameter.
|
||||||
// @Values: -1:Disabled,0:Bus0,1:Bus1
|
// @Values: -1:Disabled,0:Bus0,1:Bus1
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("EXT_BUS", 7, AP_Baro, _ext_bus, -1),
|
AP_GROUPINFO("_EXT_BUS", 7, AP_Baro, _ext_bus, -1),
|
||||||
|
|
||||||
// @Param: SPEC_GRAV
|
// @Param: _SPEC_GRAV
|
||||||
// @DisplayName: Specific Gravity (For water depth measurement)
|
// @DisplayName: Specific Gravity (For water depth measurement)
|
||||||
// @Description: This sets the specific gravity of the fluid when flying an underwater ROV.
|
// @Description: This sets the specific gravity of the fluid when flying an underwater ROV.
|
||||||
// @Values: 1.0:Freshwater,1.024:Saltwater
|
// @Values: 1.0:Freshwater,1.024:Saltwater
|
||||||
AP_GROUPINFO_FRAME("SPEC_GRAV", 8, AP_Baro, _specific_gravity, 1.0, AP_PARAM_FRAME_SUB),
|
AP_GROUPINFO_FRAME("_SPEC_GRAV", 8, AP_Baro, _specific_gravity, 1.0, AP_PARAM_FRAME_SUB),
|
||||||
|
|
||||||
#if BARO_MAX_INSTANCES > 1
|
#if BARO_MAX_INSTANCES > 1
|
||||||
// @Param: ABS_PRESS2
|
// @Param: 2_GND_PRESS
|
||||||
// @DisplayName: Absolute Pressure
|
// @DisplayName: Ground Pressure
|
||||||
// @Description: calibrated ground pressure in Pascals
|
// @Description: calibrated ground pressure in Pascals
|
||||||
// @Units: Pa
|
// @Units: Pa
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @ReadOnly: True
|
// @ReadOnly: True
|
||||||
// @Volatile: True
|
// @Volatile: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("ABS_PRESS2", 9, AP_Baro, sensors[1].ground_pressure, 0),
|
AP_GROUPINFO_FLAGS("2_GND_PRESS", 9, AP_Baro, sensors[1].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
|
||||||
|
|
||||||
// Slot 10 used to be TEMP2
|
// Slot 10 used to be TEMP2
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if BARO_MAX_INSTANCES > 2
|
#if BARO_MAX_INSTANCES > 2
|
||||||
// @Param: ABS_PRESS3
|
// @Param: 3_GND_PRESS
|
||||||
// @DisplayName: Absolute Pressure
|
// @DisplayName: Absolute Pressure
|
||||||
// @Description: calibrated ground pressure in Pascals
|
// @Description: calibrated ground pressure in Pascals
|
||||||
// @Units: Pa
|
// @Units: Pa
|
||||||
@ -150,52 +150,52 @@ const AP_Param::GroupInfo AP_Baro::var_info[] = {
|
|||||||
// @ReadOnly: True
|
// @ReadOnly: True
|
||||||
// @Volatile: True
|
// @Volatile: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("ABS_PRESS3", 11, AP_Baro, sensors[2].ground_pressure, 0),
|
AP_GROUPINFO_FLAGS("3_GND_PRESS", 11, AP_Baro, sensors[2].ground_pressure, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
|
||||||
|
|
||||||
// Slot 12 used to be TEMP3
|
// Slot 12 used to be TEMP3
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @Param: FLTR_RNG
|
// @Param: _FLTR_RNG
|
||||||
// @DisplayName: Range in which sample is accepted
|
// @DisplayName: Range in which sample is accepted
|
||||||
// @Description: This sets the range around the average value that new samples must be within to be accepted. This can help reduce the impact of noise on sensors that are on long I2C cables. The value is a percentage from the average value. A value of zero disables this filter.
|
// @Description: This sets the range around the average value that new samples must be within to be accepted. This can help reduce the impact of noise on sensors that are on long I2C cables. The value is a percentage from the average value. A value of zero disables this filter.
|
||||||
// @Units: %
|
// @Units: %
|
||||||
// @Range: 0 100
|
// @Range: 0 100
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
AP_GROUPINFO("FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT),
|
AP_GROUPINFO("_FLTR_RNG", 13, AP_Baro, _filter_range, HAL_BARO_FILTER_DEFAULT),
|
||||||
|
|
||||||
#if defined(HAL_PROBE_EXTERNAL_I2C_BAROS) || defined(HAL_MSP_BARO_ENABLED)
|
#if defined(HAL_PROBE_EXTERNAL_I2C_BAROS) || defined(HAL_MSP_BARO_ENABLED)
|
||||||
// @Param: PROBE_EXT
|
// @Param: _PROBE_EXT
|
||||||
// @DisplayName: External barometers to probe
|
// @DisplayName: External barometers to probe
|
||||||
// @Description: This sets which types of external i2c barometer to look for. It is a bitmask of barometer types. The I2C buses to probe is based on GND_EXT_BUS. If GND_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in GND_EXT_BUS.
|
// @Description: This sets which types of external i2c barometer to look for. It is a bitmask of barometer types. The I2C buses to probe is based on GND_EXT_BUS. If BARO_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in GND_EXT_BUS.
|
||||||
// @Bitmask: 0:BMP085,1:BMP280,2:MS5611,3:MS5607,4:MS5637,5:FBM320,6:DPS280,7:LPS25H,8:Keller,9:MS5837,10:BMP388,11:SPL06,12:MSP
|
// @Bitmask: 0:BMP085,1:BMP280,2:MS5611,3:MS5607,4:MS5637,5:FBM320,6:DPS280,7:LPS25H,8:Keller,9:MS5837,10:BMP388,11:SPL06,12:MSP
|
||||||
// @Values: 1:BMP085,2:BMP280,4:MS5611,8:MS5607,16:MS5637,32:FBM320,64:DPS280,128:LPS25H,256:Keller,512:MS5837,1024:BMP388,2048:SPL06,4096:MSP
|
// @Values: 1:BMP085,2:BMP280,4:MS5611,8:MS5607,16:MS5637,32:FBM320,64:DPS280,128:LPS25H,256:Keller,512:MS5837,1024:BMP388,2048:SPL06,4096:MSP
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("PROBE_EXT", 14, AP_Baro, _baro_probe_ext, HAL_BARO_PROBE_EXT_DEFAULT),
|
AP_GROUPINFO("_PROBE_EXT", 14, AP_Baro, _baro_probe_ext, HAL_BARO_PROBE_EXT_DEFAULT),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @Param: BARO_ID
|
// @Param: 1_DEVID
|
||||||
// @DisplayName: Baro ID
|
// @DisplayName: Baro ID
|
||||||
// @Description: Barometer sensor ID, taking into account its type, bus and instance
|
// @Description: Barometer sensor ID, taking into account its type, bus and instance
|
||||||
// @ReadOnly: True
|
// @ReadOnly: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("BARO_ID", 15, AP_Baro, sensors[0].bus_id, 0),
|
AP_GROUPINFO_FLAGS("1_DEVID", 15, AP_Baro, sensors[0].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
|
||||||
|
|
||||||
#if BARO_MAX_INSTANCES > 1
|
#if BARO_MAX_INSTANCES > 1
|
||||||
// @Param: BARO2_ID
|
// @Param: 2_DEVID
|
||||||
// @DisplayName: Baro ID2
|
// @DisplayName: Baro ID2
|
||||||
// @Description: Barometer2 sensor ID, taking into account its type, bus and instance
|
// @Description: Barometer2 sensor ID, taking into account its type, bus and instance
|
||||||
// @ReadOnly: True
|
// @ReadOnly: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("BARO2_ID", 16, AP_Baro, sensors[1].bus_id, 0),
|
AP_GROUPINFO_FLAGS("2_DEVID", 16, AP_Baro, sensors[1].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if BARO_MAX_INSTANCES > 2
|
#if BARO_MAX_INSTANCES > 2
|
||||||
// @Param: BARO3_ID
|
// @Param: 3_DEVID
|
||||||
// @DisplayName: Baro ID3
|
// @DisplayName: Baro ID3
|
||||||
// @Description: Barometer3 sensor ID, taking into account its type, bus and instance
|
// @Description: Barometer3 sensor ID, taking into account its type, bus and instance
|
||||||
// @ReadOnly: True
|
// @ReadOnly: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("BARO3_ID", 17, AP_Baro, sensors[2].bus_id, 0),
|
AP_GROUPINFO_FLAGS("3_DEVID", 17, AP_Baro, sensors[2].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
@ -673,7 +673,7 @@ void AP_Baro::init(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
probe all the i2c barometers enabled with GND_PROBE_EXT. This is
|
probe all the i2c barometers enabled with BARO_PROBE_EXT. This is
|
||||||
used on boards without a builtin barometer
|
used on boards without a builtin barometer
|
||||||
*/
|
*/
|
||||||
void AP_Baro::_probe_i2c_barometers(void)
|
void AP_Baro::_probe_i2c_barometers(void)
|
||||||
|
@ -30,7 +30,7 @@ public:
|
|||||||
|
|
||||||
/*
|
/*
|
||||||
device driver IDs. These are used to fill in the devtype field
|
device driver IDs. These are used to fill in the devtype field
|
||||||
of the device ID, which shows up as GND_BARO_ID* parameters to
|
of the device ID, which shows up as BARO_DEVID* parameters to
|
||||||
users.
|
users.
|
||||||
*/
|
*/
|
||||||
enum DevTypes {
|
enum DevTypes {
|
||||||
@ -66,7 +66,7 @@ protected:
|
|||||||
// number of dropped samples. Not used for now, but can be usable to choose more reliable sensor
|
// number of dropped samples. Not used for now, but can be usable to choose more reliable sensor
|
||||||
uint32_t _error_count;
|
uint32_t _error_count;
|
||||||
|
|
||||||
// set bus ID of this instance, for GND_BARO_ID parameters
|
// set bus ID of this instance, for BARO_DEVID parameters
|
||||||
void set_bus_id(uint8_t instance, uint32_t id) {
|
void set_bus_id(uint8_t instance, uint32_t id) {
|
||||||
_frontend.sensors[instance].bus_id.set(int32_t(id));
|
_frontend.sensors[instance].bus_id.set(int32_t(id));
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user