mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
SITL: add tests for ICE Planes
This commit is contained in:
parent
61e65ca5f2
commit
db59117b83
@ -30,6 +30,9 @@ float ICEngine::update(const struct sitl_input &input)
|
|||||||
bool have_choke = choke_servo>=0;
|
bool have_choke = choke_servo>=0;
|
||||||
bool have_starter = starter_servo>=0;
|
bool have_starter = starter_servo>=0;
|
||||||
float throttle_demand = (input.servos[throttle_servo]-1000) * 0.001f;
|
float throttle_demand = (input.servos[throttle_servo]-1000) * 0.001f;
|
||||||
|
if (throttle_reversed) {
|
||||||
|
throttle_demand = 1 - throttle_demand;
|
||||||
|
}
|
||||||
|
|
||||||
state.ignition = have_ignition?input.servos[ignition_servo]>1700:true;
|
state.ignition = have_ignition?input.servos[ignition_servo]>1700:true;
|
||||||
state.choke = have_choke?input.servos[choke_servo]>1700:false;
|
state.choke = have_choke?input.servos[choke_servo]>1700:false;
|
||||||
|
@ -30,12 +30,13 @@ public:
|
|||||||
const int8_t starter_servo;
|
const int8_t starter_servo;
|
||||||
const float slew_rate; // percent-per-second
|
const float slew_rate; // percent-per-second
|
||||||
|
|
||||||
ICEngine(uint8_t _throttle, int8_t _choke, int8_t _ignition, int8_t _starter, float _slew_rate) :
|
ICEngine(uint8_t _throttle, int8_t _choke, int8_t _ignition, int8_t _starter, float _slew_rate, bool _throttle_reversed) :
|
||||||
throttle_servo(_throttle),
|
throttle_servo(_throttle),
|
||||||
choke_servo(_choke),
|
choke_servo(_choke),
|
||||||
ignition_servo(_ignition),
|
ignition_servo(_ignition),
|
||||||
starter_servo(_starter),
|
starter_servo(_starter),
|
||||||
slew_rate(_slew_rate)
|
slew_rate(_slew_rate),
|
||||||
|
throttle_reversed(_throttle_reversed)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
// update motor state
|
// update motor state
|
||||||
@ -54,5 +55,6 @@ private:
|
|||||||
uint8_t value;
|
uint8_t value;
|
||||||
} state, last_state;
|
} state, last_state;
|
||||||
bool overheat:1;
|
bool overheat:1;
|
||||||
|
bool throttle_reversed;
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
@ -115,7 +115,8 @@ protected:
|
|||||||
choke_servo,
|
choke_servo,
|
||||||
ignition_servo,
|
ignition_servo,
|
||||||
starter_servo,
|
starter_servo,
|
||||||
slewrate
|
slewrate,
|
||||||
|
true
|
||||||
};
|
};
|
||||||
|
|
||||||
float liftCoeff(float alpha) const;
|
float liftCoeff(float alpha) const;
|
||||||
|
Loading…
Reference in New Issue
Block a user