Skip to content

Commit 97b256e

Browse files
committed
AP_HAL_Linux: remove unused RC input methods
these protocols have come from AP_RCProtocol for years
1 parent d1de760 commit 97b256e

File tree

2 files changed

+0
-255
lines changed

2 files changed

+0
-255
lines changed

libraries/AP_HAL_Linux/RCInput.cpp

Lines changed: 0 additions & 226 deletions
Original file line numberDiff line numberDiff line change
@@ -330,229 +330,3 @@ void RCInput::_update_periods(uint16_t *periods, uint8_t len)
330330
_num_channels = len;
331331
rc_input_count++;
332332
}
333-
334-
335-
/*
336-
add some bytes of input in DSM serial stream format, coping with partial packets
337-
*/
338-
bool RCInput::add_dsm_input(const uint8_t *bytes, size_t nbytes)
339-
{
340-
if (nbytes == 0) {
341-
return false;
342-
}
343-
const uint8_t dsm_frame_size = sizeof(dsm.frame);
344-
bool ret = false;
345-
346-
uint32_t now = AP_HAL::millis();
347-
if (now - dsm.last_input_ms > 5) {
348-
// resync based on time
349-
dsm.partial_frame_count = 0;
350-
}
351-
dsm.last_input_ms = now;
352-
353-
while (nbytes > 0) {
354-
size_t n = nbytes;
355-
if (dsm.partial_frame_count + n > dsm_frame_size) {
356-
n = dsm_frame_size - dsm.partial_frame_count;
357-
}
358-
if (n > 0) {
359-
memcpy(&dsm.frame[dsm.partial_frame_count], bytes, n);
360-
dsm.partial_frame_count += n;
361-
nbytes -= n;
362-
bytes += n;
363-
}
364-
365-
if (dsm.partial_frame_count == dsm_frame_size) {
366-
dsm.partial_frame_count = 0;
367-
uint16_t values[16] {};
368-
uint16_t num_values=0;
369-
/*
370-
we only accept input when nbytes==0 as dsm is highly
371-
sensitive to framing, and extra bytes may be an
372-
indication this is really SRXL
373-
*/
374-
if (dsm_decode(AP_HAL::micros64(), dsm.frame, values, &num_values, 16) &&
375-
num_values >= MIN_NUM_CHANNELS &&
376-
nbytes == 0) {
377-
for (uint8_t i=0; i<num_values; i++) {
378-
if (values[i] != 0) {
379-
_pwm_values[i] = values[i];
380-
}
381-
}
382-
/*
383-
the apparent number of channels can change on DSM,
384-
as they are spread across multiple frames. We just
385-
use the max num_values we get
386-
*/
387-
if (num_values > _num_channels) {
388-
_num_channels = num_values;
389-
}
390-
rc_input_count++;
391-
#if 0
392-
printf("Decoded DSM %u channels %u %u %u %u %u %u %u %u\n",
393-
(unsigned)num_values,
394-
values[0], values[1], values[2], values[3], values[4], values[5], values[6], values[7]);
395-
#endif
396-
ret = true;
397-
}
398-
}
399-
}
400-
return ret;
401-
}
402-
403-
404-
/*
405-
add some bytes of input in SUMD serial stream format, coping with partial packets
406-
*/
407-
bool RCInput::add_sumd_input(const uint8_t *bytes, size_t nbytes)
408-
{
409-
uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
410-
uint8_t rssi;
411-
uint8_t rx_count;
412-
uint16_t channel_count;
413-
bool ret = false;
414-
415-
while (nbytes > 0) {
416-
if (sumd_decode(*bytes++, &rssi, &rx_count, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) {
417-
if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) {
418-
continue;
419-
}
420-
for (uint8_t i=0; i<channel_count; i++) {
421-
if (values[i] != 0) {
422-
_pwm_values[i] = values[i];
423-
}
424-
}
425-
_num_channels = channel_count;
426-
rc_input_count++;
427-
ret = true;
428-
_rssi = rssi;
429-
}
430-
nbytes--;
431-
}
432-
return ret;
433-
}
434-
435-
/*
436-
add some bytes of input in ST24 serial stream format, coping with partial packets
437-
*/
438-
bool RCInput::add_st24_input(const uint8_t *bytes, size_t nbytes)
439-
{
440-
uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
441-
uint8_t rssi;
442-
uint8_t rx_count;
443-
uint16_t channel_count;
444-
bool ret = false;
445-
446-
while (nbytes > 0) {
447-
if (st24_decode(*bytes++, &rssi, &rx_count, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) {
448-
if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) {
449-
continue;
450-
}
451-
for (uint8_t i=0; i<channel_count; i++) {
452-
if (values[i] != 0) {
453-
_pwm_values[i] = values[i];
454-
}
455-
}
456-
_num_channels = channel_count;
457-
rc_input_count++;
458-
ret = true;
459-
_rssi = rssi;
460-
}
461-
nbytes--;
462-
}
463-
return ret;
464-
}
465-
466-
/*
467-
add some bytes of input in SRXL serial stream format, coping with partial packets
468-
*/
469-
bool RCInput::add_srxl_input(const uint8_t *bytes, size_t nbytes)
470-
{
471-
uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
472-
uint8_t channel_count;
473-
uint64_t now = AP_HAL::micros64();
474-
bool ret = false;
475-
bool failsafe_state;
476-
477-
while (nbytes > 0) {
478-
if (srxl_decode(now, *bytes++, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS, &failsafe_state) == 0) {
479-
if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) {
480-
continue;
481-
}
482-
for (uint8_t i=0; i<channel_count; i++) {
483-
_pwm_values[i] = values[i];
484-
}
485-
_num_channels = channel_count;
486-
if (failsafe_state == false) {
487-
rc_input_count++;
488-
}
489-
ret = true;
490-
}
491-
nbytes--;
492-
}
493-
return ret;
494-
}
495-
496-
497-
/*
498-
add some bytes of input in SBUS serial stream format, coping with partial packets
499-
*/
500-
void RCInput::add_sbus_input(const uint8_t *bytes, size_t nbytes)
501-
{
502-
if (nbytes == 0) {
503-
return;
504-
}
505-
const uint8_t sbus_frame_size = sizeof(sbus.frame);
506-
507-
uint32_t now = AP_HAL::millis();
508-
if (now - sbus.last_input_ms > 5) {
509-
// resync based on time
510-
sbus.partial_frame_count = 0;
511-
}
512-
sbus.last_input_ms = now;
513-
514-
while (nbytes > 0) {
515-
size_t n = nbytes;
516-
if (sbus.partial_frame_count + n > sbus_frame_size) {
517-
n = sbus_frame_size - sbus.partial_frame_count;
518-
}
519-
if (n > 0) {
520-
memcpy(&sbus.frame[sbus.partial_frame_count], bytes, n);
521-
sbus.partial_frame_count += n;
522-
nbytes -= n;
523-
bytes += n;
524-
}
525-
526-
if (sbus.partial_frame_count == sbus_frame_size) {
527-
sbus.partial_frame_count = 0;
528-
uint16_t values[16] {};
529-
uint16_t num_values=0;
530-
bool sbus_failsafe;
531-
if (AP_RCProtocol_SBUS::sbus_decode(sbus.frame, values, &num_values, sbus_failsafe, 16) &&
532-
num_values >= MIN_NUM_CHANNELS) {
533-
for (uint8_t i=0; i<num_values; i++) {
534-
if (values[i] != 0) {
535-
_pwm_values[i] = values[i];
536-
}
537-
}
538-
/*
539-
the apparent number of channels can change on SBUS,
540-
as they are spread across multiple frames. We just
541-
use the max num_values we get
542-
*/
543-
if (num_values > _num_channels) {
544-
_num_channels = num_values;
545-
}
546-
if (!sbus_failsafe) {
547-
rc_input_count++;
548-
}
549-
#if 0
550-
printf("Decoded SBUS %u channels %u %u %u %u %u %u %u %u %s\n",
551-
(unsigned)num_values,
552-
values[0], values[1], values[2], values[3], values[4], values[5], values[6], values[7],
553-
sbus_failsafe?"FAIL":"OK");
554-
#endif
555-
}
556-
}
557-
}
558-
}

libraries/AP_HAL_Linux/RCInput.h

Lines changed: 0 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -33,21 +33,6 @@ class RCInput : public AP_HAL::RCInput {
3333
// specific implementations
3434
virtual void _timer_tick() {}
3535

36-
// add some DSM input bytes, for RCInput over a serial port
37-
bool add_dsm_input(const uint8_t *bytes, size_t nbytes);
38-
39-
// add some SBUS input bytes, for RCInput over a serial port
40-
void add_sbus_input(const uint8_t *bytes, size_t nbytes);
41-
42-
// add some SUMD input bytes, for RCInput over a serial port
43-
bool add_sumd_input(const uint8_t *bytes, size_t nbytes);
44-
45-
// add some st24 input bytes, for RCInput over a serial port
46-
bool add_st24_input(const uint8_t *bytes, size_t nbytes);
47-
48-
// add some srxl input bytes, for RCInput over a serial port
49-
bool add_srxl_input(const uint8_t *bytes, size_t nbytes);
50-
5136
protected:
5237
void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1);
5338
void _update_periods(uint16_t *periods, uint8_t len);
@@ -81,20 +66,6 @@ class RCInput : public AP_HAL::RCInput {
8166
uint16_t bit_ofs;
8267
} dsm_state;
8368

84-
// state of add_dsm_input
85-
struct {
86-
uint8_t frame[16];
87-
uint8_t partial_frame_count;
88-
uint32_t last_input_ms;
89-
} dsm;
90-
91-
// state of add_sbus_input
92-
struct {
93-
uint8_t frame[25];
94-
uint8_t partial_frame_count;
95-
uint32_t last_input_ms;
96-
} sbus;
97-
9869
int16_t _rssi = -1;
9970
};
10071

0 commit comments

Comments
 (0)