ArduPilot / ardupilot

ArduPlane, ArduCopter, ArduRover, ArduSub source
http://ardupilot.org/
GNU General Public License v3.0
10.71k stars 17.17k forks source link

DSM 11ms SYNC DeSync Spectrum Receiver #13711

Open Andrewiski opened 4 years ago

Andrewiski commented 4 years ago

Possible related to #12129

Bug report

DSM no longer functions dsm_debug output report lots of DESYNC

Version Arducopter 4.0.3

Platform [ ] All [ ] AntennaTracker [ X ] Copter [ ] Plane [ ] Rover [ ] Submarine

Airframe type HEX

Hardware type Beagle Bone Blue

Logs dsm state: DSM_DECODE_STATE_SYNC, count: 2, val: d8

dsm state: DSM_DECODE_STATE_DESYNC, count: 0, val: ff

dsm state: DSM_DECODE_STATE_DESYNC, count: 0, val: 52

dsm state: DSM_DECODE_STATE_DESYNC, count: 0, val: d8

dsm state: DSM_DECODE_STATE_SYNC, count: 1, val: 10

dsm state: DSM_DECODE_STATE_DESYNC, count: 0, val: d8

dsm state: DSM_DECODE_STATE_SYNC, count: 1, val: 18

dsm state: DSM_DECODE_STATE_DESYNC, count: 0, val: ff

dsm state: DSM_DECODE_STATE_DESYNC, count: 0, val: d8

dsm state: DSM_DECODE_STATE_SYNC, count: 1, val: ff

dsm state: DSM_DECODE_STATE_SYNC, count: 2, val: 10

dsm state: DSM_DECODE_STATE_DESYNC, count: 0, val: d8

dsm state: DSM_DECODE_STATE_SYNC, count: 1, val: ff

dsm state: DSM_DECODE_STATE_SYNC, count: 2, val: 10

dsm state: DSM_DECODE_STATE_SYNC, count: 3, val: 98

Andrewiski commented 4 years ago

So issue seems to be in timing If I add print of lastms and frame ms timing differnec is 10 ms looks like we are expecting less then 5 else desync

case DSM_DECODE_STATE_DESYNC:

    /* we are de-synced and only interested in the frame marker */
    if ((frame_time_ms - last_rx_time_ms) >= 5) {
        dsm_decode_state = DSM_DECODE_STATE_SYNC;
        byte_input.ofs = 0;
        byte_input.buf[byte_input.ofs++] = b;
    }
    break;

case DSM_DECODE_STATE_SYNC: {
    if ((frame_time_ms - last_rx_time_ms) >= 5 && byte_input.ofs > 0) {
        byte_input.ofs = 0;
        dsm_decode_state = DSM_DECODE_STATE_DESYNC;
        break;
    }
    byte_input.buf[byte_input.ofs++] = b;

    /* decode whatever we got and expect */
    if (byte_input.ofs < DSM_FRAME_SIZE) {
        break;
    }

dsm state ad: DSM_DECODE_STATE_SYNC, count: 1, val: d8, framems: 22034, lastms: 22024

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 0, val: 00, framems: 22044, lastms: 22034

dsm state ad: DSM_DECODE_STATE_SYNC, count: 1, val: d8, framems: 22054, lastms: 22044

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 0, val: 00, framems: 22064, lastms: 22054

dsm state ad: DSM_DECODE_STATE_SYNC, count: 1, val: d8, framems: 22074, lastms: 22064

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 0, val: 52, framems: 22084, lastms: 22074

Andrewiski commented 4 years ago

@tridge The setup is a DX8e with a SPM 4648 receiver connected to a Beagle Bone Blue dsm port

The transmitter is set to DSM 11ms and DSMX.

Andrewiski commented 4 years ago

I made some changes to the debug print as I didn't want the debug output on valid sync to mess with the timing of the dsm packets as writing debug slows us down and we need every ms.

DSM: 10 0x06fc -> 1 764 DSM: 11 0x06fc -> 0 1788 DSM: 10 0x0bff -> 2 1023 DSM: 11 0x0bff -> 1 1023 DSM: 10 0x09fe -> 2 510 DSM: 11 0x09fe -> 1 510 DSM: 10 0x86ff -> 1 767 DSM: 11 0x86ff -> 0 1791 DSM: 10 0x09fe -> 2 510 DSM: 11 0x09fe -> 1 510 DSM: 10 0x89ff -> 2 511 DSM: 11 0x89ff -> 1 511 DSM: 10 0x09fc -> 2 508 DSM: 11 0x09fc -> 1 508 DSM: samples++ < 5

DSM: channel_shift = 0

DSM: dsm_decode returned false

DSM: 10 0x09fe -> 2 510 DSM: 11 0x09fe -> 1 510 DSM: 10 0x9ffd -> 7 1021 DSM: 11 0x9ffd -> 3 2045 DSM: 10 0x09fe -> 2 510 DSM: 11 0x09fe -> 1 510 DSM: 10 0x82ff -> 0 767 DSM: 11 0x82ff -> 0 767 DSM: 10 0x89fc -> 2 508 DSM: 11 0x89fc -> 1 508 DSM: 10 0x89fd -> 2 509 DSM: 11 0x89fd -> 1 509 DSM: 10 0xd989 -> 6 393 DSM: 11 0xd989 -> 11 393 DSM: samples++ < 5

DSM: channel_shift = 0

DSM: dsm_decode returned false

DSM: 10 0xfc0b -> 15 11 DSM: 11 0xfc0b -> 15 1035 DSM: 10 0xff09 -> 15 777 DSM: 11 0xff09 -> 15 1801 DSM: 10 0xfe86 -> 15 646 DSM: 11 0xfe86 -> 15 1670 DSM: 10 0xff01 -> 15 769 DSM: 11 0xff01 -> 15 1793 DSM: 10 0xfc89 -> 15 137 DSM: 11 0xfc89 -> 15 1161 DSM: 10 0xff09 -> 15 777 DSM: 11 0xff09 -> 15 1801 DSM: 10 0xfe80 -> 15 640 DSM: 11 0xfe80 -> 15 1664 DSM: samples++ < 5

DSM: channel_shift = 0

DSM: dsm_decode returned false

DSM: DSM_DECODE_STATE_DESYNC

DSM: 10 0x89ff -> 2 511 DSM: 11 0x89ff -> 1 511 DSM: 10 0x1f89 -> 7 905 DSM: 11 0x1f89 -> 3 1929 DSM: 10 0xfe09 -> 15 521 DSM: 11 0xfe09 -> 15 1545 DSM: 10 0xfe5b -> 15 603 DSM: 11 0xfe5b -> 15 1627 DSM: 10 0xff09 -> 15 777 DSM: 11 0xff09 -> 15 1801 DSM: 10 0xfe89 -> 15 649 DSM: 11 0xfe89 -> 15 1673 DSM: 10 0xfe09 -> 15 521 DSM: 11 0xfe09 -> 15 1545 DSM: samples++ < 5

DSM: channel_shift = 0

DSM: dsm_decode returned false

DSM: 10 0x190b -> 6 267 DSM: 11 0x190b -> 3 267 DSM: 10 0xff08 -> 15 776 DSM: 11 0xff08 -> 15 1800 DSM: 10 0xfc89 -> 15 137 DSM: 11 0xfc89 -> 15 1161 DSM: 10 0xff49 -> 15 841 DSM: 11 0xff49 -> 15 1865 DSM: 10 0xfe0b -> 15 523 DSM: 11 0xfe0b -> 15 1547 DSM: 10 0xff49 -> 15 841 DSM: 11 0xff49 -> 15 1865 DSM: 10 0xfe0b -> 15 523 DSM: 11 0xfe0b -> 15 1547 DSM: samples++ < 5

DSM: channel_shift = 0

DSM: dsm_decode returned false

DSM: DSM_DECODE_STATE_DESYNC

Andrewiski commented 4 years ago

@mirkix @tridge

There must be something missing in Copter-4.0 that is in Copter-3.6 as far as setting up the DSM port on the beaglebone blue, but I am not sure where to look as it didn't look like the pru code changed between these branches.

If I do a clean boot and start ArduCopter-3.6.12 udp to Mission planner, I get RC Input seems to function as expected.

If I then start ArduCopter-4.0.3 without a reboot dsm works but drops packets.

If I do a clean boot and then start 4.0 (No 3.6 First)

I drop every dsm packet with DSM: byte_input.ofs < DSM_FRAME_SIZE

The debug I added is in the Copter 4.0 branch of my fork https://github.com/Andrewiski/ardupilot

Below is if I start 3.6 firs then 4.0.

Why does 4.0 always keep checking for 10bit or 11bit once we find it it shouldn't change so why does it always fall back to detecting it.

Maybe this is just a spectrum thing but according to this Spectrum doc

we should be able to use System byte to determine.

Also If its the detection that is failing and only from Spectrum maybe we could pass through the 11ms or 22ms 1024 or 2048 parameters on the command line?

Any suggestions on where I should look?

DSM: 10 0x8c00 -> 3 0 DSM: 11 0x8c00 -> 1 1024 DSM: 10 0x01c6 -> 0 454 DSM: 11 0x01c6 -> 0 454 DSM: 10 0x1400 -> 5 0 DSM: 11 0x1400 -> 2 1024 DSM: 10 0x1bff -> 6 1023 DSM: 11 0x1bff -> 3 1023 DSM: 10 0x2eaa -> 11 682 DSM: 11 0x2eaa -> 5 1706 DSM: 10 0x39a0 -> 14 416 DSM: 11 0x39a0 -> 7 416 DSM: 10 0x36aa -> 13 682 DSM: 11 0x36aa -> 6 1706 DSM: 11-bit format DSM: dsm_decode returned false

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x39a0 -> 7 416 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0fb2 -> 1 1970 DSM: 11 0x0c00 -> 1 1024 DSM: 11 0x01c6 -> 0 454 DSM: 11 0x1400 -> 2 1024 DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: byte_input.ofs < DSM_FRAME_SIZE

DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x0fb2 -> 1 1970 DSM: 11 0x8c00 -> 1 1024 DSM: 11 0x01c6 -> 0 454 DSM: 11 0x1400 -> 2 1024 DSM: byte_input.ofs < DSM_FRAME_SIZE

Andrewiski commented 4 years ago

So weird that the DSM timing is > 20 ms between byte if I do not start Copter 3.6 before starting Copter 4.0. Is there something in Copter 3.6 that speeds up the processor it is so weird. DSM can not decode a single packet.

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 2, val: 44, framems: 20800, lastms: 20790

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 1, val: 40, framems: 20820, lastms: 20810

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 1, val: 4a, framems: 20850, lastms: 20830

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 2, val: 02, framems: 20870, lastms: 20860

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 2, val: c2, framems: 20890, lastms: 20880

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 2, val: 61, framems: 20910, lastms: 20900

Run 3.6 then 4.0 and DSM starts working again and keeps working until you reboot. It does have timeouts but there 9ms timeouts and they are every once in awhile.

DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: lost signal > 200ms

DSM: 10 0x8c01 -> 3 1 DSM: 11 0x8c01 -> 1 1025 DSM: 10 0x0159 -> 0 345 DSM: 11 0x0159 -> 0 345 DSM: 10 0x1401 -> 5 1 DSM: 11 0x1401 -> 2 1025 DSM: 10 0x1bfe -> 6 1022 DSM: 11 0x1bfe -> 3 1022 DSM: 10 0x2eaa -> 11 682 DSM: 11 0x2eaa -> 5 1706 DSM: 10 0x3999 -> 14 409 DSM: 11 0x3999 -> 7 409 DSM: 10 0x36aa -> 13 682 DSM: 11 0x36aa -> 6 1706 DSM: 11-bit format DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 dsm state ad: DSM_DECODE_STATE_DESYNC, count: 8, val: 1b, framems: 14389, lastms: 14380

DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 dsm state ad: DSM_DECODE_STATE_DESYNC, count: 8, val: 1b, framems: 14409, lastms: 14400

DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 dsm state ad: DSM_DECODE_STATE_DESYNC, count: 8, val: 1b, framems: 14429, lastms: 14420

andyp1per commented 4 years ago

Andrew, I think the best thing to do would be what I did for the last bug - find a working version in the history of master and git bisect to the problem. It’s a little time consuming but at least the results are certain.

Sent from my iPhone

On 15 Mar 2020, at 05:48, Andrew DeVries notifications@github.com wrote:

 So weird that the DSM timing is > 20 ms between byte if I do not start Copter 3.6 before starting Copter 4.0. Is there something in Copter 3.6 that speeds up the processor it is so weird. DSM can not decode a single packet.

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 2, val: 44, framems: 20800, lastms: 20790

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 1, val: 40, framems: 20820, lastms: 20810

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 1, val: 4a, framems: 20850, lastms: 20830

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 2, val: 02, framems: 20870, lastms: 20860

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 2, val: c2, framems: 20890, lastms: 20880

dsm state ad: DSM_DECODE_STATE_DESYNC, count: 2, val: 61, framems: 20910, lastms: 20900

Run 3.6 then 4.0 and DSM starts working again and keeps working until you reboot. It does have timeouts but there 9ms timeouts and they are every once in awhile.

DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: lost signal > 200ms

DSM: 10 0x8c01 -> 3 1 DSM: 11 0x8c01 -> 1 1025 DSM: 10 0x0159 -> 0 345 DSM: 11 0x0159 -> 0 345 DSM: 10 0x1401 -> 5 1 DSM: 11 0x1401 -> 2 1025 DSM: 10 0x1bfe -> 6 1022 DSM: 11 0x1bfe -> 3 1022 DSM: 10 0x2eaa -> 11 682 DSM: 11 0x2eaa -> 5 1706 DSM: 10 0x3999 -> 14 409 DSM: 11 0x3999 -> 7 409 DSM: 10 0x36aa -> 13 682 DSM: 11 0x36aa -> 6 1706 DSM: 11-bit format DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 dsm state ad: DSM_DECODE_STATE_DESYNC, count: 8, val: 1b, framems: 14389, lastms: 14380

DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x015a -> 0 346 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 dsm state ad: DSM_DECODE_STATE_DESYNC, count: 8, val: 1b, framems: 14409, lastms: 14400

DSM: 11 0x8c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfe -> 3 1022 DSM: 11 0x2eaa -> 5 1706 DSM: 11 0x3999 -> 7 409 DSM: 11 0x36aa -> 6 1706 DSM: 11 0x0c01 -> 1 1025 DSM: 11 0x0159 -> 0 345 DSM: 11 0x1401 -> 2 1025 DSM: 11 0x1bfd -> 3 1021 DSM: 11 0x2156 -> 4 342 DSM: 11 0x4400 -> 8 1024 DSM: 11 0x4c00 -> 9 1024 dsm state ad: DSM_DECODE_STATE_DESYNC, count: 8, val: 1b, framems: 14429, lastms: 14420

— You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub, or unsubscribe.

Andrewiski commented 4 years ago

Digging into it I believe the issue may be up one level possibly in AP_RCProtocol, where some autodetect dsm sbus etc is going on. It seems a bit overkill and more pron to failure to do all of the rc protocol as a detect and then in DSM protocol keep doing repeated checks for 11ms or 22ms timing and or 1024 or 2048. I assume most everyone else is like me and doesn't change receivers all that often. I am thinking along the lines of passing in a -R (?) on the command line with dsm:/dev/ttyS0:115200 as an override to skip the auto detect. Also we may be able to fix the timing on DSM spectrum if we bump to 125000 baud. https://www.spektrumrc.com/ProdInfo/Files/Remote%20Receiver%20Interfacing%20Rev%20A.pdf

andyp1per commented 4 years ago

@Andrewiski we already have support for specifying a particular protocol on a UART, see AP_SerialManager.h - would be trivial to add specific configuration around DSM

Andrewiski commented 4 years ago

I will take a look at AP_SerialManager.h, Taking this approach should eliminate the hard coded line in AP_HAL_Linux/HAL_Linux_Class.

#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE static RCInput_Multi rcinDriver{2, new RCInput_AioPRU, new RCInput_RCProtocol(NULL, "/dev/ttyO4")};

This should also fix

12743

Andrewiski commented 4 years ago

@mirkix @tridge Is there a need for both SBUS and DSM ie multiple RCInputs would be active at the same time? It seems that was the purpose of RCInput_Multi.cpp but is that a real world need where two controllers would control the same drone?

andyp1per commented 4 years ago

Are you able to try https://github.com/ArduPilot/ardupilot/pull/14174 ? I rewrote the decoder based on the remote receiver spec to address some other issues I was having, but interested to see if it solves your problem.

andyp1per commented 4 years ago

My PR has been backed out, so re-opening