Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[WIP] Protocol JJRC345 #853

Open
wants to merge 8 commits into
base: master
Choose a base branch
from

Conversation

goebish
Copy link
Member

@goebish goebish commented Apr 12, 2019

Protocol for JJRC 345 mini quadcopter
Reverse engineered thanks to the built-in Deviation XN297 dumper !

https://www.deviationtx.com/forum/protocol-development/8329-jjrc345-drones-as-gift-in-return-for-protocol

@konstantint
Copy link

Just curious, what is blocking this PR? I have a multiprotocol module and this particular drone, could I help with development here?

@goebish
Copy link
Member Author

goebish commented May 20, 2020

That's because this protocol isn't complete, we need someone with a stock TX to make some more XN297 dumps (with the tool built-in DeviationTX), please read the thread that's linked in the first comment then post in the forums if you're willing to help.

@goebish
Copy link
Member Author

goebish commented May 20, 2020

If you do not have a DeviationTX radio but OpenTX+MultiModule you can make a custom build of the MultiModule to enable the XN297 dump protocol.

@konstantint
Copy link

Nice.
I could not register myself at the DeviationTX forum to continue the original discussion there (I'm not receiving the confirmation email somewhy), but perhaps this is just as good a forum.

So I flashed the XN297Dump firmware to the MultiModule and following the suggestions in the post seem to have sniffed out the following:

  • Binding is happening on channel 2, with payload 00 05 00 0A 46 4A 41 47 00 00 40 46 A5 4A F1 18.
RX: 44711us C=2 S=Y A= CC CC CC CC CC P(16)= 00 05 00 0A 46 4A 41 47 00 00 40 46 A5 4A F1 18
  • Channels 65, 71, 70 and 74 are used for transmission with the following timings:
Channel order:
65:     0us
71:  7456us
70: 14882us
74: 22348us
  • The payload seems to work as follows:
P: 00 41 00 0A 00 80 80 80 00    00 40 46 00 49 F1 18
      Ch    T? Th Ru El Ai HL/RT ET AT    Ra Crc

Ai = Aileron. 80 center, 01..41..60..70 to the left, 81..C1..E0..F0 to the right
     (depending on the rate, i.e. with rate 0 maximums are 41/C1,
	  with rate 1 they are 60/E0 and with rate 1 max is 70/F0)
El = Elevator. 80 center, 01..41..60..70 down, 81..C1..E0..F0 up
Ru = Rudder. 80 center, 01..41..60..70 left, 81..C1..E0..F0 right
Th = Throttle. 0..FF
T? = Some throttle flag. 0A when Thr <= B6, 0E when Thr >= B7, sometimes 06 when moving Ele/Ail
HL = Headless mode. 00 normal, 40 headless
ET = Elevator trim, 00 when not used, 20..25 when trimmed up, 0..1F when trimmed down
AT = Aileron trim, 40 when not used, 40..5F when trimmed left, 61..7F when trimmed right
RT = Rudder trim, 00 when not used, 01..1F when trimmed left, 20..3F when trimmed right (20==00)
Ra = Rate, 00-01-02
Crc = Some kind of checksum.
Chn = 47 on channel 65, 46 on channel 71, 4A on channel 70, 41 on channel 74

Let me know if I can offer more help. As noted, I don't have a DeviationTX transmitter, but I suspect it should be easy to try a proof of concept implementation on the multiprotocol module, right (mine is the STM-based Jumper4in1).

@goebish
Copy link
Member Author

goebish commented May 21, 2020

Can you try to implement it in MPM ?
My first try for DeviationTX is here:
https://github.com/DeviationTX/deviation/pull/853/files#diff-9cd9071ab94572aca0eef6e93bc2751d
It works but flips are permanently enabled, find the wrong flag and fix it ;)

@pascallanger
Copy link
Contributor

pascallanger commented May 21, 2020

My XN297Dump is working quite well ;-) It finds the freq being used, order and timing on its own :D
Not sure why it flips randomely with your code goebish unless it flips when losing connectivity since the timing is wrong...

@goebish
Copy link
Member Author

goebish commented May 21, 2020

I don't know either, the guy who started to capture the packets stopped responding on the forums :(

@goebish
Copy link
Member Author

goebish commented May 21, 2020

My code was only for testing, packet period is set with a protocol option

@pascallanger
Copy link
Contributor

I'm currently adding the proto to Multi.

@pascallanger
Copy link
Contributor

@konstantint I'm wondering about this:

Ai = Aileron. 80 center, 01..41..60..70 to the left, 81..C1..E0..F0 to the right
(depending on the rate, i.e. with rate 0 maximums are 41/C1,
with rate 1 they are 60/E0 and with rate 1 max is 70/F0)

For me it doesn't make sense...
When you move from far left to far right, should it be instead 70..60..41..01, 80 center, 81..C1..E0..F0 ?

@goebish
Copy link
Member Author

goebish commented May 21, 2020

I'd just map it to 00-80-FF

@konstantint
Copy link

That's what I meant, the signal is 70 on the far left and F0 on the far right, which looks unintuitive to me, I'd expect 00 at the far left. However, as you move the stick to the left, the value first changes from 80 to 01 and then starts increasing.

@konstantint
Copy link

@pascallanger, indeed, the auto-search functionality of your XN297Dump is amazing!

@pascallanger
Copy link
Contributor

@konstantint How do you do flips on this quad? It's not in your assessment.

@konstantint
Copy link

Strangely, nothing seemed to change when I clicked the flip shoulder button. I now think that maybe it only works at some throttle value or only on some of the four channels. I'll try to look into it again soon.

@konstantint
Copy link

OK, I found the flip. Apparently, the signal for the flip is setting the corresponding channel to FF or 7F momentarily - the flip button on the shoulder itself is not transmitted.

@pascallanger
Copy link
Contributor

@konstantint I've updated the MPM master on GitHub with the JJRC345 protocol.
By default I'm using your TX ID and RF freqs but to test with any ID and RF freq you need to open the file JJRC345_nrf24l01.ino and comment #define JJRC345_FORCE_ID (add // at the begining of the line)
I've also pushed a bit further the channels to: 7F..01, 80 center, 81..FF. Let's see if your quad flips when you go at full deflection to the right.
Pascal

@pascallanger
Copy link
Contributor

pascallanger commented May 21, 2020

OK, I found the flip. Apparently, the signal for the flip is setting the corresponding channel to FF or 7F momentarily - the flip button on the shoulder itself is not transmitted.

Our posts have crossed...
How do you select the flip on AIL/ELE? Can you also select a flip CW and CCW?

@konstantint
Copy link

To make a flip you first click the shoulder button, the TX starts beeping, after which you move the AIL/ELE stick in the desired direction, which makes the transmitter send the maximum value for that channel in that direction.

@konstantint
Copy link

Out of curiosity I decided to make sure the chosen channels are correct and did some extra measurements. The auto-scan functionality seems to reliably reproduce the result like the following:

Channel order:
65:     0us
71:  7441us
70: 14890us
74: 22351us

However, if I manually tune in to some of these channels, things look a bit different. So I fixed the stock TX sticks to a nonzero position with a rubber band and tuned for each of the channels between 65 and 79 for 30 seconds, counting the number of packets received, which of those were bad and good, and looking at the "Channel" byte of the good channels. The results look like that:

Total packets:
Total packets

Valid packets by channel byte:
Packets by channel byte

@konstantint
Copy link

I'll try compiling the MPM now, haven't done that before.

@pascallanger
Copy link
Contributor

Ok let me know if you run into troubles but it should be straight forward...
Otherwise give me what type of build you need.

@konstantint
Copy link

Right, I tried your protocol code. It kind-of-works in the sense that it sometimes manages to bind and the binding sometimes manages to persist long enough (~5-10 seconds or so) to try controlling the drone. The controls seem to be correct (also, the flips happen when the sticks are moved to the extreme positions). Unfortunately, the connection is very flaky and is often lost (the several cases where it binds, senses some throttle and flies away immediately losing the binding gives a whole new meaning to the term "Bind and Fly" for me).

I tried removing the FORCE_ID definition and it kind-of-works as well, but it feels worse (not sure if I'm just imagining things).

Would tuning the packet period help? I tried some values in vain. It would be nice if this could be done via the option parameter, because reflashing every new value is annoying (and I'm not familiar enough with the code to find how to do this quickly).

Having read the code the whole frequency hopping thing makes sense to me now, however I did a couple of attempts to listen in to the stock TX and noticed that it seems to mostly hop between 0x41 and 0x47 (i.e. all the packets on channel 0x41 point to 0x47 and vice versa). There are very rare packets on the two other channels and those somehow seem to also only point only between them.

Another unclear thing is with the binding channel. I'm pretty sure only channel 2 is used to send the binding packets - nothing is sent on channel 5 neither during nor after binding. Your code sets it to 5 (apparently because the number is mentioned in the packet) and it works fine none the less. I'm not sure whether this could be a problem.

@pascallanger
Copy link
Contributor

pascallanger commented May 21, 2020

I've just pushed a new code on master with the debug outputs for the rf_ch+packet. It matches what you've posted above... Flip should not happen anymore when you go to full extreme, instead you need to set CH5 while moving the stick in the direction you want the flip to happen.
Can you post the full debug output (copy, paste in a new file and upload it somewhere) of the XN297Dump in auto mode including adding at the end moving the sticks? I want to check that the cheksum is good for all packets as an example but also the timing on the different channels and other things.

@pascallanger
Copy link
Contributor

Looking at the pictures on the Deviation forum the current checksum calculation cannot be applied to all packets. So I really need a full dump with loads of movement on the sticks and buttons to see how the checksum calculation changes.
I've pushed another version on Master with FLIP on CH5, HeadLess on CH6 and RTH on CH7.

@pascallanger
Copy link
Contributor

pascallanger commented May 21, 2020

If you think bind is difficult due to the channel 5 being used, change this line:
NRF24L01_WriteReg(NRF24L01_05_RF_CH, JJRC345_RF_BIND_CHANNEL); // Bind channel
by
NRF24L01_WriteReg(NRF24L01_05_RF_CH, 2); // Bind channel

@konstantint
Copy link

Here is the log of the auto-scan routine. You are right - the checksum computation you suggested seems to only be correct about half the time, and this may be the reason for the dropouts.

I also think it is a bit strange that not all of the four channels are used equally, which means the stock TX is not really doing a uniform hopping at all. I'll record small sessions for each of the four channels to make sure.

@konstantint
Copy link

If you think bind is difficult due to the channel 5 being used, change this line:

I tried changing the JJRC345_RF_BIND_CHANNEL constant itself (and hard-coding 0x05 in the binding packet instead). Seems to make more sense, right?

But it does not affect things much - the quad eventually binds for either channel (perhaps trying at a longer distance would show the difference).

@konstantint
Copy link

Here is the log, obtained by playing with the sticks and buttons while tuning in to the four presumably main channels ~ 1-1.5 minutes each.

Things to note:

  • The checksum is equal to sum(packet[0:13]) + 0xf8 only in about a third of the cases.
  • Packets on channel 0x41 are most frequent (950) and always contain 0x47 in their second byte
  • Packets on channel 0x47 are the next most frequent (275) and in all except two cases refer to 0x41 in their second byte. In two packets this byte is 0x46
  • Then there are 175 packets on channel 0x4A which almost always contain the byte 0x4A. In 6 cases it was 0x41, though.
  • Channel 0x46 is basically silent - there were three stray packets (mentioning 0x4A).

Maybe I'm misunderstanding how the packet capture works in XN297Dump, but if it simply reports everything that flows through the air, this does not look like a cyclic frequency hopping.

@konstantint
Copy link

konstantint commented May 21, 2020

Another observation: the correct checksum can be computed by adding the first 13 packet bytes except the fourth one plus two:

checksum(packet) = (sum(packet[0:13]) - packet[3] + 2) % 256

The meaning of the fourth byte still evades me, though. It can have four different values: 0A, 0E (most popular) and 06, 12 (rarely). The lowest two bits are always 10, the bits 2..5 look like some kind of flags then. Or, maybe it is just another checksum.

@konstantint
Copy link

Another curiosity. The bind seems to persist as long as I am moving the stick around actively. As soon as I stop doing it, the signal latency quickly (within milliseconds) increases, the quad stops responding, and, soon after (still within a second), starts blinking indicating a lost transmitter.

@pascallanger
Copy link
Contributor

pascallanger commented May 21, 2020

checksum(packet) = (sum(packet[0:13]) - packet[3] + 2) % 256

Good finding. I've just posted another version with the corrected checksum. I'm guessing you might have already tried with it but if not please give it a go.

@pascallanger
Copy link
Contributor

Another curiosity. The bind seems to persist as long as I am moving the stick around actively. As soon as I stop doing it, the signal latency quickly (within milliseconds) increases, the quad stops responding, and, soon after (still within a second), starts blinking indicating a lost transmitter.

I'm thinking this is because by moving the sticks he is receiving something (check , sum...) which is pleasing him so it stays locked to your signal. As soon as he has incorrect packets they start to deviate and it gives up.
Have you tried to bind making sure that all your sticks are well centered at 0% and -100% for throttle (may be by fixing all of them in OpenTX) to see how long it stays locked on the signal?

@pascallanger
Copy link
Contributor

I've looked at your file(s) but they are a little too wild to draw any conclusion.
We need to narrow down the packet[3] value and see what's making it change.
For example don't touch the sticks but just the trims. Does packet[3] change for any values of the trims?
Same test with the features: RTH, headless, rate. Does packet[3] change for any values?
Leaving the trims centered and all the features desactivated, if you only move slowly rudder does the packet[3] value change?
Leaving the trims centered and all the features desactivated, if you only move slowly elevator does the packet[3] value change?
...

@konstantint
Copy link

Yes, the dumps were made by random stick movements hoping to find the checksum rule and are not helpful for figuring out packet[3].

More observations: the bind is not lost if I keep the aileron & elevator signal values above 0. Given that packet[3] does seem to change from A to E or 6 when the Ail/Ele stick is in the lower left region, I have a strong hunch that figuring out the mystery of packet[3] is the only thing left now. I'll eyeball the logs now a bit more.

Oh, btw, I can't seem to make use of the serial debug in the version I'm compiling myself - I'm uncommenting DEBUG_SERIAL and commenting out a couple of protocols to have the binary fit, but I don't see anything on the terminal.
The pre-built multi-stm-opentx-xn297dump-inv-ftdidebug-v1.3.0.95 talks fine to me. Any hint on what I'm missing here?

@konstantint
Copy link

konstantint commented May 21, 2020

OK, I think I know the rule now. The value of packet[3] depends on the sum of packet[0:13] (excluding packet[3], of course, or assuming it is initially 0). It is 06 when the sum is <0x1fe, otherwise it is 0A when the sum is <0x2fe, otherwise it is 0E when it is <0x3fe, or otherwise it is 12.

Another way to describe this would be as follows:

packet[3] = (sum(packet[0:13]) + 2) >> 8) * 4 + 2

(Apparently, there's an imaginary byte 02 somewhere at the beginning of the packet, given that it's the second checksum here that adds it to the sum of bytes)

I'll try it out now.

@konstantint
Copy link

konstantint commented May 21, 2020

Woohoo, it works! 🎉

So, to summarize, that's how you compute the checksum bytes:

packet[3] = 0;
uint16_t csum = 0x02;
for (uint8_t i = 0; i < 13; i++) csum += packet[i];
packet[13] = csum & 0xff;
packet[3] = (csum >> 8) * 4 + 2;

The headless and RTH switches work fine. The flip switch is unusable (basically, as soon as I turn it on, the quad starts flipping in random directions like crazy). I think the correct way to implement it would be something like this:

if(CH5_SW)	//Flip
{
	if(packet[6] == 0x70) packet[6] = 0x7F;
	else if (packet[6] == 0xF0) packet[6] = 0xFF;
	if (packet[7] == 0x70) packet[7] = 0x7F;
	else if (packet[7] == 0xF0) packet[7] = 0xFF;
}

As a last thing, I'll see whether binding on channel 2 rather than 5 works better at a distance now.

@konstantint
Copy link

Two last bits of information:

  • Binding on channel 5 is the right thing (although I still don't understand how come I see the binding packets from the stock TX on channel 2 rather than 5).
  • No need to hard-code the frequencies - the code works fine without #define JJRC345_FORCE_ID and a single call to calc_fh_channels(4) is enough in initialize_txid.

@konstantint
Copy link

An unrelated question. OpenTX seems to limit the max protocol number to 63 (so I had to remap this protocol to something else). Do you know whether this has been improved in the latest OpenTX releases (I'd prefer not to upgrade without a good reason).

@goebish
Copy link
Member Author

goebish commented May 22, 2020

Yes, OpenTX 2.3 supports more than 64 protocols, you should upgrade, a lot of work has been done in 2.3 for MPM integration.
Good job on the checksum ;)

@pascallanger
Copy link
Contributor

Awesome! You made it!

I've pushed a new code version on GitHub. Can you test it and see if we could call it final?
Flips were my bad, it was missing 0x... Let me know if it flips ok as it is or if the sensitivity needs to be decreased.

For serial debug, you need to do it from Arduino. Under "Board: Multi 4-in-1", you have Debug option.

For OpenTX, you should try the latest nightly 2.3.8, the release 2.3.8 is only a couple of days away. With this version you don't need custom anymore, the module tells the radio what to display like protocol name, sub protocol, option field... Also the protocols are ordered alphabetically and many more.

Pascal

@konstantint
Copy link

I think you forgot to push the code to master.

@konstantint
Copy link

konstantint commented May 22, 2020

And before you commit your last version, let's add one extra change. Namely, replace the maximal values for the rud/ail/ele with 7E and FE (in place of the current 70 and F0 respectively) in the JJRC345_convert_channel function and the piece with the flip logic. Although the stock transmitter does not seem to transmit values larger than 70 and F0, the drone does understand them, and given that it is somewhat sluggish as-is (especially on the rudder), the small extra signal range is noticeable.

I was hoping the speed could be increased further by setting the trim signal, but the effect is so miniscule it is not worth the hassle.

@pascallanger
Copy link
Contributor

pascallanger commented May 22, 2020

Can you check the latest Master? It's there now. Hopefully this is the last commit after that I will do a release.

konstantint added a commit to konstantint/DIY-Multiprotocol-TX-Module that referenced this pull request May 22, 2020
A largely symbolic contribution to record participation in protocol development.
See: DeviationTX/deviation#853
@konstantint
Copy link

konstantint commented May 22, 2020

Yes, all works fine. I do think that the flip logic should be changed to be less sensitive. With the current parameters it starts flipping way too early and stick space in the center is needed to be able to keep the quadcopter under control before doing the flip.

I sent a symbolic PR for that.

pascallanger pushed a commit to pascallanger/DIY-Multiprotocol-TX-Module that referenced this pull request May 22, 2020
A largely symbolic contribution to record participation in protocol development.
See: DeviationTX/deviation#853
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants