mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RCProtocol: add tracer 250Hz mode
This commit is contained in:
parent
79640e5d94
commit
f6a2d20579
@ -98,7 +98,8 @@ static const char* get_frame_type(uint8_t byte)
|
||||
#endif
|
||||
|
||||
#define CRSF_MAX_FRAME_TIME_US 1100U // 700us + 400us for potential ad-hoc request
|
||||
#define CRSF_INTER_FRAME_TIME_US_150HZ 6667U // At fastest, frames are sent by the transmitter every 6.667 ms, 150 Hz
|
||||
#define CRSF_INTER_FRAME_TIME_US_250HZ 4000U // At fastest, frames are sent by the transmitter every 4 ms, 250 Hz
|
||||
#define CRSF_INTER_FRAME_TIME_US_150HZ 6667U // At medium, frames are sent by the transmitter every 6.667 ms, 150 Hz
|
||||
#define CRSF_INTER_FRAME_TIME_US_50HZ 20000U // At slowest, frames are sent by the transmitter every 20ms, 50 Hz
|
||||
#define CSRF_HEADER_LEN 2
|
||||
|
||||
@ -230,7 +231,7 @@ void AP_RCProtocol_CRSF::update(void)
|
||||
|
||||
// never received RC frames, but have received CRSF frames so make sure we give the telemetry opportunity to run
|
||||
uint32_t now = AP_HAL::micros();
|
||||
if (_last_frame_time_us > 0 && !get_rc_frame_count() && now - _last_frame_time_us > CRSF_INTER_FRAME_TIME_US_150HZ) {
|
||||
if (_last_frame_time_us > 0 && !get_rc_frame_count() && now - _last_frame_time_us > CRSF_INTER_FRAME_TIME_US_250HZ) {
|
||||
process_telemetry(false);
|
||||
_last_frame_time_us = now;
|
||||
}
|
||||
|
@ -175,6 +175,7 @@ public:
|
||||
CRSF_RF_MODE_4HZ = 0,
|
||||
CRSF_RF_MODE_50HZ,
|
||||
CRSF_RF_MODE_150HZ,
|
||||
CRSF_RF_MODE_250HZ,
|
||||
CRSF_RF_MODE_UNKNOWN,
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user