mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-06 16:08:28 -04:00
AP_BoardConfig: added get_heater_duty_cycle()
This commit is contained in:
parent
5920c52285
commit
1097d04e5d
@ -189,6 +189,11 @@ public:
|
|||||||
|
|
||||||
#if HAL_HAVE_IMU_HEATER
|
#if HAL_HAVE_IMU_HEATER
|
||||||
void set_imu_temp(float current_temp_c);
|
void set_imu_temp(float current_temp_c);
|
||||||
|
|
||||||
|
// heater duty cycle is as a percentage (0 to 100)
|
||||||
|
float get_heater_duty_cycle(void) const {
|
||||||
|
return heater.output;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
Loading…
Reference in New Issue
Block a user