2015-09-25 11:07:59 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
2017-10-17 15:09:10 -03:00
|
|
|
#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
|
|
|
|
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <cmath>
|
2015-09-25 11:07:59 -03:00
|
|
|
#include <fcntl.h>
|
|
|
|
#include <linux/limits.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <stdio.h>
|
2015-09-25 11:07:59 -03:00
|
|
|
#include <stdlib.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <string.h>
|
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
|
2015-09-25 11:07:59 -03:00
|
|
|
#include "Heat_Pwm.h"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
using namespace Linux;
|
|
|
|
|
2016-06-15 05:01:14 -03:00
|
|
|
HeatPwm::HeatPwm(uint8_t pwm_num, float Kp, float Ki, uint32_t period_ns) :
|
2015-09-25 11:07:59 -03:00
|
|
|
_Kp(Kp),
|
|
|
|
_Ki(Ki),
|
2016-06-15 05:01:14 -03:00
|
|
|
_period_ns(period_ns)
|
2015-09-25 11:07:59 -03:00
|
|
|
{
|
2017-10-17 15:09:10 -03:00
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
|
|
|
|
_pwm = new PWM_Sysfs(0, pwm_num);
|
|
|
|
hal.gpio->pinMode(26, HAL_GPIO_OUTPUT);
|
|
|
|
hal.gpio->write(26, 1);
|
|
|
|
#else
|
2015-11-27 06:36:00 -04:00
|
|
|
_pwm = new PWM_Sysfs_Bebop(pwm_num);
|
2017-10-17 15:09:10 -03:00
|
|
|
#endif
|
2016-10-27 04:46:08 -03:00
|
|
|
_pwm->init();
|
2015-11-27 06:36:00 -04:00
|
|
|
_pwm->set_period(_period_ns);
|
|
|
|
_pwm->set_duty_cycle(0);
|
|
|
|
_pwm->enable(true);
|
2015-09-25 11:07:59 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void HeatPwm::set_imu_temp(float current)
|
2015-09-25 11:07:59 -03:00
|
|
|
{
|
|
|
|
float error, output;
|
|
|
|
|
2016-06-15 05:01:14 -03:00
|
|
|
if (_target == nullptr) {
|
|
|
|
// not configured
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-11-19 23:10:58 -04:00
|
|
|
if (AP_HAL::millis() - _last_temp_update < 5) {
|
2015-09-25 11:07:59 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* minimal PI algo without dt */
|
2016-06-15 05:01:14 -03:00
|
|
|
error = ((float)*_target) - current;
|
2015-09-25 11:07:59 -03:00
|
|
|
/* Don't accumulate errors if the integrated error is superior
|
|
|
|
* to the max duty cycle(pwm_period)
|
|
|
|
*/
|
|
|
|
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;
|
|
|
|
}
|
|
|
|
|
2015-11-27 06:36:00 -04:00
|
|
|
_pwm->set_duty_cycle(output);
|
2015-11-19 23:10:58 -04:00
|
|
|
_last_temp_update = AP_HAL::millis();
|
2016-06-08 21:56:06 -03:00
|
|
|
// printf("target %.1f current %.1f out %.2f\n", _target, current, output);
|
2015-09-25 11:07:59 -03:00
|
|
|
}
|
|
|
|
|
2016-06-15 05:01:14 -03:00
|
|
|
void HeatPwm::set_imu_target_temp(int8_t *target)
|
|
|
|
{
|
|
|
|
_target = target;
|
|
|
|
}
|
|
|
|
|
2015-09-25 11:07:59 -03:00
|
|
|
#endif
|