APM:Libraries
Heat_Pwm.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #include <AP_HAL/AP_HAL.h>
17 
18 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
19  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
20  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
21 
22 #include <cmath>
23 #include <fcntl.h>
24 #include <linux/limits.h>
25 #include <stdio.h>
26 #include <stdlib.h>
27 #include <string.h>
28 #include <sys/stat.h>
29 #include <sys/types.h>
30 #include <unistd.h>
31 
32 #include "Heat_Pwm.h"
33 #include "GPIO.h"
34 
35 extern const AP_HAL::HAL& hal;
36 
37 using namespace Linux;
38 
39 HeatPwm::HeatPwm(uint8_t pwm_num, float Kp, float Ki, uint32_t period_ns) :
40  _Kp(Kp),
41  _Ki(Ki),
42  _period_ns(period_ns)
43 {
44 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
45  _pwm = new PWM_Sysfs(0, pwm_num);
48 #else
49  _pwm = new PWM_Sysfs_Bebop(pwm_num);
50 #endif
51  _pwm->init();
53  _pwm->set_duty_cycle(0);
54  _pwm->enable(true);
55 }
56 
57 void HeatPwm::set_imu_temp(float current)
58 {
59  float error, output;
60 
61  if (_target == nullptr) {
62  // not configured
63  return;
64  }
65 
66  if (AP_HAL::millis() - _last_temp_update < 5) {
67  return;
68  }
69 
70  /* minimal PI algo without dt */
71  error = ((float)*_target) - current;
72  /* Don't accumulate errors if the integrated error is superior
73  * to the max duty cycle(pwm_period)
74  */
75  if ((fabsf(_sum_error) * _Ki < _period_ns)) {
77  }
78 
79  output = _Kp*error + _Ki * _sum_error;
80 
81  if (output > _period_ns) {
82  output = _period_ns;
83  } else if (output < 0) {
84  output = 0;
85  }
86 
87  _pwm->set_duty_cycle(output);
89  // printf("target %.1f current %.1f out %.2f\n", _target, current, output);
90 }
91 
92 void HeatPwm::set_imu_target_temp(int8_t *target)
93 {
94  _target = target;
95 }
96 
97 #endif
HeatPwm(uint8_t pwm_num, float Kp, float Ki, uint32_t period_ns)
Definition: Heat_Pwm.cpp:39
bool set_duty_cycle(uint32_t nsec_duty_cycle)
Definition: PWM_Sysfs.cpp:127
int8_t * _target
Definition: Heat_Pwm.h:37
virtual void write(uint8_t pin, uint8_t value)=0
float _sum_error
Definition: Heat_Pwm.h:36
uint32_t millis()
Definition: system.cpp:157
void set_period(uint32_t nsec_period)
Definition: PWM_Sysfs.cpp:95
virtual void pinMode(uint8_t pin, uint8_t output)=0
uint32_t _last_temp_update
Definition: Heat_Pwm.h:32
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
AP_HAL::GPIO * gpio
Definition: HAL.h:111
#define error(fmt, args ...)
void enable(bool value)
Definition: PWM_Sysfs.cpp:76
uint32_t _period_ns
Definition: Heat_Pwm.h:35
void set_imu_target_temp(int8_t *target) override
Definition: Heat_Pwm.cpp:92
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
PWM_Sysfs_Base * _pwm
Definition: Heat_Pwm.h:31
void set_imu_temp(float current) override
Definition: Heat_Pwm.cpp:57