mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: support OneShot on PX4
this greatly lowers output latency
This commit is contained in:
parent
e24d600e78
commit
934b4dd475
|
@ -18,6 +18,12 @@ extern const AP_HAL::HAL& hal;
|
|||
|
||||
using namespace PX4;
|
||||
|
||||
/*
|
||||
enable RCOUT_DEBUG_LATENCY to measure output latency using a logic
|
||||
analyser. AUX6 will go high during the cork/push output.
|
||||
*/
|
||||
#define RCOUT_DEBUG_LATENCY 0
|
||||
|
||||
void PX4RCOutput::init()
|
||||
{
|
||||
_perf_rcout = perf_alloc(PC_ELAPSED, "APM_rcout");
|
||||
|
@ -151,6 +157,10 @@ void PX4RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
|
|||
if (freq_hz > 400) {
|
||||
freq_hz = 400;
|
||||
}
|
||||
if (freq_hz == 400) {
|
||||
// remember mask for fast channels
|
||||
_fast_channel_mask = chmask;
|
||||
}
|
||||
uint32_t primary_mask = chmask & ((1UL<<_servo_count)-1);
|
||||
uint32_t alt_mask = chmask >> _servo_count;
|
||||
if (primary_mask && _pwm_fd != -1) {
|
||||
|
@ -369,7 +379,7 @@ void PX4RCOutput::_publish_actuators(void)
|
|||
}
|
||||
}
|
||||
|
||||
void PX4RCOutput::_timer_tick(void)
|
||||
void PX4RCOutput::_send_outputs(void)
|
||||
{
|
||||
uint32_t now = AP_HAL::micros();
|
||||
|
||||
|
@ -431,4 +441,38 @@ update_pwm:
|
|||
|
||||
}
|
||||
|
||||
void PX4RCOutput::cork()
|
||||
{
|
||||
#if RCOUT_DEBUG_LATENCY
|
||||
hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(55, 1);
|
||||
#endif
|
||||
_corking = true;
|
||||
}
|
||||
|
||||
void PX4RCOutput::push()
|
||||
{
|
||||
#if RCOUT_DEBUG_LATENCY
|
||||
hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(55, 0);
|
||||
#endif
|
||||
_corking = false;
|
||||
if (_output_mode == MODE_PWM_ONESHOT) {
|
||||
// run timer immediately in oneshot mode
|
||||
_send_outputs();
|
||||
if (_fast_channel_mask != 0) {
|
||||
// this is a crude way of triggering immediate output
|
||||
set_freq(_fast_channel_mask, 400);
|
||||
set_freq(_fast_channel_mask, 0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void PX4RCOutput::_timer_tick(void)
|
||||
{
|
||||
if (_output_mode != MODE_PWM_ONESHOT) {
|
||||
_send_outputs();
|
||||
}
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
|
|
@ -28,7 +28,13 @@ public:
|
|||
_esc_pwm_min = min_pwm;
|
||||
_esc_pwm_max = max_pwm;
|
||||
}
|
||||
void cork();
|
||||
void push();
|
||||
|
||||
void set_output_mode(enum output_mode mode) override {
|
||||
_output_mode = mode;
|
||||
}
|
||||
|
||||
void _timer_tick(void);
|
||||
|
||||
private:
|
||||
|
@ -55,9 +61,13 @@ private:
|
|||
orb_advert_t _actuator_armed_pub = NULL;
|
||||
uint16_t _esc_pwm_min = 0;
|
||||
uint16_t _esc_pwm_max = 0;
|
||||
uint16_t _fast_channel_mask;
|
||||
|
||||
void _init_alt_channels(void);
|
||||
void _publish_actuators(void);
|
||||
void _arm_actuators(bool arm);
|
||||
void set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz);
|
||||
bool _corking;
|
||||
enum output_mode _output_mode = MODE_PWM_NORMAL;
|
||||
void _send_outputs(void);
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue