12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697 |
- #include <AP_HAL/AP_HAL.h>
- #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
- CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
- CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
- #include <cmath>
- #include <fcntl.h>
- #include <linux/limits.h>
- #include <stdio.h>
- #include <stdlib.h>
- #include <string.h>
- #include <sys/stat.h>
- #include <sys/types.h>
- #include <unistd.h>
- #include "Heat_Pwm.h"
- #include "GPIO.h"
- extern const AP_HAL::HAL& hal;
- using namespace Linux;
- HeatPwm::HeatPwm(uint8_t pwm_num, float Kp, float Ki, uint32_t period_ns) :
- _Kp(Kp),
- _Ki(Ki),
- _period_ns(period_ns)
- {
- #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
- _pwm = new PWM_Sysfs(0, pwm_num);
- hal.gpio->pinMode(EDGE_GPIO_HEAT_ENABLE, HAL_GPIO_OUTPUT);
- hal.gpio->write(EDGE_GPIO_HEAT_ENABLE, 1);
- #else
- _pwm = new PWM_Sysfs_Bebop(pwm_num);
- #endif
- _pwm->init();
- _pwm->set_period(_period_ns);
- _pwm->set_duty_cycle(0);
- _pwm->enable(true);
- }
- void HeatPwm::set_imu_temp(float current)
- {
- float error, output;
- if (_target == nullptr) {
-
- return;
- }
-
- if (AP_HAL::millis() - _last_temp_update < 5) {
- return;
- }
-
- error = ((float)*_target) - current;
-
- if ((fabsf(_sum_error) * _Ki < _period_ns)) {
- _sum_error = _sum_error + error;
- }
- output = _Kp*error + _Ki * _sum_error;
- if (output > _period_ns) {
- output = _period_ns;
- } else if (output < 0) {
- output = 0;
- }
- _pwm->set_duty_cycle(output);
- _last_temp_update = AP_HAL::millis();
-
- }
- void HeatPwm::set_imu_target_temp(int8_t *target)
- {
- _target = target;
- }
- #endif
|