mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
PWM_Sysfs: add an init method to do hal dependent stuff.
When PWM_Sysfs_Base constructor is called, global variable hal may not have been initialized resulting in NULL dereferencing error. Move hal dependent stuff from contructor to init method.
This commit is contained in:
parent
91c4bf470f
commit
0fa441a8a5
@ -38,6 +38,7 @@ HeatPwm::HeatPwm(uint8_t pwm_num, float Kp, float Ki, uint32_t period_ns) :
|
||||
_period_ns(period_ns)
|
||||
{
|
||||
_pwm = new PWM_Sysfs_Bebop(pwm_num);
|
||||
_pwm->init();
|
||||
_pwm->set_period(_period_ns);
|
||||
_pwm->set_duty_cycle(0);
|
||||
_pwm->enable(true);
|
||||
|
@ -76,6 +76,7 @@ void OpticalFlow_Onboard::init(AP_HAL::OpticalFlow::Gyro_Cb get_gyro)
|
||||
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
||||
_pwm = new PWM_Sysfs_Bebop(BEBOP_CAMV_PWM);
|
||||
_pwm->init();
|
||||
_pwm->set_freq(BEBOP_CAMV_PWM_FREQ);
|
||||
_pwm->enable(true);
|
||||
|
||||
|
@ -38,6 +38,20 @@ PWM_Sysfs_Base::PWM_Sysfs_Base(char* export_path, char* polarity_path,
|
||||
, _enable_path(enable_path)
|
||||
, _duty_path(duty_path)
|
||||
, _period_path(period_path)
|
||||
, _channel(channel)
|
||||
{
|
||||
}
|
||||
|
||||
PWM_Sysfs_Base::~PWM_Sysfs_Base()
|
||||
{
|
||||
::close(_duty_cycle_fd);
|
||||
|
||||
free(_polarity_path);
|
||||
free(_enable_path);
|
||||
free(_period_path);
|
||||
}
|
||||
|
||||
void PWM_Sysfs_Base::init()
|
||||
{
|
||||
if (_export_path == nullptr || _enable_path == nullptr ||
|
||||
_period_path == nullptr || _duty_path == nullptr) {
|
||||
@ -48,7 +62,7 @@ PWM_Sysfs_Base::PWM_Sysfs_Base(char* export_path, char* polarity_path,
|
||||
/* Not checking the return of write_file since it will fail if
|
||||
* the pwm has already been exported
|
||||
*/
|
||||
Util::from(hal.util)->write_file(_export_path, "%u", channel);
|
||||
Util::from(hal.util)->write_file(_export_path, "%u", _channel);
|
||||
free(_export_path);
|
||||
|
||||
_duty_cycle_fd = ::open(_duty_path, O_RDWR | O_CLOEXEC);
|
||||
@ -59,15 +73,6 @@ PWM_Sysfs_Base::PWM_Sysfs_Base(char* export_path, char* polarity_path,
|
||||
free(_duty_path);
|
||||
}
|
||||
|
||||
PWM_Sysfs_Base::~PWM_Sysfs_Base()
|
||||
{
|
||||
::close(_duty_cycle_fd);
|
||||
|
||||
free(_polarity_path);
|
||||
free(_enable_path);
|
||||
free(_period_path);
|
||||
}
|
||||
|
||||
void PWM_Sysfs_Base::enable(bool value)
|
||||
{
|
||||
if (Util::from(hal.util)->write_file(_enable_path, "%u", value) < 0) {
|
||||
|
@ -16,6 +16,7 @@ public:
|
||||
INVERSE = 1,
|
||||
};
|
||||
|
||||
void init();
|
||||
void enable(bool value);
|
||||
bool is_enabled();
|
||||
void set_period(uint32_t nsec_period);
|
||||
@ -46,6 +47,7 @@ protected:
|
||||
private:
|
||||
uint32_t _nsec_duty_cycle_value = 0;
|
||||
int _duty_cycle_fd = -1;
|
||||
uint8_t _channel;
|
||||
char *_export_path = nullptr;
|
||||
char *_polarity_path = nullptr;
|
||||
char *_enable_path = nullptr;
|
||||
|
@ -51,6 +51,7 @@ void RCOutput_Sysfs::init()
|
||||
if (!_pwm_channels[i]) {
|
||||
AP_HAL::panic("RCOutput_Sysfs_PWM: Unable to setup PWM pin.");
|
||||
}
|
||||
_pwm_channels[i]->init();
|
||||
_pwm_channels[i]->enable(false);
|
||||
|
||||
/* Set the initial frequency */
|
||||
|
Loading…
Reference in New Issue
Block a user