mirror of https://github.com/ArduPilot/ardupilot
SITL: param use baro temp_board_offset instead of temp_flight
This commit is contained in:
parent
695ad5b4f6
commit
e8dcdd60c5
|
@ -112,5 +112,11 @@ void MS5611::get_pressure_temperature_readings(float &P_Pa, float &Temp_C)
|
|||
AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta);
|
||||
P_Pa = SSL_AIR_PRESSURE * delta;
|
||||
|
||||
Temp_C = (30.0 + C_TO_KELVIN) * theta - C_TO_KELVIN; // Assume 30 degrees at sea level - converted to degrees Kelvin
|
||||
Temp_C = (SSL_AIR_TEMPERATURE * theta - C_TO_KELVIN) + AP::sitl()->temp_board_offset;
|
||||
|
||||
// TO DO add in temperature adjustment by inheritting from AP_Baro_SITL_Generic?
|
||||
// AP_Baro_SITL::temperature_adjustment(P_Pa, Temp_C);
|
||||
|
||||
// TO DO add in wind correction by inheritting from AP_Baro_SITL_Generic?
|
||||
// P_Pa += AP_Baro_SITL::wind_pressure_correction(instance);
|
||||
}
|
||||
|
|
|
@ -85,7 +85,7 @@ const AP_Param::GroupInfo SIM::var_info[] = {
|
|||
// second table of user settable parameters for SITL.
|
||||
const AP_Param::GroupInfo SIM::var_info2[] = {
|
||||
AP_GROUPINFO("TEMP_START", 1, SIM, temp_start, 25),
|
||||
AP_GROUPINFO("TEMP_FLIGHT", 2, SIM, temp_flight, 35),
|
||||
AP_GROUPINFO("TEMP_BRD_OFF", 2, SIM, temp_board_offset, 20),
|
||||
AP_GROUPINFO("TEMP_TCONST", 3, SIM, temp_tconst, 30),
|
||||
AP_GROUPINFO("TEMP_BFACTOR", 4, SIM, temp_baro_factor, 0),
|
||||
|
||||
|
|
|
@ -308,10 +308,10 @@ public:
|
|||
AP_Vector3f optflow_pos_offset; // XYZ position of the optical flow sensor focal point relative to the body frame origin (m)
|
||||
AP_Vector3f vicon_pos_offset; // XYZ position of the vicon sensor relative to the body frame origin (m)
|
||||
|
||||
// temperature control
|
||||
AP_Float temp_start;
|
||||
AP_Float temp_flight;
|
||||
AP_Float temp_tconst;
|
||||
// barometer temperature control
|
||||
AP_Float temp_start; // [deg C] Barometer start temperature
|
||||
AP_Float temp_board_offset; // [deg C] Barometer board temperature offset from atmospheric temperature
|
||||
AP_Float temp_tconst; // [deg C] Barometer warmup temperature time constant
|
||||
AP_Float temp_baro_factor;
|
||||
|
||||
AP_Int8 thermal_scenario;
|
||||
|
|
|
@ -692,7 +692,7 @@ SIM_SONAR_RND,0
|
|||
SIM_SONAR_SCALE,12.1212
|
||||
SIM_SPEEDUP,-1
|
||||
SIM_TEMP_BFACTOR,0
|
||||
SIM_TEMP_FLIGHT,35
|
||||
SIM_TEMP_BRD_OFF,20
|
||||
SIM_TEMP_START,25
|
||||
SIM_TEMP_TCONST,30
|
||||
SIM_TERRAIN,1
|
||||
|
|
|
@ -723,7 +723,7 @@ SIM_SPR_ENABLE,0
|
|||
SIM_SPR_PUMP,-1
|
||||
SIM_SPR_SPIN,-1
|
||||
SIM_TEMP_BFACTOR,0
|
||||
SIM_TEMP_FLIGHT,35
|
||||
SIM_TEMP_BRD_OFF,20
|
||||
SIM_TEMP_START,25
|
||||
SIM_TEMP_TCONST,30
|
||||
SIM_TERRAIN,1
|
||||
|
|
Loading…
Reference in New Issue