mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
AP_RCProtocol: allow selection of protocols for pulse input
This commit is contained in:
parent
9354aca07d
commit
68c9f52b3e
@ -56,13 +56,11 @@ void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// otherwise scan all protocols
|
// otherwise scan all protocols
|
||||||
rcprotocol_t last_protocol = AP_RCProtocol::NONE;
|
for (uint8_t i = 0; i < AP_RCProtocol::NONE; i++) {
|
||||||
#ifdef HAL_RCIN_PULSE_PPM_ONLY
|
if (_disabled_for_pulses & (1U << i)) {
|
||||||
// only uses pulses for PPM on this board, using process_byte() for
|
// this protocol is disabled for pulse input
|
||||||
// other protocols
|
continue;
|
||||||
last_protocol = (rcprotocol_t)1;
|
}
|
||||||
#endif
|
|
||||||
for (uint8_t i = 0; i < last_protocol; i++) {
|
|
||||||
if (backend[i] != nullptr) {
|
if (backend[i] != nullptr) {
|
||||||
backend[i]->process_pulse(width_s0, width_s1);
|
backend[i]->process_pulse(width_s0, width_s1);
|
||||||
if (backend[i]->new_input()) {
|
if (backend[i]->new_input()) {
|
||||||
|
@ -45,6 +45,11 @@ public:
|
|||||||
}
|
}
|
||||||
void process_pulse(uint32_t width_s0, uint32_t width_s1);
|
void process_pulse(uint32_t width_s0, uint32_t width_s1);
|
||||||
void process_byte(uint8_t byte, uint32_t baudrate);
|
void process_byte(uint8_t byte, uint32_t baudrate);
|
||||||
|
|
||||||
|
void disable_for_pulses(enum rcprotocol_t protocol) {
|
||||||
|
_disabled_for_pulses |= (1U<<(uint8_t)protocol);
|
||||||
|
}
|
||||||
|
|
||||||
enum rcprotocol_t protocol_detected()
|
enum rcprotocol_t protocol_detected()
|
||||||
{
|
{
|
||||||
return _detected_protocol;
|
return _detected_protocol;
|
||||||
@ -61,6 +66,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
enum rcprotocol_t _detected_protocol = NONE;
|
enum rcprotocol_t _detected_protocol = NONE;
|
||||||
|
uint16_t _disabled_for_pulses;
|
||||||
bool _detected_with_bytes;
|
bool _detected_with_bytes;
|
||||||
AP_RCProtocol_Backend *backend[NONE];
|
AP_RCProtocol_Backend *backend[NONE];
|
||||||
bool _new_input = false;
|
bool _new_input = false;
|
||||||
|
@ -18,8 +18,6 @@
|
|||||||
|
|
||||||
#include "AP_RCProtocol.h"
|
#include "AP_RCProtocol.h"
|
||||||
|
|
||||||
#define MAX_PPM_CHANNELS 16
|
|
||||||
|
|
||||||
class AP_RCProtocol_PPMSum : public AP_RCProtocol_Backend {
|
class AP_RCProtocol_PPMSum : public AP_RCProtocol_Backend {
|
||||||
public:
|
public:
|
||||||
AP_RCProtocol_PPMSum(AP_RCProtocol &_frontend) : AP_RCProtocol_Backend(_frontend) {}
|
AP_RCProtocol_PPMSum(AP_RCProtocol &_frontend) : AP_RCProtocol_Backend(_frontend) {}
|
||||||
@ -30,4 +28,4 @@ private:
|
|||||||
int8_t _channel_counter;
|
int8_t _channel_counter;
|
||||||
uint16_t _pulse_capt[MAX_RCIN_CHANNELS];
|
uint16_t _pulse_capt[MAX_RCIN_CHANNELS];
|
||||||
} ppm_state;
|
} ppm_state;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user