AP_HAL_Linux: Adapt Heat_Pwm to use PWM_Sysfs

Only compiled on Bebop, the constructor will need to be modified to
pass the pwm chip number and to create a PWM_Sysfs instead of a PWM_Sysfs_Bebop
in case it is used on a mainline linux board
This commit is contained in:
Julien BERAUD 2015-11-27 11:36:00 +01:00 committed by Andrew Tridgell
parent 0fa362ff5c
commit 88236821c0
4 changed files with 12 additions and 79 deletions

View File

@ -207,7 +207,7 @@
#define HAL_BARO_MS5607_I2C_ADDR 0x77 #define HAL_BARO_MS5607_I2C_ADDR 0x77
#define HAL_BARO_DEFAULT HAL_BARO_MS5607 #define HAL_BARO_DEFAULT HAL_BARO_MS5607
#define HAL_UTILS_HEAT HAL_LINUX_HEAT_PWM #define HAL_UTILS_HEAT HAL_LINUX_HEAT_PWM
#define HAL_LINUX_HEAT_PWM_SYSFS_DIR "/sys/class/pwm/pwm_6" #define HAL_LINUX_HEAT_PWM_NUM 6
#define HAL_LINUX_HEAT_KP 20000 #define HAL_LINUX_HEAT_KP 20000
#define HAL_LINUX_HEAT_KI 6 #define HAL_LINUX_HEAT_KI 6
#define HAL_LINUX_HEAT_PERIOD_NS 125000 #define HAL_LINUX_HEAT_PERIOD_NS 125000

View File

@ -30,60 +30,18 @@
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
#define HEAT_PWM_DUTY "duty_ns"
#define HEAT_PWM_PERIOD "period_ns"
#define HEAT_PWM_RUN "run"
using namespace Linux; using namespace Linux;
/* HeatPwm::HeatPwm(uint8_t pwm_num, float Kp, float Ki, uint32_t period_ns, float target) :
* Constructor :
* argument : pwm_sysfs_path is the path to the pwm directory,
* i.e /sys/class/pwm/pwm_6 on the bebop
*/
HeatPwm::HeatPwm(const char* pwm_sysfs_path, float Kp, float Ki, uint32_t period_ns, float target) :
_Kp(Kp), _Kp(Kp),
_Ki(Ki), _Ki(Ki),
_period_ns(period_ns), _period_ns(period_ns),
_target(target) _target(target)
{ {
char *duty_path; _pwm = new PWM_Sysfs_Bebop(pwm_num);
char *period_path; _pwm->set_period(_period_ns);
char *run_path; _pwm->set_duty_cycle(0);
_pwm->enable(true);
if (asprintf(&duty_path, "%s/%s", pwm_sysfs_path, HEAT_PWM_DUTY) == -1) {
AP_HAL::panic("HeatPwm not enough memory\n");
}
_duty_fd = open(duty_path, O_RDWR);
if (_duty_fd == -1) {
perror("opening duty");
AP_HAL::panic("Error Initializing Pwm heat\n");
}
free(duty_path);
if (asprintf(&period_path, "%s/%s", pwm_sysfs_path, HEAT_PWM_PERIOD) == -1) {
AP_HAL::panic("HeatPwm not enough memory\n");
}
_period_fd = open(period_path, O_RDWR);
if (_period_fd == -1) {
perror("opening period");
AP_HAL::panic("Error Initializing Pwm heat\n");
}
free(period_path);
if (asprintf(&run_path, "%s/%s", pwm_sysfs_path, HEAT_PWM_RUN) == -1) {
AP_HAL::panic("HeatPwm not enough memory\n");
}
_run_fd = open(run_path, O_RDWR);
if (_run_fd == -1) {
perror("opening run");
AP_HAL::panic("Error Initializing Pwm heat\n");
}
free(run_path);
_set_period(_period_ns);
_set_duty(0);
_set_run();
} }
void HeatPwm::set_imu_temp(float current) void HeatPwm::set_imu_temp(float current)
@ -111,29 +69,8 @@ void HeatPwm::set_imu_temp(float current)
output = 0; output = 0;
} }
_set_duty(output); _pwm->set_duty_cycle(output);
_last_temp_update = AP_HAL::millis(); _last_temp_update = AP_HAL::millis();
} }
void HeatPwm::_set_duty(uint32_t duty)
{
if (dprintf(_duty_fd, "0x%x", duty) < 0) {
perror("pwm set_duty");
}
}
void HeatPwm::_set_period(uint32_t period)
{
if (dprintf(_period_fd, "0x%x", period) < 0) {
perror("pwm set_period");
}
}
void HeatPwm::_set_run()
{
if (dprintf(_run_fd, "1") < 0) {
perror("pwm set_run");
}
}
#endif #endif

View File

@ -18,26 +18,22 @@
#define __HEAT_PWM_H__ #define __HEAT_PWM_H__
#include "AP_HAL_Linux.h" #include "AP_HAL_Linux.h"
#include "PWM_Sysfs.h"
#include "Heat.h" #include "Heat.h"
class Linux::HeatPwm : public Linux::Heat { class Linux::HeatPwm : public Linux::Heat {
public: public:
HeatPwm(const char* pwm_sysfs_path, float Kp, float Ki,uint32_t period_ns, float target); HeatPwm(uint8_t pwm_num, float Kp, float Ki,
uint32_t period_ns, float target);
void set_imu_temp(float current)override; void set_imu_temp(float current)override;
private: private:
int _duty_fd = -1; PWM_Sysfs_Base *_pwm;
int _period_fd = -1;
int _run_fd = -1;
uint32_t _last_temp_update = 0; uint32_t _last_temp_update = 0;
float _Kp; float _Kp;
float _Ki; float _Ki;
uint32_t _period_ns; uint32_t _period_ns;
float _sum_error; float _sum_error;
float _target; float _target;
void _set_duty(uint32_t duty);
void _set_period(uint32_t period);
void _set_run();
}; };
#endif #endif

View File

@ -26,7 +26,7 @@ void Util::init(int argc, char * const *argv) {
#ifdef HAL_UTILS_HEAT #ifdef HAL_UTILS_HEAT
#if HAL_UTILS_HEAT == HAL_LINUX_HEAT_PWM #if HAL_UTILS_HEAT == HAL_LINUX_HEAT_PWM
_heat = new Linux::HeatPwm(HAL_LINUX_HEAT_PWM_SYSFS_DIR, _heat = new Linux::HeatPwm(HAL_LINUX_HEAT_PWM_NUM,
HAL_LINUX_HEAT_KP, HAL_LINUX_HEAT_KP,
HAL_LINUX_HEAT_KI, HAL_LINUX_HEAT_KI,
HAL_LINUX_HEAT_PERIOD_NS, HAL_LINUX_HEAT_PERIOD_NS,