Heat_Pwm.cpp 2.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include <AP_HAL/AP_HAL.h>
  14. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
  15. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
  16. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
  17. #include <cmath>
  18. #include <fcntl.h>
  19. #include <linux/limits.h>
  20. #include <stdio.h>
  21. #include <stdlib.h>
  22. #include <string.h>
  23. #include <sys/stat.h>
  24. #include <sys/types.h>
  25. #include <unistd.h>
  26. #include "Heat_Pwm.h"
  27. #include "GPIO.h"
  28. extern const AP_HAL::HAL& hal;
  29. using namespace Linux;
  30. HeatPwm::HeatPwm(uint8_t pwm_num, float Kp, float Ki, uint32_t period_ns) :
  31. _Kp(Kp),
  32. _Ki(Ki),
  33. _period_ns(period_ns)
  34. {
  35. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
  36. _pwm = new PWM_Sysfs(0, pwm_num);
  37. hal.gpio->pinMode(EDGE_GPIO_HEAT_ENABLE, HAL_GPIO_OUTPUT);
  38. hal.gpio->write(EDGE_GPIO_HEAT_ENABLE, 1);
  39. #else
  40. _pwm = new PWM_Sysfs_Bebop(pwm_num);
  41. #endif
  42. _pwm->init();
  43. _pwm->set_period(_period_ns);
  44. _pwm->set_duty_cycle(0);
  45. _pwm->enable(true);
  46. }
  47. void HeatPwm::set_imu_temp(float current)
  48. {
  49. float error, output;
  50. if (_target == nullptr) {
  51. // not configured
  52. return;
  53. }
  54. if (AP_HAL::millis() - _last_temp_update < 5) {
  55. return;
  56. }
  57. /* minimal PI algo without dt */
  58. error = ((float)*_target) - current;
  59. /* Don't accumulate errors if the integrated error is superior
  60. * to the max duty cycle(pwm_period)
  61. */
  62. if ((fabsf(_sum_error) * _Ki < _period_ns)) {
  63. _sum_error = _sum_error + error;
  64. }
  65. output = _Kp*error + _Ki * _sum_error;
  66. if (output > _period_ns) {
  67. output = _period_ns;
  68. } else if (output < 0) {
  69. output = 0;
  70. }
  71. _pwm->set_duty_cycle(output);
  72. _last_temp_update = AP_HAL::millis();
  73. // printf("target %.1f current %.1f out %.2f\n", _target, current, output);
  74. }
  75. void HeatPwm::set_imu_target_temp(int8_t *target)
  76. {
  77. _target = target;
  78. }
  79. #endif