SITL: TSYS01 add sim temperature based on altitude
This commit is contained in:
parent
ed5a0557ca
commit
3fdf87a6c7
@ -175,9 +175,10 @@ void SITL::TSYS01::update(const class Aircraft &aircraft)
|
||||
break;
|
||||
case State::CONVERTING:
|
||||
if (time_in_state_ms() > 5) {
|
||||
if (!is_equal(last_temperature, some_temperature)) {
|
||||
last_temperature = some_temperature;
|
||||
adc = calculate_adc(some_temperature);
|
||||
const float temperature = get_sim_temperature();
|
||||
if (!is_equal(last_temperature, temperature)) {
|
||||
last_temperature = temperature;
|
||||
adc = calculate_adc(temperature);
|
||||
}
|
||||
set_state(State::CONVERTED);
|
||||
}
|
||||
@ -187,3 +188,14 @@ void SITL::TSYS01::update(const class Aircraft &aircraft)
|
||||
}
|
||||
}
|
||||
|
||||
float SITL::TSYS01::get_sim_temperature() const
|
||||
{
|
||||
float sim_alt = AP::sitl()->state.altitude;
|
||||
sim_alt += 2 * rand_float();
|
||||
|
||||
float sigma, delta, theta;
|
||||
AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta);
|
||||
|
||||
// To Do: Add a sensor board temperature offset parameter
|
||||
return (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0;
|
||||
}
|
||||
|
@ -20,7 +20,6 @@ public:
|
||||
private:
|
||||
|
||||
// should be a call on aircraft:
|
||||
float some_temperature = 26.5;
|
||||
float last_temperature = -1000.0f;
|
||||
|
||||
enum class State {
|
||||
@ -42,6 +41,8 @@ private:
|
||||
return AP_HAL::millis() - state_start_time_ms;
|
||||
}
|
||||
|
||||
float get_sim_temperature() const;
|
||||
|
||||
float temperature_for_adc(uint32_t adc) const;
|
||||
uint32_t calculate_adc(float temperature) const;
|
||||
uint32_t adc;
|
||||
|
Loading…
Reference in New Issue
Block a user