123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109 |
- #pragma once
- #include <AP_HAL/AP_HAL.h>
- #include <AP_RPM/AP_RPM.h>
- class AP_ICEngine {
- public:
-
- AP_ICEngine(const AP_RPM &_rpm);
- static const struct AP_Param::GroupInfo var_info[];
-
- void update(void);
-
- bool throttle_override(uint8_t &percent);
- enum ICE_State {
- ICE_OFF=0,
- ICE_START_HEIGHT_DELAY=1,
- ICE_START_DELAY=2,
- ICE_STARTING=3,
- ICE_RUNNING=4
- };
-
- ICE_State get_state(void) const { return state; }
-
- bool engine_control(float start_control, float cold_start, float height_delay);
-
- static AP_ICEngine *get_singleton() { return _singleton; }
- private:
- static AP_ICEngine *_singleton;
- const AP_RPM &rpm;
- enum ICE_State state;
-
- AP_Int8 enable;
-
- AP_Int8 start_chan;
-
- AP_Int8 rpm_instance;
-
-
- AP_Float starter_time;
-
- AP_Float starter_delay;
-
-
- AP_Int16 pwm_ignition_on;
- AP_Int16 pwm_ignition_off;
- AP_Int16 pwm_starter_on;
- AP_Int16 pwm_starter_off;
-
-
- AP_Int32 rpm_threshold;
-
-
- uint32_t starter_start_time_ms;
-
- uint32_t starter_last_run_ms;
-
- AP_Int8 start_percent;
-
- AP_Int8 idle_percent;
-
- float initial_height;
-
- float height_required;
-
- bool height_pending:1;
- };
- namespace AP {
- AP_ICEngine *ice();
- };
|