HAL_PX4: use write() to /dev/pwm_output for servo output
this lowest the cost of PWM output a lot, but relies on the new I2C based IO firmware
This commit is contained in:
parent
9178022a73
commit
8f2f4b1bc5
@ -18,6 +18,7 @@ using namespace PX4;
|
|||||||
|
|
||||||
void PX4RCOutput::init(void* unused)
|
void PX4RCOutput::init(void* unused)
|
||||||
{
|
{
|
||||||
|
_perf_rcout = perf_alloc(PC_ELAPSED, "APM_rcout");
|
||||||
_pwm_fd = open(PWM_OUTPUT_DEVICE_PATH, O_RDWR);
|
_pwm_fd = open(PWM_OUTPUT_DEVICE_PATH, O_RDWR);
|
||||||
if (_pwm_fd == -1) {
|
if (_pwm_fd == -1) {
|
||||||
hal.scheduler->panic("Unable to open " PWM_OUTPUT_DEVICE_PATH);
|
hal.scheduler->panic("Unable to open " PWM_OUTPUT_DEVICE_PATH);
|
||||||
@ -67,9 +68,12 @@ void PX4RCOutput::write(uint8_t ch, uint16_t period_us)
|
|||||||
if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
|
if (ch >= PX4_NUM_OUTPUT_CHANNELS) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
if (ch > _max_channel) {
|
||||||
|
_max_channel = ch;
|
||||||
|
}
|
||||||
if (period_us != _period[ch]) {
|
if (period_us != _period[ch]) {
|
||||||
ioctl(_pwm_fd, PWM_SERVO_SET(ch), (unsigned long)period_us);
|
|
||||||
_period[ch] = period_us;
|
_period[ch] = period_us;
|
||||||
|
_need_update = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -95,4 +99,23 @@ void PX4RCOutput::read(uint16_t* period_us, uint8_t len)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PX4RCOutput::_timer_tick(void)
|
||||||
|
{
|
||||||
|
uint32_t now = hal.scheduler->micros();
|
||||||
|
|
||||||
|
// always send at least at 20Hz, otherwise the IO board may think
|
||||||
|
// we are dead
|
||||||
|
if (now - _last_output > 50000) {
|
||||||
|
_need_update = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (_need_update && _pwm_fd != -1) {
|
||||||
|
_need_update = false;
|
||||||
|
perf_begin(_perf_rcout);
|
||||||
|
::write(_pwm_fd, _period, _max_channel*sizeof(_period[0]));
|
||||||
|
perf_end(_perf_rcout);
|
||||||
|
_last_output = now;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
@ -3,6 +3,7 @@
|
|||||||
#define __AP_HAL_PX4_RCOUTPUT_H__
|
#define __AP_HAL_PX4_RCOUTPUT_H__
|
||||||
|
|
||||||
#include <AP_HAL_PX4.h>
|
#include <AP_HAL_PX4.h>
|
||||||
|
#include <systemlib/perf_counter.h>
|
||||||
|
|
||||||
#define PX4_NUM_OUTPUT_CHANNELS 16
|
#define PX4_NUM_OUTPUT_CHANNELS 16
|
||||||
|
|
||||||
@ -21,10 +22,16 @@ public:
|
|||||||
uint16_t read(uint8_t ch);
|
uint16_t read(uint8_t ch);
|
||||||
void read(uint16_t* period_us, uint8_t len);
|
void read(uint16_t* period_us, uint8_t len);
|
||||||
|
|
||||||
|
void _timer_tick(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
int _pwm_fd;
|
int _pwm_fd;
|
||||||
uint16_t _freq_hz;
|
uint16_t _freq_hz;
|
||||||
uint16_t _period[PX4_NUM_OUTPUT_CHANNELS];
|
uint16_t _period[PX4_NUM_OUTPUT_CHANNELS];
|
||||||
|
volatile uint8_t _max_channel;
|
||||||
|
volatile bool _need_update;
|
||||||
|
perf_counter_t _perf_rcout;
|
||||||
|
uint32_t _last_output;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __AP_HAL_PX4_RCOUTPUT_H__
|
#endif // __AP_HAL_PX4_RCOUTPUT_H__
|
||||||
|
@ -18,6 +18,7 @@
|
|||||||
|
|
||||||
#include "UARTDriver.h"
|
#include "UARTDriver.h"
|
||||||
#include "Storage.h"
|
#include "Storage.h"
|
||||||
|
#include "RCOutput.h"
|
||||||
|
|
||||||
using namespace PX4;
|
using namespace PX4;
|
||||||
|
|
||||||
@ -190,6 +191,9 @@ void *PX4Scheduler::_timer_thread(void)
|
|||||||
perf_begin(_perf_timers);
|
perf_begin(_perf_timers);
|
||||||
_run_timers(true);
|
_run_timers(true);
|
||||||
perf_end(_perf_timers);
|
perf_end(_perf_timers);
|
||||||
|
|
||||||
|
// process any pending RC output requests
|
||||||
|
((PX4RCOutput *)hal.rcout)->_timer_tick();
|
||||||
}
|
}
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user