#include <Heat_Pwm.h>
Definition at line 23 of file Heat_Pwm.h.
◆ HeatPwm()
HeatPwm::HeatPwm |
( |
uint8_t |
pwm_num, |
|
|
float |
Kp, |
|
|
float |
Ki, |
|
|
uint32_t |
period_ns |
|
) |
| |
◆ set_imu_target_temp()
void HeatPwm::set_imu_target_temp |
( |
int8_t * |
target | ) |
|
|
overridevirtual |
◆ set_imu_temp()
void HeatPwm::set_imu_temp |
( |
float |
current | ) |
|
|
overridevirtual |
◆ _Ki
float Linux::HeatPwm::_Ki |
|
private |
◆ _Kp
float Linux::HeatPwm::_Kp |
|
private |
◆ _last_temp_update
uint32_t Linux::HeatPwm::_last_temp_update = 0 |
|
private |
◆ _period_ns
uint32_t Linux::HeatPwm::_period_ns |
|
private |
◆ _pwm
◆ _sum_error
float Linux::HeatPwm::_sum_error |
|
private |
◆ _target
int8_t* Linux::HeatPwm::_target = nullptr |
|
private |
The documentation for this class was generated from the following files: