بناء 4ch RC Receiver متوافق مع بروتوكول WLToys V202

Greeting
بسم الله الرحمن الرحيم , و الصلاة و السلام على أشرف الأنبياء و المرسلين نبينا محمد وعلى آله وصحبه أجمعين اللهم لا سهل إلا ماجعلته سهلاً وأنت تجعل الحزن إذا شئت سهلاً.
3D Pcb 4ch Receiver Ver 1.1

مقدمة

تكلمت في تدوينة سابقة عن بناء 4Channel RC Transmitter متوافق مع بروتكول WLToys V202 لكن لم اتطرق لكيفية بناء 4ch RC Receiver متوافق معه و بصراحة تعمدت أن افصل الموضوعين عن بعض لتسهيل مناقشتهم وفهمهم بشكل افضل .


1- المخطط النظري


قمت ببناء التصميم على نواة الـ Arduino المتحكم ATmega328 لكن إن لم يتوفر لديك فبإمكانك إستخدام ATmega168 أو حتى ATmega8 فالكود صغير نسبيا لكن الأفضل إستخدام ATmega328 لأنني أنوي في الأيام القادمة تحديث الكود لتحويل الـ
Receiver إلى Flight Controller بعد إضافة 6DOF 3-Axis Accelerometer and Gyroscope إليه إن شاء الله .

المخطط النظري باستخدام الاردوينو :


المواصفات

  • المتحكم المستخدم ATmega328P و يتوجب عليك حرق محمل الإقلاع Bootloader عليه لتحويله إلى Arduino قبل تركيب المديول nRF24L01 .
  • تعمل القنوات من 1 حتى 4 بنمط PWM 50Hz أما القناة رقم 5 فهي غير مفعلة ضمن البرنامج حاليا.
  • دعم ميزة Failsafe الطيران الأمن وهذه الميزة تخولك وضع قيم افتراضية يقوم المستقبل بإخراجها في حال انقطاع الاتصال مع المرسل ويعمل المفتاح اللحظي S1 على تخزين هذه القيم في الذاكرة .
  • الـ jumper SJ1 يحدد نظام العمل هل هو V-tail Mixer أو Normal و يستخدك الـ V-tail Mixer في كل من الطائرات Delta wing and Helicopters
  • يقوم المأخذ Lamp بقيادة بواعث ضوئية Led في طائرتك و عند تفعيله يومض البواعث بشكل مشابه للطائرات المدنية.
  • منفذ I2C 3.3V لدعم أجهزة الإستشعار مثل WiiMotionPlus, WiiNunchuk, MEMs gyros, barometers and accelerometers
  • المنفذ التسلسلي لتحميل البرامج الثابتة وتطبيقات القياس عن بعد Telemetry


شرح الكود

 في البداية تمت تهيئة المداخل و المخارج
void setup() {
  // SS pin must be set as output to set SPI to master !
  pinMode(SS, OUTPUT);
  pinMode(GREEN_LED_pin, OUTPUT);  
  pinMode(Servo1_OUT, OUTPUT); //Servo1
  pinMode(Servo2_OUT, OUTPUT); //Servo2
  pinMode(Servo3_OUT, OUTPUT); //Servo3
  pinMode(Servo4_OUT, OUTPUT); //Servo4
  pinMode(Servo5_OUT, OUTPUT); //Servo5
  pinMode(Lamp_OUT, OUTPUT);   //Lamp
  pinMode(MODE_pin, INPUT_PULLUP);
  pinMode(FS_BTN, INPUT_PULLUP);

  // Set CS pin to D9 and CE pin to D10
  wireless.setPins(CS_pin, CE_pin);
  protocol.init(&wireless);
#if DEBUG==1
  Serial.begin(115200);
  Serial.println("Start");
#endif
  INIT_SERVO_DRIVER();
}

الدالة INIT_SERVO_DRIVER تعمل على ضبط إعدادات المؤقت العداد Timer1 لتوليد فاصل زمني 20ms و في مقاطعة طفحان المؤقت يتم توليد الـ PWM على المخارج برمجيا عن طريق الكود
void INIT_SERVO_DRIVER(void)
{
  TCCR1B = 0x00;   //stop timer
  TCNT1H = 0x00;   //setup
  TCNT1L = 0x00;
  ICR1   = 40000;   // used for TOP, makes for 50 hz

  TCCR1A = 0x02;   
  TCCR1B = 0x1A; //start timer with 1/8 prescaler for 0.5us PPM resolution
  #ifdef TIMSK1
  TIMSK1 = (1<<TOIE1);   
  #else
  TIMSK = (1<<TOIE1); // for ATmega8
  #endif
} 
//****************************************************

ISR(TIMER1_OVF_vect)
{
  unsigned int us; 

  Servo_Ports_LOW;

  Servo_Number++; // jump to next servo
  if (Servo_Number>4) // back to the first servo 
  {
    total_ppm_time = 0; // clear the total servo ppm time
    Servo_Number = 0;
  }

  if (Servo_Number == MAX_CH)  // Check the servo number. 
    //Servos accepting 50hz ppm signal, this is why we are waiting for 20ms before second signal brust. 
    us = 40000 - total_ppm_time; //wait for total 20ms loop.  waiting time = 20.000us - total servo times
  else
    us = Servo_Buffer[Servo_Number];

  total_ppm_time += us; // calculate total servo signal times.

  switch (Servo_Number) {
  case 0:
    Servo1_OUT_HIGH;
    break;
  case 1:
    Servo2_OUT_HIGH;
    break;
  case 2:
    Servo3_OUT_HIGH;
    break;
  case 3:
    Servo4_OUT_HIGH;
    break;
  case 4:
    Servo5_OUT_HIGH;
    break;
  }

  TCNT1 = 40000 - us;
}

الدالة check_failsafe_button تتحقق هل المفتاح اللحظي الـ Push Buton S1 تم الضغط عليه أم لا فإن تم الضغط عليه مطولا لمدة 2 ثانية سيتم إستدعاء الدالة save_failsafe_values و بعدها ستقوم بعمل وميض للباعث الضوئي الأخضر لتعلمك بأنه تم تخزين قيم الـ failsafe  .
void check_failsafe_button(void) {
  unsigned long loop_time;
  if (digitalRead(FS_BTN)==0) { // Check the button
  Green_LED_OFF;
    time = millis();  //set the current time
    loop_time = time;
    // wait for button reelase if it is already pressed.
    while ((digitalRead(FS_BTN)==0) && (loop_time < time + 2000)) { 
      loop_time = millis(); 
    }
    if (digitalRead(FS_BTN)==0) {
      save_failsafe_values();
      for(uint8_t i = 0; i < 4; i++) {
        Green_LED_ON;
        delay(100);
        Green_LED_OFF;
        delay(100);
      }
    }
  }
}

الدالة subtrim تعمل على تصحيح نسبة الخطاء في عصي التحكم الموجودة في الـ Transmitter (  أظن أنك تقول في خاطرك الأن لماذا أتكلف عناء أرسل هذه القيم و بالإمكان ان تتم  معالجتها في الـ Transmitter ؟.. 
بصراحة لأنني استخدم جهاز التحكم الأساسي من شركة WLToys و بروتوكول نقل البيانات يفرض علي أن أقوم بمعالجة subtrim في الـ Receiver لعدم معالجتها في الـ Transmitter ).

uint8_t subtrim(int8_t Val, int8_t Trim) {
  int ret = Val;
  ret += Trim; 
  if(ret < -127) ret = -127;
  else if( ret > 127) ret = 127; 
  ret = map(ret, -127, 127, 0, 255);
  return lowByte(ret);
}

الدالة reverse تعمل على عكس القيمة المدخلة إليها أما الدالة mixer فتقوم بعمل مزج بين قناتين وكلا الدالتين يتم استخدامهم في اجرائية V-tail Mixer في حال تفعيل العمل بأسلوب V-tail Mixer

uint8_t reverse(uint8_t val) {
  int ret = ((int)val - 127) * -1 + 127; 
  if(ret < 0)ret = 0;
  else if(ret > 255) ret = 255;
  return lowByte(ret);
}
//****************************************************

uint8_t mixer(uint8_t input1, uint8_t input2) {
  int out = ((input1 - 127) + (input2 - 127)) + 127;
  if(out < 0) out = 0;
  //else if(out > 255) out = 255;
  return lowByte(out);
}

بعد أن تعرفنا على الدوال الأساسية في برنامجنا وعلى وظيفة كل دالة سيسهل علينا فهم ما يجري في الحلقة الرئيسية Loop
 في البداية نتحقق إن كانت هناك بيانات جديدة قد وصلتنا من الـ  Transmitter
في حال وصول البيانات يتم التحقق من اسلوب العمل هل هو V-tail Mode أم Normal Mode فإن كان الأول فسيتم العمل بالترتيب التالي :
  1.  إستدعاء الدالة subtrim لكل قناة على حدى بإستثناء القناة throttle. 
  2.  إن كانت القناة تحتاج لعكس قيمتها يتم إستدعاء الدالة reverse.
  3.  يتم استتدعاء الدالة mixer لمزج القناتين المحددتين وخرجها يقع ضمن المجال 0..255
  4.  يتم تحويل القيمة من 0..255 إلى 1501..4499 بإستدعاء الدالة map. 
  5.  وأخيرا يتم تخزين القيمة الجديدة للقناة في Servo_Buffer ليتم اخراجها على هيئة PWM للـ Flight Controller.
ملاحظة : ميزة الـ V-tail mixer تحتاج قناتين محددتين لتقوم بعمل المزج بينهم و عادتا تكون القناة الأولى هي pitch
أما القناة الثانية فيتم تحديدها من قبل المستخدم و تكون عادتا roll أو yaw و في اعلى البرنامج ستجد الموجه التالي تستطيع أن تحدد من خلاله القناة التي ترغب بإدخالها على المازج
#define V_TAIL ROLL // ROLL or YAW


 و إن كان Normal Mode فسيتم العمل بالترتيب التالي :

  1. إستدعاء الدالة subtrim لكل قناة على حدى بإستثناء القناة throttle . 
  2. يتم تحويل القيمة من 0..255 إلى 1501..4499 بإستدعاء الدالة map . 
  3. أخيرا يتم تخزين القيمة الجديدة للقناة في Servo_Buffer ليتم اخراجها على هيئة PWM للـ Flight Controller .
في حال انقضاء 40ms لعدم وصول أي بيانات جديدة يتم استدعاء الدالة load_failsafe_values و يبداء الباعث الضوئي الأخضر بالوميض بشكل بطيء أما إن وصلت قبل إنقضاء هذا الزمن سيومض بشكل سريع .
 

void loop() {
  time = millis();
  uint8_t value = protocol.run(&rxValues);

  if(value == BIND_IN_PROGRESS) {
    if(!bind_in_progress) {
      bind_in_progress = true;
#if DEBUG==1
      Serial.println("Bind in progress");
#endif
    }
  }
  else if(value == BOUND_NEW_VALUES) {
    last_pack_time = time; // record last package time
    failsafeMode = false;

    if (digitalRead(MODE_pin) == 0) { // check V-Tail Mixer Mode
      // do the v-tail mixing
      // input 1 : elevator(pitch)
      // input 2 : aileron(roll) or rudder(yaw)

#if V_TAIL == ROLL
      Servo_Buffer[AILERON] =  map(mixer(
      subtrim(rxValues.pitch, rxValues.trim_pitch), 
      subtrim(rxValues.roll, rxValues.trim_roll)), 0, 255, 1501, 4499);

      Servo_Buffer[ELEVATOR] = map(mixer(reverse(
      subtrim(rxValues.pitch, rxValues.trim_pitch)),
      subtrim(rxValues.roll, rxValues.trim_roll)), 0, 255, 1501, 4499);

      Servo_Buffer[RUDDER] = map(subtrim(rxValues.yaw, rxValues.trim_yaw), 0, 255, 1501, 4499);
#else
      Servo_Buffer[RUDDER] =  map(mixer( 
      subtrim(rxValues.pitch, rxValues.trim_pitch), 
      subtrim(rxValues.yaw, rxValues.trim_yaw)), 0, 255, 1501, 4499);

      Servo_Buffer[ELEVATOR] = map(mixer(reverse(
      subtrim(rxValues.pitch, rxValues.trim_pitch)),
      subtrim(rxValues.yaw, rxValues.trim_yaw)), 0, 255, 1501, 4499);

      Servo_Buffer[AILERON] = map(subtrim(rxValues.roll, rxValues.trim_roll), 0, 255, 1501, 4499);
#endif

    } 
    else {
      Servo_Buffer[AILERON]  = map(subtrim(rxValues.roll, rxValues.trim_roll), 0, 255, 1501, 4499);
      Servo_Buffer[ELEVATOR] = map(subtrim(rxValues.pitch, rxValues.trim_pitch), 0, 255, 1501, 4499);
      Servo_Buffer[RUDDER]   = map(subtrim(rxValues.yaw, rxValues.trim_yaw), 0, 255, 1501, 4499);
    }

    Servo_Buffer[THROTTLE] = map(rxValues.throttle, 0, 255, 1501, 4499);
    Servo_Buffer[AUX1] = rxValues.flags;
    
    check_failsafe_button();
    
#if DEBUG==1
    Serial.print("ail : ");    
    Serial.print(Servo_Buffer[AILERON]);
    Serial.print("\t ele : "); 
    Serial.print(Servo_Buffer[ELEVATOR]);
    Serial.print("\t thr : "); 
    Serial.print(Servo_Buffer[THROTTLE]);
    Serial.print("\t rud : "); 
    Serial.println(Servo_Buffer[RUDDER]);
#endif
  } 
  else if(time-last_pack_time > 40 && !failsafeMode) {
    failsafeMode = true;
    last_pack_time = time;
    load_failsafe_values(); // Load Failsafe positions from EEPROM.
  }
  
  if(failsafeMode) {
    if(time - last_led_time > 200) {
      last_led_time = time;
      Green_LED_TOG;
    }
  } else {
    if(time - last_led_time > 50) {
      last_led_time = time;
      Green_LED_TOG;
    }
  }
  
  if(Servo_Buffer[AUX1] & FLAG_LED) {
    if(time > last_flasher_time) {
      last_flasher_time = time + ledFlasher[ledFlasherIndex]; 
      if(++ledFlasherIndex == sizeof(ledFlasher)/2) ledFlasherIndex = 0;
      ledFlasherState ^= true;
      if(ledFlasherState) Lamp_OUT_HIGH; 
      else Lamp_OUT_LOW;
    }
  } 
  else {
    Lamp_OUT_LOW;
    ledFlasherState = false;
    ledFlasherIndex = 0;
  }
  
  
} /* END MAIN LOOP */
 
و هذا فيديو يوضح تجربة الـ 4ch RC Receiver



تحميل ملفات المشروع


وهكذا لكل بداية نهاية ، وخير العمل ما حسن آخره وخير الكلام ما قل ودل وبعد هذا الجهد المتواضع أتمنى أن أكون موفقا في شرحي لهذا المشروع موضحا أهم التفاصيل لهذا الموضوع الشائق الممتع ، وفقني الله وإياكم لما فيه صالحنا جميعا . 
share

29 التعليقات

إضغط هنا لـ التعليقات
احمد قاسم
المدير
29 يوليو 2015 في 4:17 م ×

شاكر جدا لمجهود حضراتكم المحترم

رد
avatar
horizon4electronics
المدير
30 يوليو 2015 في 12:14 ص ×

العفو اخي أحمد و اهلا بك في مدونتنا المتواضعة :)
ونتمنى ان يكون المحتوى العلمي يرقى للمستوى

رد
avatar
Unknown
المدير
14 مارس 2016 في 1:22 م ×

السلام عليكم
موضوع اكثر من رائع ومفيد بخاصة لمحبي صانعي الطائرات الاسلكية
هل يعمل المستلم هذا مع موضوع الذي تم طرحه في الموقع FalconRC 4X Transmitter بستخدام الاردينيو وهل يمكن زيادة عدد القنوات في المرسل والمستلم

رد
avatar
horizon4electronics
المدير
14 مارس 2016 في 10:04 م ×

وعليكم السلام ورحمة الله وبركاته
اهلا بك اخي الكريم في مدونتنا المتواضعة
نعم يعمل بدون أي مشاكل مع FalconRC 4X Transmitter :-bd
بالامكان تعديل الكود لزيادة عدد القنوات و كنت قد شرحت أهم الأجزاء في الكود حتى يستطيع القارئ تعديل ما يرغب به بدون اي صعوبة .

رد
avatar
Unknown
المدير
22 مارس 2016 في 12:28 م ×

أبداع في العمل شكرا لكل من ساهم في الموضوع وننتضر برنامج جديد مع زيادة في عدد القنوات

رد
avatar
horizon4electronics
المدير
22 مارس 2016 في 10:32 م ×

شكرا أخي الكريم هذه شهادة نعتز بها
و إن شاء الله سيكون الإصدار القادم بمواصفات أعلى و بعدد قنوات أكبر :)

رد
avatar
Unknown
المدير
23 مارس 2016 في 8:37 م ×

اثناء بحثي في الانترنيت وجدت ريمونت بستخدام الاردينو ميكا وعدد قنوات 8 قنوات او اكثر من ذلك ولاكن الصراحة لم اجربه اذا ترغب ارسل لك الرابط مساهمه في هذ الموضوع الشيق لحضرتكم

رد
avatar
horizon4electronics
المدير
24 مارس 2016 في 1:07 ص ×

اهلا بك اخي mos mo و شكرا لإهتمامك ارسل لي الرابط و سأطلع عليه وان كان بالمستوى المطلوب سأنشره على المدونة و جزاك الله عنا كل خير

رد
avatar
Unknown
المدير
24 مارس 2016 في 12:54 م ×

السلام عليكم
هل من طريقة لعمل 6 قنوات للمرسل والمستلم

رد
avatar
Unknown
المدير
24 مارس 2016 في 1:03 م ×

تفضل اخي
http://www.rcgroups.com/forums/showthread.php?t=1833077

رد
avatar
horizon4electronics
المدير
25 مارس 2016 في 2:26 ص ×

للأسف هذا المشروع لا يدعم سوى الـ Trim ولا يدعم تقنية FHSS :(

رد
avatar
horizon4electronics
المدير
25 مارس 2016 في 2:29 ص ×

قريبا سيكون هناك تحديث جديد لمشروع FalconRC Transmitter and Receiver ليدعم الثمانية قنوات + شاشة لعرض البارمترات في الـ Transmitter :)

رد
avatar
Unknown
المدير
26 مارس 2016 في 7:31 م ×

ما شاء الله انت صاحب خبره في مجالك واعرف بهذه الامور
ونحن بانتضار التحديث الجديد FalconRC Transmitter and Receiver
وشكرا

رد
avatar
eshmael
المدير
29 مايو 2016 في 7:19 م ×

مساء الخير استاذي بصراحة اشكرك على المجهود الرائع بطريقة الشرح المميزة وقد استفد منها كثيرا . ويا حبا ذا لو انك تشرح أيضا طريقة اللوحة الالكترونية ال التابعة للمشروع الأنف ذكرهpcb ولك جزيل الشكر

رد
avatar
horizon4electronics
المدير
31 مايو 2016 في 2:08 ص ×

مساء الخير و اهلا بك أخي الكريم في مدونتنا المتواضعة
سعيد جدا لإستفادتك من ما نقدم و هذا شهادة نعتز بها :)
سأقوم ان شاء الله في القريب العاجل بشرح الدارة بشكل ادق و سأحاول تقديم مخططها للربط مع الاردوينو بدل المتحكم حتى تكون اسهل في التنفيذ :-bd

رد
avatar
Unknown
المدير
2 يوليو 2016 في 12:56 م ×

اولا كل عام و الجميع بخير
وثانيا نشكر كل هذا المجهود الرائع خبره ممتازة و شرح ممتاز و في انتظار المزيد ان شاء الله .

رد
avatar
horizon4electronics
المدير
7 يوليو 2016 في 3:21 م ×

كل عام و انت بألف خير و اعاده الله علينا وعليكم بالخير و البركة
سلمت لنا يمناك على كل حرف خطته و على كل كلمة رسمتها :lv
لك ودي وجل تقديري :)

رد
avatar
Unknown
المدير
12 يوليو 2016 في 12:21 ص ×

هندسه في مشكله اني مش عارف اوصل للترانزيستور " IRLML2502 " ممكن اعرف الحل
.

رد
avatar
horizon4electronics
المدير
13 يوليو 2016 في 12:14 ص ×

بامكانك استبداله بأي ترانزستور N channel mosfet ذو تيار 1A او اكثر
او تستطيع استبداله بترانزستور BJT نوع NPN مثل BC337 و تعديل قيمة مقاومة تحديد تيار القاعدة R11 بمقاومة 2.2k

رد
avatar
Unknown
المدير
13 يوليو 2016 في 11:54 م ×

الف شكر يا هندسة علي الافاده.

رد
avatar
Unknown
المدير
15 يوليو 2016 في 5:51 م ×

السلام عليكم ورحمة الله و بركاته
هندسه ممكن التواصل علي الموبيل ضروري تم الانتهاء من تنفيذ البورد و لكن يوجد مشكلة عند رفع bootloader ارجو التواصل مع جزيل الشكر
01100900159

رد
avatar
Unknown
المدير
15 يوليو 2016 في 9:06 م ×

انا متوقف علي برمجة الرسيفر هل هيتم برمجة الشريحة قبل لحامها بال pcb و لا ممكن بعد لحامها و ياريت توضيح الطريقه و الاطراف مع الarduino uno .

رد
avatar
horizon4electronics
المدير
16 يوليو 2016 في 6:37 م ×

وعليكم السلام ورحمة الله وبركاته
عذرا اخي احمد لتأخري بالرد
إذا لم تستطع حل مشكلتك بعد فيمكننا التحدث عبر تطبيق facebook messenger
https://www.facebook.com/Abdullah.m.Jalloul

رد
avatar
horizon4electronics
المدير
16 يوليو 2016 في 6:39 م ×

الفيديو التالي يوضح طريقة برمجة المتحكم باستخدام Arduino UNO
https://www.youtube.com/watch?v=g90xb0nNX50

رد
avatar
Unknown
المدير
16 مارس 2017 في 1:21 ص ×

هو امتى هينزل جزء الflight controller ؟؟

رد
avatar
Unknown
المدير
11 أبريل 2017 في 1:36 ص ×

مجهود عبقرى جدا
و كنت عاوز اسأل عن الجزئية دى "لأنني أنوي في الأيام القادمة تحديث الكود لتحويل الـ
Receiver إلى Flight Controller بعد إضافة 6DOF 3-Axis Accelerometer and Gyroscope إليه إن شاء الله ."
هل بدأت العمل عليهأ و شكرا

رد
avatar
horizon4electronics
المدير
12 أبريل 2017 في 2:05 ص ×

شكرا اخي ميسرة
قمت بتعديل برمجية MultiWii Flight Controller و اضافة مديول nRF24L01 إليها وعند تجربتها ظهرت بعض المشاكل وقمت بحل بعضها لكن ضيق الوقت منعني من تكملتها :(

رد
avatar
Unknown
المدير
14 يونيو 2017 في 10:12 م ×

السلام عليكم ورمضان كريم عند تنفيذ المستقبل وربط السيرفو الاول على منفذ رقم 2 يشتغل بصورة طبيعية يشتغل بتجاهين عند تحريك عصى التتحكم للاعلى والاسفل واما بقية السيرفوات على المنافذ رقم 3 و4 و5 يشتغل باتجاه واحد عند تحريك عصى التحكم بالاتجاهين يتحرك السيرفو باتجاه واحد ويعود الى وضعة الاصلي ممكن حل لهذه المشكلة وجزاكم الله خيرا

رد
avatar
Unknown
المدير
14 يونيو 2017 في 11:08 م ×

السلام عليكم ورمضان كريم عند تنفيذ المستقبل وربط السيرفو على منفذ رقم 2 لاردوينو يشتغل بالاتجاهين عن تحريك عصى التحكم الاعلى والاسفل وعند ربط السيرفوات على المنافذ 3و 4 و5 بيشتغل باتجاه واحد فقط عند تحريك عصى التحكم لاعلى والاسفل يعني يتحرك باتجاه واحد ويعود لوضعة الاصلى ممكن اعرف اية المشكلة وجزاكم الله خيرا

رد
avatar
شكرا لك ولمرورك