بسم الله الرحمن الرحيم , و الصلاة و السلام على أشرف الأنبياء و المرسلين نبينا محمد وعلى آله وصحبه أجمعين اللهم لا سهل إلا ماجعلته سهلاً وأنت تجعل الحزن إذا شئت سهلاً
1- قبل تشغيل الجهاز يجب إنزال عصا throttle للاسفل و بعدها تقوم بتشغيل الجهاز .
2- بعد تشغيل الجهاز ارفع عصا throttle للأخير لعمل binding بمعنى أخر موالفة بين الجهاز و الطائرة .
3- انزل العصا للأسفل و ستسمع صوت Beep يعلمك بانه تم الإتصال بين الجهاز و الطائرة .
أظن أنه أصبح لدينا فكرة أولية عن ما يجري وراء الكواليس و يمكن إختصاره بالمخطط التالي :
كيف تتم عملية frequency hopping وكيف يستطيع المرسل تحديد القنوات التي سيعمل عليها بناء على رقم الـ ID المخصص له ؟...
في البداية يتوجب عليك تحديد رقم خاص للجهاز مؤلف من 3 بايت وستجد المصفوفة المخصصة له في بداية الكود
و أخيرا اتمنى من الله ان يكون هذا المقال ببساطته نافعا لكم و انتظروا المقال القادم لبناء 4ch rc receiver لهذا المشروع .
بناء 4ch RC Receiver متوافق مع بروتوكول WLToys V202
مقدمة :
لا شك انك سمعت عن أو شاهدت طائرات Micro Quadcopter و شركة WLToys من الشركات الرائدة في صناعة هذا النوع من الطائرات باللإضافة إلى الـ Helicopter أيضا والجدير بالذكر ان جميع اجهزة التحكم لهذه الطائرات ذات الرقم V202 تعمل بنفس البروتوكول .
في موضوعنا لهذا اليوم سنتكلم عن طريقة عمل هذا البروتوكول بالتفصيل الممل لتكون لديكم ارضية جيدة عن كيفية بناء و تصميم أجهزة الإرسال و سنقدم مثال بسيط على بناء مرسل RC باربع قنوات متوافق مع بروتوكول V202و في تدوينة لاحقة سأقوم بعمل تصميم لـ 8Ch RC Transmitter and Receiver بمواصفات عالية إن شاء الله .
في موضوعنا لهذا اليوم سنتكلم عن طريقة عمل هذا البروتوكول بالتفصيل الممل لتكون لديكم ارضية جيدة عن كيفية بناء و تصميم أجهزة الإرسال و سنقدم مثال بسيط على بناء مرسل RC باربع قنوات متوافق مع بروتوكول V202و في تدوينة لاحقة سأقوم بعمل تصميم لـ 8Ch RC Transmitter and Receiver بمواصفات عالية إن شاء الله .
1- ما المقصود بكلمة بروتوكول Protocol :
البروتوكول هو عبارة عن لغة التفاهم بين أجهزة الإلكترونية. حيث أنه إذا كان هناك اختلاف في نوع البروتوكول المستخدم بين الأجهزة فإنه لن يتم التخاطب ونقل البيانات فيما بينها وذلك لأن الأوامر الصادرة من كلا الجهازين لن يتم التعرف عليها من قبل الطرف الآخر. ويمكننا تشبيه البروتوكول باللغة عند الإنسان فلو مثلاً شخص يتكلم العربية ويريد أن يتكلم مع شخص آخر و لكن هذا الشخص لا يعرف العربية و إنما يعرف لغة أخرى غيرها و ليكن مثلاً اللغة الإنجليزية . في هذه الحالة عندما يتحدث أحد
هاذين الطرفين لن يتم فهمه من قبل الطرف الآخر وذلك لإختلاف عنصر التوحيد بين اللغتين. أما إذا كان كلا الطرفين يتحدثون اللغة نفسها فسيسهل على كل طرف فهم حديث الآخر. كذ لك هو الحال في أنظمة الإلكترونية.
هاذين الطرفين لن يتم فهمه من قبل الطرف الآخر وذلك لإختلاف عنصر التوحيد بين اللغتين. أما إذا كان كلا الطرفين يتحدثون اللغة نفسها فسيسهل على كل طرف فهم حديث الآخر. كذ لك هو الحال في أنظمة الإلكترونية.
2- مقدمة عن بروتوكول V202 :
من اين أتت تسمية البروتوكول بـ V202 : شركة WLToys تعتمد هذا الجهاز في جميع طائراتها ذات البادئة V2 و هي طائرات من النوع Micro Quadcopter وهذه قائمة بأرقام الموديلات المصنعة من قبل شركة WLToys
V202/V212/V222/.../V292 كما تلاحظ فإن الفارق الوحيد بين أرقام الموديلات هو الرقم الأوسط لذالك وقع اختياري على التسمية V202 و طبعا هناك اختلاف بين الموديلات مثلا حجم الطائرة و مع أو بدون كمرة .
V202/V212/V222/.../V292 كما تلاحظ فإن الفارق الوحيد بين أرقام الموديلات هو الرقم الأوسط لذالك وقع اختياري على التسمية V202 و طبعا هناك اختلاف بين الموديلات مثلا حجم الطائرة و مع أو بدون كمرة .
3- كيف يعمل بروتوكول V202 :
ما اريد ان تعلموه جيدا عن هذا البروتوكول انه :
- لكل جهاز تحكم رقم فريد ID مؤلف من 3 بايت تحدده الشركة المصنعة .
- يعمل على التردد 2.4GHz ISM Frequency Range و لضمان عدم التداخل مع اجهزة اخرى يختار 16 قناة للعمل عليهم بناء على رقم الـ ID المخصص له .
- دعم ميزة Auto ID في الـ Receiver وهذا يعني ان جميع الطائرات بإمكانها العمل على نفس الجهاز .
- بعد ارسال حزمة البيانات يقوم بالقفز إلى التردد التالي من القنوات المحددة له وتسمى هذه التقنية بـ FHSS .
- حجم البايتات المرسلة في الحزمة الواحدة هو 16 بايت .
- يتم ترتيب حزمة البيانات بحسب الجدول التالي بحيث كل حقل من index يمثل 1 بايت :
15
|
14
|
13
|
12
|
11
|
10
|
9
|
8
|
7
|
6
|
5
|
4
|
3
|
2
|
1
|
0
|
Index
|
Sum
|
Flags
|
empty
|
TX id
|
Trims
|
Regular packet
|
Struct
| ||||||||||
var
|
bits
|
3
|
2
|
1
|
0
|
2
|
1
|
0
|
roll
|
pitch
|
yaw
|
roll
|
pitch
|
yaw
|
throttle
|
Data
|
?
|
?
|
0x00
|
0..0xFFFFFF
|
-64 .. 64
|
-127..127
|
0..255
|
Value
|
4- تشغيل الجهاز
قبل الخوض في الأكواد البرمجية للبروتوكول دعونا نلقي نظرة سريعة على الإجراءات الواجب التقيد بها عند تشغيل الجهاز :1- قبل تشغيل الجهاز يجب إنزال عصا throttle للاسفل و بعدها تقوم بتشغيل الجهاز .
2- بعد تشغيل الجهاز ارفع عصا throttle للأخير لعمل binding بمعنى أخر موالفة بين الجهاز و الطائرة .
3- انزل العصا للأسفل و ستسمع صوت Beep يعلمك بانه تم الإتصال بين الجهاز و الطائرة .
أظن أنه أصبح لدينا فكرة أولية عن ما يجري وراء الكواليس و يمكن إختصاره بالمخطط التالي :
مخطط تنفيذ البرنامج الرئيسي |
5- المخطط النظري
إعتمدت تبسيط التصميم كبداية فقط لكن لن يكون بهذه البساطة في المشروع القادم 8Channel RC Transmitter إن شاء اللهالمكونات :
1- Joystick عدد 2 ( تستطيع الحصول عليهم من قبضة PlayStation 3 قديمة ) .
2- لوحة اردوينو ( لا فرق بين UNO او Mini او Nano فجميع أقطابهم تعتمد نفس الترقيم ).
3- مديول nRF24L01 ( يفضل ربط مكثف سيرميكي 100nF و مكثف كيميائي 10uF على اقطاب تغذية المديول مباشرتا ) .
4- مقاومات 220 اوم عدد 4 ( إن لم تتوفر عليهم تستطيع الإستغناء عنهم ) .
ملاحظة : لمن يريد معرفة طريقة التعامل برمجيا مع المديول NRF24L01 و فهمها بشكل صحيح فأنصحه بمشاهدة
سلسلة دروس الاتصالات اللاسلكية (nRF24L01)
إضغط هنا لتحميل ملفات المشروع
في الكود التالي تم حجز المتحولات و تهئيتها بالقيم الأولية ومن لم تسند إليه أي قيمة سيقوم المترجم بإسناد القيمة صفر إليه
كلنا يعلم أن عصي التحكم Joystick تتكون من two potentiometers على كل من المحورين XY و لكل محور حد علوي و اخر سفلي و مهما كانت جودة الـ Joystick عالية فإنه من النادر ان تتوافق قيم الحد الأدنا و الأعلى لأي منهم مع Joystick اخرى بسبب نسبة الخطاء الموجودة في الـ potentiometer و حدود الحركة الميكانيكية .
و بعدها يقوم بتفعيل أو إلغاء تفعيل العلم FLAG_LED لتشغيل و اطفاء الأضواء في الطائرة كل 1 ثانية تقريبا و هذا الأمر للإختبار فقط .
3- مديول nRF24L01 ( يفضل ربط مكثف سيرميكي 100nF و مكثف كيميائي 10uF على اقطاب تغذية المديول مباشرتا ) .
4- مقاومات 220 اوم عدد 4 ( إن لم تتوفر عليهم تستطيع الإستغناء عنهم ) .
ملاحظة : لمن يريد معرفة طريقة التعامل برمجيا مع المديول NRF24L01 و فهمها بشكل صحيح فأنصحه بمشاهدة
سلسلة دروس الاتصالات اللاسلكية (nRF24L01)
الكود
ملاحظة : الإصدار Ver 1.0.1 يمتاز بسرعة تنفيذ اكبر من النسخة القديمة المرفقة سابقا و حجم اصغر و دعم ميزة Debug بإضافة أي قيمة غير صفرية بجانبه .
/************************************************************ ** V202 protocol 4ch Transmitter ** Ver 1.0.1 ** By : Andullah Jalloul (2015-07) ** Website: http://horizon4electronics.blogspot.com ************************************************************/ #include <SPI.h> #include "nRF24L01.h" #include "V202.h" #define DEBUG 0 #define THROTTLE_AI_Pin A0 #define YAW_AI_Pin A1 #define ROLL_AI_Pin A2 #define PITCH_AI_Pin A3 #define CE_PIN 9 #define CSN_PIN 10 enum { THROTTLE, YAW, ROLL, PITCH }; enum { FLAG_CAMERA = 0x01, FLAG_VIDEO = 0x02, FLAG_FLIP = 0x04, FLAG_UNK9 = 0x08, FLAG_LED = 0x10, FLAG_UNK10 = 0x20, FLAG_BIND = 0xC0 }; const int joy_pin[] = { THROTTLE_AI_Pin, YAW_AI_Pin, ROLL_AI_Pin, PITCH_AI_Pin }; uint8_t txid[3] = { 0x00, 0x00, 0x00 }; nRF24 radio(CE_PIN, CSN_PIN); V202_TX tx(radio); uint8_t throttle, flags; uint8_t yaw , pitch, roll; int counter = 0; int direction = 1; bool bind = true; struct { int iVal; int iMin; int iMax; } joyLimit[4]; /************************************************************/ void calibrate() { for(byte n = 0; n < 4; n++) { joyLimit[n].iMin = 150; joyLimit[n].iMax = 600; } } /************************************************************/ void initInput() { pinMode(THROTTLE_AI_Pin, INPUT); pinMode(YAW_AI_Pin, INPUT); pinMode(ROLL_AI_Pin, INPUT); pinMode(PITCH_AI_Pin, INPUT); calibrate(); } /************************************************************/ bool readInput() { bool changed = false; long a; for(byte n = 0; n < 4; n++) { a = analogRead(joy_pin[n]); if (a < joyLimit[n].iMin) joyLimit[n].iMin = a; else if (a > joyLimit[n].iMax) joyLimit[n].iMax = a; a = (a-joyLimit[n].iMin)*255/(joyLimit[n].iMax-joyLimit[n].iMin); if (a != joyLimit[n].iVal) { changed = true; joyLimit[n].iVal = a; } } return changed; } /************************************************************/ void setup() { initInput(); readInput(); #if (DEBUG != 0) Serial.begin(115200); #endif tx.setTXId(txid); tx.begin(); #if (DEBUG != 0) Serial.write("Reading status\n"); uint8_t res = radio.read_register(STATUS); Serial.write("Result: "); Serial.print(res); Serial.write("\n"); #endif } /************************************************************/ void loop() { bool changed = readInput(); #if (DEBUG != 0) // if (changed) { Serial.write("sticks: "); for(byte n = 0; n < 4; n++) { Serial.print(joyLimit[n].iVal); Serial.write(" "); } Serial.write("\n"); // } #endif if (bind) { throttle = joyLimit[THROTTLE].iVal; flags = FLAG_BIND; if (direction > 0) { if (throttle >= 255) direction = -1; } else { if (throttle == 0) { direction = 1; counter = 0; bind = false; flags = 0; #if (DEBUG != 0) Serial.write("Bound\n"); for(byte n = 0; n < 4; n++) { Serial.write("min " ); Serial.write(n); Serial.write(":"); Serial.write(joyLimit[n].iMin); Serial.write(" max "); Serial.write(n); Serial.write(":"); Serial.write(joyLimit[n].iMax); Serial.write("\n"); } #endif } } } else { throttle = joyLimit[THROTTLE].iVal; yaw = joyLimit[YAW].iVal; // < 0x80 ? 0x7f - joyLimit[YAW].iVal : joyLimit[YAW].iVal; roll = joyLimit[ROLL].iVal; // < 0x80 ? 0x7f - joyLimit[ROLL].iVal : joyLimit[ROLL].iVal ; pitch = joyLimit[PITCH].iVal; // < 0x80 ? 0x7f - joyLimit[PITCH].iVal : joyLimit[PITCH].iVal; // Blinking LED lights counter += direction; if (direction > 0) { if (counter > 255) { direction = -1; counter = 255; flags = FLAG_LED; } } else { if (counter < 0) { direction = 1; counter = 0; flags = 0x00; } } } tx.command(throttle, yaw, pitch, roll, flags); delay(4); } /************************************************************/
شرح الكود
في البداية تم إستدعاء المكتبات اللازمة لعمل المشروع#include <SPI.h> #include "nRF24L01.h" #include "V202.h"
تمثل التعدادات تعريفا لثوابت إذ تستخدم الكلمة المحجوزة enum لإسناد قيم ثوابت صحيحة (integer) متتابعة إلى لائحة معرفات :
فالاسم throttle تسند إليه القيمة 0 و yaw القيمة 1 و تسند القيمة 2 للاسم roll وهكذا . كما يمكن فرض القيمة الأولى كما في التعداد التالي : حيث FLAG_CAMERA تأخذ القيمة 1 و FLAG_VIDEO تأخذ القيمة 2 و هكذا .
أما وظيفة هذه التعدادات فالأول يعمل على ترتيب البيانات ضمن المصفوفة joyLimit و الثاني يستخدم لإسناد القيم للعلم flags بحيث تكون القيم ذات معنى واضح .
أما وظيفة هذه التعدادات فالأول يعمل على ترتيب البيانات ضمن المصفوفة joyLimit و الثاني يستخدم لإسناد القيم للعلم flags بحيث تكون القيم ذات معنى واضح .
شرح وظائف التعداد الثاني
القيم المدرجة خاصة بالطائرة بإستثناء FLAG_BIND :
FLAG_CAMERA : لإلتقاط صورة .
FLAG_VIDEO : لبدء تسجيل فيديو .
FLAG_FLIP : عمل شقلبة في الجو .
FLAG_UNK9 : غير مستخدم .
FLAG_LED : تشغيل اضواء الطائرة .
FLAG_UNK10 : غير مستخدم .
FLAG_BIND : عمل إتصال مع الطائرة عند بداية التشغيل .
enum { THROTTLE, YAW, ROLL, PITCH }; enum { FLAG_CAMERA = 0x01, FLAG_VIDEO = 0x02, FLAG_FLIP = 0x04, FLAG_UNK9 = 0x08, FLAG_LED = 0x10, FLAG_UNK10 = 0x20, FLAG_BIND = 0xC0 };ذكرت أن لكل Transmitter رقم فريد مؤلف من 3 بايت تحدده الشركة المصنعة و تستطيع تحديد الرقم الذي تريد من خلال هذه المصفوفة بالقيمة الست عشرية :
uint8_t txid[3] = { 0x00, 0x00, 0x00 };
في الكود التالي تم حجز المتحولات و تهئيتها بالقيم الأولية ومن لم تسند إليه أي قيمة سيقوم المترجم بإسناد القيمة صفر إليه
uint8_t throttle, flags; uint8_t yaw , pitch, roll; int counter = 0; int direction = 1; bool bind = true;
قراءة قيم Joystick
كلنا يعلم أن عصي التحكم Joystick تتكون من two potentiometers على كل من المحورين XY و لكل محور حد علوي و اخر سفلي و مهما كانت جودة الـ Joystick عالية فإنه من النادر ان تتوافق قيم الحد الأدنا و الأعلى لأي منهم مع Joystick اخرى بسبب نسبة الخطاء الموجودة في الـ potentiometer و حدود الحركة الميكانيكية .
تعمل
الدالة calibrate على تحديد القيم الإفتراضية العالية و المنخفضة لعصي
التحكم ثم تعمل الدالة readInput على قراءة القيم الحالية لموضع العصي و
إعادة تحديد القيم العليا و المنخفضة لكل محور على حدى و بعدها تقوم بحساب
القيمة الموافقة لموقع العصا مع الأخذ بالحسبان القيمة العليا و المنخفضة و
بذالك نحصل على قيم مستقرة عندما تكون العصا في المنتصف .
مما ذكر نفهم انه يتوجب علينا بعد كل تشغيل للجهاز ان نقوم بعمل calibration بتحريك العصي في جميع الإتجاهات ليقوم الكونترول بضبط القيم العليا و الدنيا.
ملاحظة : في الأجهزة المتقدمة تتم هذه العملية مرة واحدة و يتم تخزين هذه القيم في الذاكرة EEPROM و عند اقلاع الجهاز يقوم بجلب هذه القيم من الذاكرة و بالتالي يغنيك عن عمل calibration في كل مرة تشغل فيها الجهاز ,لا تقلق ففي المقال القادم سيتم حل هذه المشكلة .
مخطط تنفيذ الدالة readInput |
struct { int iVal; int iMin; int iMax; } joyLimit[4]; /************************************************************/ void calibrate() { for(byte n = 0; n < 4; n++) { joyLimit[n].iMin = 150; joyLimit[n].iMax = 600; } } /************************************************************/ bool readInput() { bool changed = false; long a; for(byte n = 0; n < 4; n++) { a = analogRead(joy_pin[n]); if (a < joyLimit[n].iMin) joyLimit[n].iMin = a; else if (a > joyLimit[n].iMax) joyLimit[n].iMax = a; a = (a-joyLimit[n].iMin)*255/(joyLimit[n].iMax-joyLimit[n].iMin); if (a != joyLimit[n].iVal) { changed = true; joyLimit[n].iVal = a; } } return changed; }
عملية binding
في بداية الكود قمت بتعريف المتحول bind و اسندت له القيمة true حتى أجبر المستخدم على عمل Binding عند تشغيل الجهاز و عرفت المتحول direction و اسندت القيمة 1 إليه لتحديد اتجاه عصا التحكم throttle و سيبقى الجهاز يرسل الأمر Bind حتى يتم رفع العصا throttle للأعلى و من ثم للأسفل كما هو واضح في الكود التالي :if (bind) { throttle = joyLimit[THROTTLE].iVal; flags = FLAG_BIND; if (direction > 0) { if (throttle >= 255) direction = -1; } else { if (throttle == 0) { direction = 1; counter = 0; bind = false; flags = 0; #if (DEBUG != 0) Serial.write("Bound\n"); for(byte n = 0; n < 4; n++) { Serial.write("min " ); Serial.write(n); Serial.write(":"); Serial.write(joyLimit[n].iMin); Serial.write(" max "); Serial.write(n); Serial.write(":"); Serial.write(joyLimit[n].iMax); Serial.write("\n"); } #endif } } }
إرسال البيانات :
بعد الإنتهاء من عمل Bind يبداء الجهاز بإسناد قيم عصي التحكم للمتحولات حسب الجدول السابق ذكره :throttle = joyLimit[THROTTLE].iVal; yaw = joyLimit[YAW].iVal; // < 0x80 ? 0x7f - joyLimit[YAW].iVal : joyLimit[YAW].iVal; roll = joyLimit[ROLL].iVal; // < 0x80 ? 0x7f - joyLimit[ROLL].iVal : joyLimit[ROLL].iVal ; pitch = joyLimit[PITCH].iVal; // < 0x80 ? 0x7f - joyLimit[PITCH].iVal : joyLimit[PITCH].iVal;
// Blinking LED lights counter += direction; if (direction > 0) { if (counter > 255) { direction = -1; counter = 255; flags = FLAG_LED; } } else { if (counter < 0) { direction = 1; counter = 0; flags = 0x00; } }
و اخيرا يرسل القيم إلى المستقبل و ينتظر 4 ميلي ثانية ثم ينتقل لبداية الحلقة Loop ليبداء من جديد بقراءة قيم العصي و ارسالها .
tx.command(throttle, yaw, pitch, roll, flags);
delay(4);
شرح مختصر لمكتبة V202
الدالة tx.begin تقوم بتهيئة مسجلات المديول nRF24L01 و قد أشرت في البداية إلى كورس باللغة العربية للتعامل مع هذا المديول .void V202_TX::begin() { radio.begin(); radio.write_register(CONFIG, _BV(EN_CRC) | _BV(CRCO)); radio.write_register(EN_AA, 0x00); radio.write_register(EN_RXADDR, 0x3F); radio.write_register(SETUP_AW, 0x03); radio.write_register(SETUP_RETR, 0xFF); radio.write_register(RF_CH, 0x08); radio.write_register(RF_SETUP, 0x05); // 0x05 - 1Mbps, 0dBm power, LNA high gaim radio.write_register(STATUS, 0x70); radio.write_register(OBSERVE_TX, 0x00); radio.write_register(CD, 0x00); radio.write_register(RX_ADDR_P2, 0xC3); radio.write_register(RX_ADDR_P3, 0xC4); radio.write_register(RX_ADDR_P4, 0xC5); radio.write_register(RX_ADDR_P5, 0xC6); radio.write_register(RX_PW_P0, 0x10); radio.write_register(RX_PW_P1, 0x10); radio.write_register(RX_PW_P2, 0x10); radio.write_register(RX_PW_P3, 0x10); radio.write_register(RX_PW_P4, 0x10); radio.write_register(RX_PW_P5, 0x10); radio.write_register(FIFO_STATUS, 0x00); const uint8_t* rx_tx_addr = reinterpret_cast<const uint8_t *>("\x66\x88\x68\x68\x68"); const uint8_t* rx_p1_addr = reinterpret_cast<const uint8_t *>("\x88\x66\x86\x86\x86"); radio.write_register(RX_ADDR_P0, rx_tx_addr, 5); radio.write_register(RX_ADDR_P1, rx_p1_addr, 5); radio.write_register(TX_ADDR, rx_tx_addr, 5); // Check for Beken BK2421/BK2423 chip // It is done by using Beken specific activate code, 0x53 // and checking that status register changed appropriately // There is no harm to run it on nRF24L01 because following // closing activate command changes state back even if it // does something on nRF24L01 radio.activate(0x53); // magic for BK2421 bank switch Serial.write("Try to switch banks "); Serial.print(radio.read_register(STATUS)); Serial.write("\n"); if (radio.read_register(STATUS) & 0x80) { Serial.write("BK2421!\n"); long nul = 0; radio.write_register(0x00, (const uint8_t *) "\x40\x4B\x01\xE2", 4); radio.write_register(0x01, (const uint8_t *) "\xC0\x4B\x00\x00", 4); radio.write_register(0x02, (const uint8_t *) "\xD0\xFC\x8C\x02", 4); radio.write_register(0x03, (const uint8_t *) "\xF9\x00\x39\x21", 4); radio.write_register(0x04, (const uint8_t *) "\xC1\x96\x9A\x1B", 4); radio.write_register(0x05, (const uint8_t *) "\x24\x06\x7F\xA6", 4); radio.write_register(0x06, (const uint8_t *) &nul, 4); radio.write_register(0x07, (const uint8_t *) &nul, 4); radio.write_register(0x08, (const uint8_t *) &nul, 4); radio.write_register(0x09, (const uint8_t *) &nul, 4); radio.write_register(0x0A, (const uint8_t *) &nul, 4); radio.write_register(0x0B, (const uint8_t *) &nul, 4); radio.write_register(0x0C, (const uint8_t *) "\x00\x12\x73\x00", 4); radio.write_register(0x0D, (const uint8_t *) "\x46\xB4\x80\x00", 4); radio.write_register(0x0E, (const uint8_t *) "\x41\x10\x04\x82\x20\x08\x08\xF2\x7D\xEF\xFF", 11); radio.write_register(0x04, (const uint8_t *) "\xC7\x96\x9A\x1B", 4); radio.write_register(0x04, (const uint8_t *) "\xC1\x96\x9A\x1B", 4); } radio.activate(0x53); // switch bank back delay(50); radio.flush_tx(); radio.write_register(CONFIG, _BV(EN_CRC) | _BV(CRCO) | _BV(PWR_UP)); delayMicroseconds(150); // packet_sent = true; rf_ch_num = 0; // This is a bogus packet which actual V202 TX sends, but it is // probably some garbage, so no need to send it. // uint8_t buf[16] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x9B, // 0x9C, 0x88, 0x48, 0x8F, 0xD3, 0x00, 0xDA, 0x8F }; // radio.flush_tx(); // radio.write_payload(buf, 16); radio.ce(HIGH); // delayMicroseconds(15); // It saves power to turn off radio after the transmission, // so as long as we have pins to do so, it is wise to turn // it back. // radio.ce(LOW); }
كيف تتم عملية frequency hopping وكيف يستطيع المرسل تحديد القنوات التي سيعمل عليها بناء على رقم الـ ID المخصص له ؟...
في البداية يتوجب عليك تحديد رقم خاص للجهاز مؤلف من 3 بايت وستجد المصفوفة المخصصة له في بداية الكود
uint8_t txid[3] = { 0x00, 0x00, 0x00 };
تستطيع وضع أي قيمة بشرط أن لا تتجاوز 0xFF(255( لكل بايت , وسيتم استدعاء الدالة
setTXId لتقوم هي بدورها في حساب أرقام القنوات التي سيعمل عليها المرسل و
ستضعهم ضمن المصفوفة rf_channels و التي سيتم استخدامها لحقا في عملية ارسال للبيانات .
كود حساب القنوات المعمول بها بناء على الـ ID
// This is frequency hopping table for V202 protocol // The table is the first 4 rows of 32 frequency hopping // patterns, all other rows are derived from the first 4. // For some reason the protocol avoids channels, dividing // by 16 and replaces them by subtracting 3 from the channel // number in this case. // The pattern is defined by 5 least significant bits of // sum of 3 bytes comprising TX id uint8_t freq_hopping[][16] = { { 0x27, 0x1B, 0x39, 0x28, 0x24, 0x22, 0x2E, 0x36, 0x19, 0x21, 0x29, 0x14, 0x1E, 0x12, 0x2D, 0x18 }, // 00 { 0x2E, 0x33, 0x25, 0x38, 0x19, 0x12, 0x18, 0x16, 0x2A, 0x1C, 0x1F, 0x37, 0x2F, 0x23, 0x34, 0x10 }, // 01 { 0x11, 0x1A, 0x35, 0x24, 0x28, 0x18, 0x25, 0x2A, 0x32, 0x2C, 0x14, 0x27, 0x36, 0x34, 0x1C, 0x17 }, // 02 { 0x22, 0x27, 0x17, 0x39, 0x34, 0x28, 0x2B, 0x1D, 0x18, 0x2A, 0x21, 0x38, 0x10, 0x26, 0x20, 0x1F } // 03 }; void V202_TX::setTXId(uint8_t txid_[3]) { uint8_t sum; txid[0] = txid_[0]; txid[1] = txid_[1]; txid[2] = txid_[2]; sum = txid[0] + txid[1] + txid[2]; // Base row is defined by lowest 2 bits uint8_t (&fh_row)[16] = freq_hopping[sum & 0x03]; // Higher 3 bits define increment to corresponding row uint8_t increment = (sum & 0x1e) >> 2; for (int i = 0; i < 16; ++i) { uint8_t val = fh_row[i] + increment; // Strange avoidance of channels divisible by 16 rf_channels[i] = (val & 0x0f) ? val : val - 3; } }ارسال البيانات يتم بإستدعاء الدالة V202_TX::command
void V202_TX::command(uint8_t throttle, uint8_t yaw, uint8_t pitch, uint8_t roll, uint8_t flags)
في حال كان المتحول flags يحمل القيمة FLAG_BIND فإن الدالة command ستنفذ العملية binding و لن يتم ارسال اي قيم أخرى .
uint8_t buf[16]; if (flags == 0xc0) { // binding buf[0] = 0x00; buf[1] = 0x00; buf[2] = 0x00; buf[3] = 0x00; buf[4] = 0x00; buf[5] = 0x00; buf[6] = 0x00; } else { // regular packet buf[0] = throttle; buf[1] = yaw; buf[2] = pitch; buf[3] = roll; // Trims, middle is 0x40 buf[4] = 0x40; // yaw buf[5] = 0x40; // pitch buf[6] = 0x40; // roll } // TX id buf[7] = txid[0]; buf[8] = txid[1]; buf[9] = txid[2]; // empty buf[10] = 0x00; buf[11] = 0x00; buf[12] = 0x00; buf[13] = 0x00; // buf[14] = flags; uint8_t sum = 0; uint8_t i; for (i = 0; i < 15; ++i) sum += buf[i]; buf[15] = sum;
في هذا الكود تتم عملية frequency hopping قبل ارسال البيانات و سيتم
القفز إلى القناة التالية بعد كل عمليتي ارسال للبيانات كما هو واضح في
الكود التالي :
// Each packet is repeated twice on the same // channel, hence >> 1 // We're not strictly repeating them, rather we // send new packet on the same frequency, so the // receiver gets the freshest command. As receiver // hops to a new frequency as soon as valid packet // received it does not matter that the packet is // not the same one repeated twice - nobody checks this uint8_t rf_ch = rf_channels[rf_ch_num >> 1]; rf_ch_num++; if (rf_ch_num >= 32) rf_ch_num = 0; // Serial.print(rf_ch); Serial.write("\n"); radio.write_register(RF_CH, rf_ch); radio.flush_tx(); radio.write_payload(buf, 16); //radio.ce(HIGH); delayMicroseconds(15); //radio.ce(LOW);
و أخيرا اتمنى من الله ان يكون هذا المقال ببساطته نافعا لكم و انتظروا المقال القادم لبناء 4ch rc receiver لهذا المشروع .
بناء 4ch RC Receiver متوافق مع بروتوكول WLToys V202
2 التعليقات
إضغط هنا لـ التعليقاتالسلام عليكم
ردشكرا لهذا المشروع الرائع ولاكن واجهتني مشكلة مع مكتبة V202 وكيفية اضافتها للبرنامح
وهل كود المستلم يعمل مع الارسال يصورة سليمة
وعليكم السلام
رداهلا بك اخي الكريم في مدونتنا المتواضعة
كل ما عليك هو فتح المشروع ببرنامج Arduino IDE و سيتم اضافة جميع الملفات للمشروع ولن يحتاج إلى أي مكتبات خارجية.
نعم يعمل المستلم مع المرسل بصورة سليمة 100%
ملاحظة : انصحك بتنفيذ الاصدار الجديد من المشروع تحت مسمى FalconRC 4X لما به من ميزات متقدمة
تحويل كودإخفاء محول الأكواد الإبتساماتإخفاء