Jan 2, 2017
Fixed the dos line endings under the common sub directory.
|
|
|
93 |
That graph shows you 4 things: |
|
94 |
|
|
95 |
- the amount of signal being received on the ground |
|
96 |
- the amount of signal being received in the aircraft |
|
97 |
- the amount of noise being received on the ground |
|
98 |
- the amount of noise being received in the aircraft |
|
99 |
|
|
100 |
For the best possible range you want the two noise lines to be low, and |
|
101 |
the two signal lines to be high. In the above graph (taken from my |
|
102 |
SkyFun with a pair of 3DR 433 radios) you can see that the noise levels |
|
103 |
in the plane are higher than the noise levels on the ground. Also note |
|
104 |
that at the start of the flight (before I started the motor) the noise |
|
105 |
levels on the plane were lower, then they went up after I started the |
|
106 |
motor. That shows I'm getting some noise from my motor. If I wanted more |
|
107 |
range I would need to move the radio further from the motor and ESC. |
|
108 |
|
|
109 |
Perhaps the most common source of noise with the 3DR-433 is noise from |
|
110 |
the USB bus on your ground station. That shows up as high values for the |
|
111 |
RADIO.noise value. If you get this, then you could try using a different |
|
112 |
USB cable, or a different laptop. You can also try using a USB hub |
|
113 |
between your laptop and your radio. |
|
114 |
|
|
115 |
If the 'rssi' and 'noise' levels meet on the graph then you will lose |
|
116 |
the link. To determine what your range would be, a rough rule of thumb |
|
117 |
is to subtract the 'rssi' and 'noise' numbers, then divide by 2. That |
|
118 |
tells you your "fade margin" in decibels. For each 6dB of fade margin |
|
119 |
your range doubles. So if you have 18dB of fade margin, then you will be |
|
120 |
able to do roughly 8x whatever range you were at when you measured the |
|
121 |
margin. |
|
122 |
|
|
123 |
Another key source of range problems is the antenna placement. Your |
|
124 |
ground station antenna should be well clear of obstructions and a couple |
|
125 |
of meters off the ground. You may need to build a stand to hold it to |
|
126 |
get the best range. |
|
127 |
|
|
128 |
Serial and air rates 'one byte form' |
|
129 |
==================================== |
|
130 |
|
|
131 |
The ``SERIAL_SPEED`` and ``AIR_SPEED`` parameters are in the same form |
|
132 |
that APM uses for the ``SERIAL3_SPEED`` EEPROM parameter. It is the rate |
|
133 |
in kbps, truncated to an integer. So '9' means 9600 baud, '38' means |
|
134 |
38400, '115' means 115200 etc. |
|
135 |
|
|
136 |
Choosing the air data rate |
|
137 |
========================== |
|
138 |
|
|
139 |
The key parameter that controls the range of your radios is the |
|
140 |
``AIR_SPEED``. The default is 64 (which is 64kbps) will give you a range |
|
141 |
of over a kilometre with small omni antennas. The lower you set the |
|
142 |
``AIR_SPEED`` the longer your range, although lowering the ``AIR_SPEED`` |
|
143 |
also lowers how much data you can send over the link. |
|
144 |
|
|
145 |
The radio firmware can only support 13 possible air date rates, which |
|
146 |
are 2, 4, 8, 16, 19, 24, 32, 48, 64, 96, 128, 192 and 250. If your |
|
147 |
application needs a different air rate for some reason then we can |
|
148 |
potentially add it to the register tables. If you choose an unsupported |
|
149 |
air rate then the next highest rate from the supported list will be |
|
150 |
chosen. |
|
151 |
|
|
152 |
What air data rate you choose will depend on the following factors: |
|
153 |
|
|
154 |
- What range you need |
|
155 |
- What data rate you will be sending |
|
156 |
- Whether you primarily send in one direction, or both |
|
157 |
- Whether you have ECC enabled |
|
158 |
- Whether you have an APM firmware with adaptive flow control |
|
159 |
|
|
160 |
For most telemetry applications you will primarily be sending data |
|
161 |
mostly in one direction, from the aircraft to the ground station. For |
|
162 |
most people, the amount of data sent from the ground station to the |
|
163 |
aircraft is small, just an occasional control packet plus heartbeat |
|
164 |
packets. |
|
165 |
|
|
166 |
If you are using a joystick to control your aircraft then you will be |
|
167 |
sending a lot more data from the ground station to the aircraft, and in |
|
168 |
that case you may find a higher ``AIR_SPEED`` is needed, although your |
|
169 |
range will be reduced. |
|
170 |
|
|
171 |
The ``ECC`` parameter makes a big difference to the data rate you can |
|
172 |
support at a given ``AIR_SPEED``. If you have ECC set to zero, then no |
|
173 |
error correcting information is sent, and the radio uses a simple 16 bit |
|
174 |
CRC to detect transmission errors. In that case your radio will be able |
|
175 |
to support data transfers in one direction of around 90% of the |
|
176 |
``AIR_SPEED``. |
|
177 |
|
|
178 |
If you enable ECC (which is highly recommended), then the data rate you |
|
179 |
can support is halved. The ECC system doubles the size of the data sent |
|
180 |
by the radios. It is worth it however, as the bit error rate will drop |
|
181 |
dramatically, and you are likely to get a much more reliable link at |
|
182 |
longer ranges. |
|
183 |
|
|
184 |
If you have the latest APM firmware (Plane 2.33 or later, or Copter 2.54 |
|
185 |
or later) then the APM will automatically adapt its telemetry rates to |
|
186 |
what the radio can handle, by using MAVLink RADIO packets injected into |
|
187 |
the MAVLink streams by the radios firmware. That allows you to |
|
188 |
'oversubscribe' your link, by setting up a ``SERIAL_SPEED`` larger than |
|
189 |
what the radios can actually handle. |
|
190 |
|
|
191 |
The other factor in choosing the air data rate is the TDM 'sync time'. |
|
192 |
The two radios need to work out each others frequency hopping pattern. |
|
193 |
They do this by slowly changing the receive channel while rapidly |
|
194 |
changing the transmit channel. This process of getting in sync with the |
|
195 |
other radio takes just a few seconds at high air data rates, but gets |
|
196 |
slower for low air data rates. |
|
197 |
|
|
198 |
For most amateur UAV applications the default ``AIR_SPEED`` of 64 with |
|
199 |
ECC enabled will be good. |
|
200 |
|
|
201 |
Error correction |
|
202 |
================ |
|
203 |
|
|
204 |
As mentioned above, the radios support a 12/24 Golay error correcting |
|
205 |
code if you set the ECC parameter to 1. This means that for every 12 |
|
206 |
bits of data the radio will send 24 bits, calculating the bits using |
|
207 |
Golay code lookup tables. The process is reversed on the receiving end, |
|
208 |
and allows the radio to correct bit errors of up to 3 bits in every 12 |
|
209 |
bits send (i.e. 25% bit error rate). |
|
210 |
|
|
211 |
The downside of the ECC option is that it halves your available data |
|
212 |
bandwidth, but in most cases this is worth it, as you are able to |
|
213 |
sustain a reliable link over longer ranges. You will also get a lot less |
|
214 |
'noise' in the serial stream. |
|
215 |
|
|
216 |
MAVLink framing |
|
217 |
=============== |
|
218 |
|
|
219 |
If you set the MAVLINK option to 1 or 2 then the radio will do 'MAVLink |
|
220 |
framing'. The MAVLink protocol is used by APM for transmitting telemetry |
|
221 |
date to a ground station. When MAVLink framing is used, the radio will |
|
222 |
try to align radio packets with MAVLink packet boundaries. This means |
|
223 |
that if a packet is lost you don't end up with half a MAVLink packet |
|
224 |
being seen by the receiver. That partial packet would appear as line |
|
225 |
noise on your ground stations console. |
|
226 |
|
|
227 |
If you set MAVLINK to 2, then in addition to doing MAVLink framing the |
|
228 |
radio will look for ``RC_OVERRIDE`` packets (used for joysticks) and |
|
229 |
ensure that those packets get sent as quickly as possible. This option |
|
230 |
is useful if you are using a tablet based joystick for control. |
|
231 |
|
|
232 |
The radio firmware will try to fit multiple MAVLink packets into one |
|
233 |
radio packet where possible for maximum efficiency. The highest radio |
|
234 |
packet size is 252 bytes. |
|
235 |
|
|
236 |
The radio firmware supports both the MAVLink 0.9 and the MAVLink 1.0 |
|
237 |
transmission formats. |
|
238 |
|
|
239 |
MAVLink reporting |
|
240 |
================= |
|
241 |
|
|
242 |
If you have MAVLINK set to 1, then the radio firmware will also look for |
|
243 |
MAVLink HEARTBEAT messages coming from the serial connection. If it sees |
|
244 |
a HEARTBEAT message then it knows that the MAVLink protocol is in use, |
|
245 |
and it will start injecting MAVLink 'RADIO' status packets into the the |
|
246 |
serial stream. |
|
247 |
|
|
248 |
The RADIO packets contain information about the RSSI (Received Signal |
|
249 |
Strength Indicator) level at both ends of the link, allowing the ground |
|
250 |
station or aircraft to take action in case the link quality falls too |
|
251 |
low. |
|
252 |
|
|
253 |
The RADIO packets also contain information about error rates, and how |
|
254 |
full the serial transmit buffer is (as a percentage). The latest APM |
|
255 |
firmware can use this information to automatically adapt the telemetry |
|
256 |
stream rates to the data rate that the radios can sustain. |
|
257 |
|
|
258 |
Power levels |
|
259 |
============ |
|
260 |
|
|
261 |
You need to be very careful to configure your radios to stay within the |
|
262 |
legal power limits of the country you are operating in. The default |
|
263 |
power level of 20dBm is fine for the US and Australia, as up to 30dBm is |
|
264 |
allowed by the LIPD class licenses there in the 915-928MHz frequency |
|
265 |
band for a frequency hopping radio. So as long as your antennas have a |
|
266 |
gain of less than 10dBi you should be within the ISM rules. |
|
267 |
|
|
268 |
The radio cannot support arbitrary power levels. It can only support the |
|
269 |
power levels given in the following table |
|
270 |
|
|
271 |
.. raw:: html |
|
272 |
|
|
273 |
<table> |
|
274 |
<tbody> |
|
275 |
<tr> |
|
276 |
<th>Power (dBm)</th> |
|
277 |
<th>Power (milliWatts)</th> |
|
278 |
</tr> |
|
279 |
<tr> |
|
280 |
<td>1</td> |
|
281 |
<td>1.3</td> |
|
282 |
</tr> |
|
283 |
<tr> |
|
284 |
<td>2</td> |
|
285 |
<td>1.6</td> |
|
286 |
</tr> |
|
287 |
<tr> |
|
288 |
<td>5</td> |
|
289 |
<td>3.2</td> |
|
290 |
</tr> |
|
291 |
<tr> |
|
292 |
<td>8</td> |
|
293 |
<td>6.3</td> |
|
294 |
</tr> |
|
295 |
<tr> |
|
296 |
<td>11</td> |
|
297 |
<td>12.5</td> |
|
298 |
</tr> |
|
299 |
<tr> |
|
300 |
<td>14</td> |
|
301 |
<td>25</td> |
|
302 |
</tr> |
|
303 |
<tr> |
|
304 |
<td>17</td> |
|
305 |
<td>50</td> |
|
306 |
</tr> |
|
307 |
<tr> |
|
308 |
<td>20</td> |
|
309 |
<td>100</td> |
|
310 |
</tr> |
|
311 |
</tbody> |
|
312 |
</table> |
|
313 |
|
|
314 |
If you choose an unsupported power level the radio will choose the next |
|
315 |
highest power level from the above table. |
|
316 |
|
|
317 |
Please carefully check the EIRP (Equivalent isotropically radiated |
|
318 |
power) power limits for your country, making sure you take into account |
|
319 |
the antenna gain. The radio is a 'DIY' radio part and it is entirely |
|
320 |
your responsibility to ensure any use of it is compliant with local |
|
321 |
rules. |
|
322 |
|
|
323 |
For example, if your local rules allow for a maximum of 30dBm (1W) EIRP, |
|
324 |
then if you use a amplifier with a 12dB transmit gain, and an antenna |
|
325 |
with 3dBi gain, then you will need to set TXPOWER to at most 14. |
|
326 |
|
|
327 |
If you don't know how to calculate it, we've made a tutorial for you |
|
328 |
here: :ref:`Understanding dB, Watts and dBm <common-antenna-design_understanding_db_watts_and_dbm>`. |
|
329 |
|
|
330 |
Using the AT command set |
|
331 |
======================== |
|
332 |
|
|
333 |
The radios support a variant of the Hayes 'AT' modem command set for |
|
334 |
configuration. |
|
335 |
|
|
336 |
If you connect with a serial console to a radio at the current serial |
|
337 |
baud rate, you can tell the radio to enter AT command mode by entering |
|
338 |
the sequence '+++'. To prevent data being seen as the command sequence |
|
339 |
there is a guard time required, so make sure you type nothing on the |
|
340 |
serial link for 1 second before and after you enter the sequence. |
|
341 |
|
|
342 |
When you enter AT command mode you will receive a 'OK' prompt from the |
|
343 |
radio and it will stop displaying data sent from the other radio. |
|
344 |
|
|
345 |
Once in AT command mode, you can give the radio either 'AT' commands to |
|
346 |
control the local radio, or (if successfully connected) you can use 'RT' |
|
347 |
commands to control the remote radio. |
|
348 |
|
|
349 |
The AT commands available are: |
|
350 |
|
|
351 |
- ATI - show radio version |
|
352 |
- ATI2 - show board type |
|
353 |
- ATI3 - show board frequency |
|
354 |
- ATI4 - show board version |
|
355 |
- ATI5 - show all user settable EEPROM parameters |
|
356 |
- ATI6 - display TDM timing report |
|
357 |
- ATI7 - display RSSI signal report |
|
358 |
- ATO - exit AT command mode |
|
359 |
- ATSn? - display radio parameter number 'n' |
|
360 |
- ATSn=X - set radio parameter number 'n' to 'X' |
|
361 |
- ATZ - reboot the radio |
|
362 |
- AT&W - write current parameters to EEPROM |
|
363 |
- AT&F - reset all parameters to factory default |
|
364 |
- AT&T=RSSI - enable RSSI debug reporting |
|
365 |
- AT&T=TDM - enable TDM debug reporting |
|
366 |
- AT&T - disable debug reporting |
|
367 |
|
|
368 |
all of these commands, except for ATO, may be used on a connected remote |
|
369 |
radio by replacing 'AT' with 'RT'. |
|
370 |
|
|
371 |
Perhaps the most useful command is 'ATI5' which displays all user |
|
372 |
settable EEPROM parameters. That will produce a report like this: |
|
373 |
|
|
374 |
:: |
|
375 |
|
|
376 |
S0: FORMAT=22 |
|
377 |
S1: SERIAL_SPEED=57 |
|
378 |
S2: AIR_SPEED=64 |
|
379 |
S3: NETID=25 |
|
380 |
S4: TXPOWER=20 |
|
381 |
S5: ECC=1 |
|
382 |
S6: MAVLINK=1 |
|
383 |
S7: OPPRESEND=1 |
|
384 |
S8: MIN_FREQ=915000 |
|
385 |
S9: MAX_FREQ=928000 |
|
386 |
S10: NUM_CHANNELS=50 |
|
387 |
S11: DUTY_CYCLE=100 |
|
388 |
S12: LBT_RSSI=0 |
|
389 |
S13: MANCHESTER=0 |
|
390 |
S14: RTSCTS=0 |
|
391 |
S15: MAX_WINDOW=131 |
|
392 |
|
|
393 |
The first column is the S register to set if you want to change that |
|
394 |
parameter. So for example, to set the transmit power to 10dBm, use |
|
395 |
'ATS4=10'. |
|
396 |
|
|
397 |
Most parameters only take effect on the next reboot. So the usual |
|
398 |
pattern is to set the parameters you want, then use 'AT&W' to write the |
|
399 |
parameters to EEPROM, then reboot using 'ATZ'. The exception is the |
|
400 |
transmit power, which changes immediately (although it will revert to |
|
401 |
the old setting on reboot unless you use AT&W). |
|
402 |
|
|
403 |
The meaning of the parameter is as follows: |
|
404 |
|
|
405 |
- ``FORMAT`` - this is for EEPROM format version. Don't change it |
|
406 |
- ``SERIAL_SPEED`` - this is the serial speed in 'one byte form' (see |
|
407 |
below) |
|
408 |
- ``AIR_SPEED`` - this is the air data rate in 'one byte form' |
|
409 |
- ``NETID`` - this is the network ID. It must be the same for both your |
|
410 |
radios |
|
411 |
- ``TXPOWER`` - this is the transmit power in dBm. The maximum is 20dBm |
|
412 |
- ``ECC`` - this enables/disables the golay error correcting code |
|
413 |
- ``MAVLINK`` - this controls MAVLink framing and reporting. 0=no |
|
414 |
mavlink framing, 1=frame mavlink, 2=low latency mavlink |
|
415 |
- ``MIN_FREQ`` - minimum frequency in kHz |
|
416 |
- ``MAX_FREQ`` - maximum frequency in kHz |
|
417 |
- ``NUM_CHANNELS`` - number of frequency hopping channels |
|
418 |
- ``DUTY_CYCLE`` - the percentage of time to allow transmit |
|
419 |
- ``LBT_RSSI`` - Listen Before Talk threshold (see docs below) |
|
420 |
- ``MAX_WINDOW`` - max transmit window in msecs, 131 is the default, 33 |
|
421 |
recommended for low latency (but lower bandwidth) |
|
422 |
|
|
423 |
For two radios to communicate the following must be the same at both |
|
424 |
ends of the link: |
|
425 |
|
|
426 |
- the radio firmware version |
|
427 |
- the AIR_SPEED |
|
428 |
- the MIN_FREQ |
|
429 |
- the MAX_FREQ |
|
430 |
- the NUM_CHANNELS |
|
431 |
- the NETID |
|
432 |
- the ECC setting |
|
433 |
- the LBT_RSSI setting |
|
434 |
- the MAX_WINDOW setting |
|
435 |
|
|
436 |
the other settings may be different at either end of the link, although |
|
437 |
you will usually set them up the same at both ends. |
|
438 |
|
|
439 |
Available frequency ranges |
|
440 |
========================== |
|
441 |
|
|
442 |
The following table may be helpful matching your local radio regulations |
|
443 |
to the two radio models available |
|
444 |
|
|
445 |
.. raw:: html |
|
446 |
|
|
447 |
<table> |
|
448 |
<tbody> |
|
449 |
<tr> |
|
450 |
<th>Radio</th> |
|
451 |
<th>Minimum Frequency (MHz)</th> |
|
452 |
<th>Maximum Frequency (MHz)</th> |
|
453 |
</tr> |
|
454 |
<tr> |
|
455 |
<td>433</td> |
|
456 |
<td>414.0</td> |
|
457 |
<td>454.0</td> |
|
458 |
</tr> |
|
459 |
<tr> |
|
460 |
<td>900</td> |
|
461 |
<td>895.0</td> |
|
462 |
<td>935.0</td> |
|
463 |
</tr> |
|
464 |
</tbody> |
|
465 |
</table> |
|
466 |
|
|
467 |
DUTY_CYCLE setting |
|
468 |
=================== |
|
469 |
|
|
470 |
Most users will want to set the ``DUTY_CYCLE`` to 100. The |
|
471 |
``DUTY_CYCLE`` is the maximum percentage of time that the radio will |
|
472 |
transmit packets. |
|
473 |
|
|
474 |
The reason the duty cycle is included is that some regions of the world |
|
475 |
allow for higher transmit power or more frequencies if you have a duty |
|
476 |
cycle below a given threshold. So for example in Europe you can transmit |
|
477 |
on a wider range of frequencies in the 433 band if your duty cycle is |
|
478 |
below 10%. |
|
479 |
|
|
480 |
When you set a duty cycle below 100% then your available bandwidth will |
|
481 |
be reduced, so you will find it will only work well for telemetry at |
|
482 |
higher baud rates. It is still quite practical to get good telemetry |
|
483 |
from an APM with a 10% duty cycle, as telemetry traffic is quite |
|
484 |
'bursty', so the average transmit time is not generally high anyway. |
|
485 |
|
|
486 |
For example, you can easily receive all telemetry streams at 2Hz with |
|
487 |
``AIR_SPEED`` set to 128, ECC enabled and a ``DUTY_CYCLE`` set to 10. |
|
488 |
|
|
489 |
You can also set a radio to receive only by setting the ``DUTY_CYCLE`` |
|
490 |
to 0. That will work best if you set ``NUM_CHANNELS`` to a low number, |
|
491 |
as otherwise the clock synchronisation will be poor. |
Jan 2, 2017
Fixed the dos line endings under the common sub directory.
|
|
|
495 |
Low latency mode |
|
496 |
================ |
|
497 |
|
|
498 |
The radio can be configured to use 'low latency mode' to improve |
|
499 |
performance for things like tablet based joysticks etc... The two |
|
500 |
parameters you should set to enable this mode are as follows: |
|
501 |
|
|
502 |
- Set ``MAVLINK`` to 2. This turns on special checking for the |
|
503 |
``RC_OVERRIDE`` packets used in joystick control, to allow those |
|
504 |
packets to always be sent first. If you are using mavlink (you |
|
505 |
probably are) there are no downsides for choosing this setting. |
|
506 |
- Change ``MAX_WINDOW`` from the default of 131 to 33. This will ensure |
|
507 |
that the GCS can send a packet to the vehicle at least once every 33 |
|
508 |
msecs. It is worth noting that this will lower the available |
|
509 |
bandwidth, so if you need absolute maximum bandwidth you are best off |
|
510 |
with the default of 131. **Both radios on a channel must have the |
|
511 |
same value for this parameter, or they will not be able to talk to |
|
512 |
each other.** |
|
513 |
|
|
514 |
Listen Before Talk (LBT) |
|
515 |
======================== |
|
516 |
|
|
517 |
The radio can implement 'listen before talk' (LBT) functionality to |
|
518 |
allow it to comply with a wider range of regional regulatory |
|
519 |
requirements. LBT is a system where the radio is required to listen for |
|
520 |
a period of time and see no signal from other radios before it is |
|
521 |
allowed to transmit. By using a non-zero ``LBT_RSSI`` value your radio |
|
522 |
will become more 'polite', by waiting until everyone else has stopped |
|
523 |
transmitting before starting to transmit itself. |
|
524 |
|
|
525 |
To enable LBT in your radio you need to set the ``LBT_RSSI`` threshold. |
|
526 |
This is the signal strength that the radio considers to be an indication |
|
527 |
that the channel is busy. If you set ``LBT_RSSI`` to zero then LBT is |
|
528 |
disabled. |
|
529 |
|
|
530 |
The minimum non-zero setting is 25 which is a few dB above the receive |
|
531 |
sensitivity of the radio (-121 dBm). To setup ``LBT_RSSI`` you need to |
|
532 |
know what signal level your local radio regulations require for LBT |
|
533 |
functionality. Each increment in LBT_RSSI above 25 is roughly equal to |
|
534 |
0.5dB above the radios receive sensitivity. So if you set LBT_RSSI to |
|
535 |
40 then the radio will consider the channel to be free if the signal |
|
536 |
strength is less than 7.5dB above the receiver sensitivity. |
|
537 |
|
|
538 |
Alternatively, you can use this formula to get the received signal |
|
539 |
strength in dBm: |
|
540 |
|
|
541 |
:: |
|
542 |
|
|
543 |
signal_dBm = (RSSI / 1.9) - 127 |
|
544 |
|
|
545 |
This formula is approximate, but quite close. See the Si1000 data sheet |
|
546 |
for a more precise graph. |
|
547 |
|
|
548 |
You will need to lookup your local regulatory requirements to see what |
|
549 |
``LBT_RSSI`` setting you should use. |
|
550 |
|
|
551 |
The LBT implementation in the radio uses a minimum listen time of 5ms, |
|
552 |
plus randomised listen time as per the European 9.2.2.2 rules. |
|
553 |
|
|
554 |
Note that in many regions you need to implement LBT in conjunction with |
|
555 |
AFA (Adaptive Frequency Agility). The radio implements AFA as long as |
|
556 |
you have ``NUM_CHANNELS`` set to more than 1. |
|
557 |
|
|
558 |
Upgrading radio firmware |
|
559 |
======================== |
|
560 |
|
|
561 |
The firmware for the radios is `open source <https://github.com/ArduPilot/SiK>`__, and new features are |
|
562 |
regularly added. You should check for new releases regularly to get the |
|
563 |
most from your radios. |
|
564 |
|
|
565 |
The easiest way to upgrade is to: |
|
566 |
|
|
567 |
- Connect the radio to be upgraded to your computer using the micro USB |
|
568 |
cable |
|
569 |
- Open the Mission Planner and go to the **Initial Setup \| Optional |
|
570 |
Hardware \| SiK Radio** page. |
|
571 |
- Select the correct COM port and set the baud rate to 57600. Ensure |
|
572 |
the "Connect" button is in a disconnected state as shown in the image |
|
573 |
below.. |
|
574 |
- Press the **Upload Firmware (Local)** button and after a short delay, |
|
575 |
the "programming" message should appear and the green bar should |
|
576 |
slowly increase from the left to right. |
Jan 2, 2017
Fixed the dos line endings under the common sub directory.
|
|
|
673 |
After you have the radio in bootloader mode you should be able to upload |
|
674 |
a firmware. |
|
675 |
|
|
676 |
Technical Details |
|
677 |
================= |
|
678 |
|
|
679 |
When evaluating if this radio meets your local regulations it may be |
|
680 |
helpful to know what technology it uses. |
|
681 |
|
|
682 |
The firmware implements frequency hopping spread spectrum (FHSS) with |
|
683 |
synchronous adaptive time division multiplexing (TDM). |
|
684 |
|
|
685 |
Specifically, the radio divides up the frequency range between |
|
686 |
MIN_FREQ+delta and MAX_FREQ-delta into ``NUM_CHANNELS`` channels. The |
|
687 |
'delta' value is a guard range to ensure that we stay well away from the |
|
688 |
edges of the allowed band. The guard range is set to half a channel |
|
689 |
width. The channel width is defined as: |
|
690 |
|
|
691 |
:: |
|
692 |
|
|
693 |
channel_width = (MAX_FREQ - MIN_FREQ) / (NUM_CHANNELS+2) |
|
694 |
|
|
695 |
Additionally, the radio skews the base frequency by up to one channel |
|
696 |
using a random seed based on ``NETID``. This means that two radios using |
|
697 |
different ``NETID`` numbers use slightly different frequencies. |
|
698 |
|
|
699 |
The radios use GFSK (Gaussian Frequency Shift Keying) for transmission |
|
700 |
on a particular frequency. |
|
701 |
|
|
702 |
The TDM works by dividing up time into slices, based on multiples of 16 |
|
703 |
microsecond ticks. The time slicing is designed to give a maximum dwell |
|
704 |
time on any frequency of 0.4s (this is to meet US regulations). The TDM |
|
705 |
algorithm then works as follows: |
|
706 |
|
|
707 |
- the EEPROM parameters determine a set of TDM parameters, particularly |
|
708 |
the transmit window and silence period, both are in 16 microsecond |
|
709 |
units. You can view the results using ATI6. |
|
710 |
- the transmit window is scaled to allow for 3 full sized packets to be |
|
711 |
transmitted |
|
712 |
- the silence period is equal to twice the packet latency, for the |
|
713 |
given data rate |
|
714 |
- The two radios synchronise their clocks automatically by adding 13 |
|
715 |
bits of timestamp information to all packets. The timestamp is in 16 |
|
716 |
microsecond units. |
|
717 |
- Each radio only transmits when it is 'their turn'. So a radio gets |
|
718 |
one transmit window worth of time, then there is a silence period |
|
719 |
when neither radio transmits, then the other radio gets its turn. We |
|
720 |
never have the situation where both radios transmit at the same time |
|
721 |
- the transmit channels are organised into a random sequence based on |
|
722 |
the ``NETID`` |
|
723 |
- the frequency is changed to the next channel twice for each full TDM |
|
724 |
round, during the silence periods |
|
725 |
- when not transmitting, data that comes in over the serial port is |
|
726 |
buffered in a 2048 byte buffer |
|
727 |
- to prevent the buffer from getting too much data (which increases |
|
728 |
latency and risks overflow) the radios send information on how full |
|
729 |
the buffer is to the connected device. The APM code adapts its |
|
730 |
telemetry rates by small amounts to keep the amount of buffered data |
|
731 |
reasonable. |
|
732 |
- The TDM algorithm is also adaptive, in the sense that when it is the |
|
733 |
turn of radio A to transmit, it can send a small token to radio B |
|
734 |
saying "I don't need to send anything right now, you can take the |
|
735 |
rest of my timeslice". That is how the link auto-balances for |
|
736 |
asymmetric loads |
|
737 |
- during the initial search for another radio, and any time the link is |
|
738 |
lost, the radios go into a mode where they move the receiving |
|
739 |
frequency very slowly but move the transmit frequency at the normal |
|
740 |
rate. This allows the two radios to find each other for initial clock |
|
741 |
sync. How long this takes depends on the number of channels, the air |
|
742 |
data rate and the packet loss rate. |
|
743 |
|
|
744 |
In some regions you may need to know the distribution of radiated energy |
|
745 |
within each channel. That depends on a number of factors, but mostly the |
|
746 |
frequency deviation used for the GFSK modulation. The following formula |
|
747 |
will give you an estimate of the frequency deviation: |
|
748 |
|
|
749 |
:: |
|
750 |
|
|
751 |
frequency_deviation = air_data_rate * 1.2 min freq deviation = 40 max freq deviation = 159 |
|
752 |
|
|
753 |
where frequency_deviation is in kHz and the air_data_rate is in kilo |
|
754 |
bits per second. |