شهدت شريحة الأردوينو في الآونة الأخيرة انتشاراً واسعاً بالأخص في مجال المعدات الالكترونية و الروبوتات وذلك بسبب بساطة استخدامها وسعرها المنخفض، ولكن هل يمكن لشريحة الأردوينو أن تقوم بمفردها بإنشاء روبوت معقد كروبوت يتحرك بشكل تلقائي ويرسم خريطة للبيئة المحيطة به؟ من المؤكد أن الجواب لا، لأن شريحة الأردوينو الأكثر شيوعاً UNO أو MEGA مثلاً تحوي على متحكمات الـAVR بإمكانات معالجة لا تناسب هذه التطبيقات المعقّدة وبالتالي لا يمكننا إجراء تطبيقات معالجة صورة عليها.
إذاً، هل من الممكن استخدام هذه الشريحة للتطبيقات عالية المستوى؟ نعم يمكن استخدامها في جزء من هذه التطبيقات، مثلاً لربط المحركات والمشغلات والحساسات التابعة للروبوت و إرسالها إلى حاسوب شخصي أو حاسوب مصغر كشريحة الراسبيري الذي سيقوم بالمعالجة المعفّدة.
بما أن نظام الـROS يُستخدَم للروبوتات عالية المستوى فيمكننا مثلاً استخدامه لمعالجة الصورة واستخدام الأردوينو لأخذ قراءات الحساسات ولكن السؤال كيف يمكننا تبادل المعلومات الحساسات التي قام الأردوينو بتحصيلها ونظام الـROS؟
ما هو rosserial ؟
يتم تبادل المعلومات عبر حزمة تُدعَى rosserial. يمكننا تعريف حزمة rosserial على أنها بروتوكول اتصال لإرسال المعلومات عبر الواجهة التسلسلية (serial interface) .يمكن تمثيل نظام الـrosserial عبارة عن rosserial_server وهو يمثل الحاسوب الشخصي PC وفيه نظام ROS الذي يتلقى المعلومات من الـrosserial_client وهو عبارة عن المتحكم المصغر الذي يستقبل البيانات من الحساسات ويقوم بإرسالها إلى الـserver عبر رسائل نظام الـROS. ومن الممكن التعبير عن الـrosserial_server بأنها عقدة ناشرة (Publisher node) وبأن الـrosserial_client عقدة متابعة (subscriber node) ومن الممكن العكس أحياناً. يتوفر الـ rosserial_client لأكثر من عائلة من المتحمات ومنها الأردوينو وأيضاً STM32 وembeddedlinux وغيرها. وأما rosserial_server فهو متوفر بنسختين إما بلغة البايثون أو لغة سي بلس بلس.
الصورة مقتبسة من ROS Integration for Miniature Mobile Robots
ستكون هذه المقالة عبارة عن شرح كيفية تنصيب واجهة الأردوينو ومكاتب الـrosserial.
تنصيب حزمة الـrosserial على نظام الـUbuntu
لتنصيب أي حزمة على نظام الـubuntu هناك طريقتان:
- إما عبر تعليمة apt-get .
أي لتنصيب حزمة الـrosserial على نظام ROS من إصدار Kinect نكتب التعليمة:
sudo apt-get install ros-kinectic-rosserial
- أو عبر نسخ الكود من المصدر.
بداية علينا أن نُنشِئ مجلد فارغ داخل منطقة العمل(workspace) في ROS ولنفترض بأن اسم المجلد هو rosserial_ws بداخله مجلد آخر باسم src فنكتب التعليمة :
mkdir -p ~/rosserial_ws/src
ثم ننتقل إلى المجلد src:
cd ~/rosserial_ws/src
ضمن هذا المسار نضع تعليمة نسخ الكود من المصدر وهي:
git clone https://github.com/ros-drivers/rosserial.git
بعد تنصيب الحزمة يلزمنا إجراء بناء للحزم داخل منطقة العمل ،ننتقل إلى المجلد الأصلي rosserial_ws :
cd ~/rosserial_ws
ومن ثم نكتب تعليمة catkin_make إضافة إلى أنها تقوم ببناء للحزم تقوم أيضاً بتوليد ملفات إضافية كـمجلد الـ build و مجلد الـdevel:
catkin_make
ولكن الحزمة التي قمنا بتنصيبها غير مرئية لبيئة الـROS لذا نقوم بكتابة التعليمة التالية لجعل الحزمة مرئية للنظام:
source ~/rosserial_ws/devel/setup.bash
تنصيب مكتبة ros_lib على واجهة الأردوينو
لكتابة أكواد أردوينو للتخاطب مع نظام ROS علينا تنصيب مكتبة ros_lib وذلك عبر الخطوات التالية:
- من واجهة Arduino، نضغط على خيار file ثم preference لنجد مسار الـsketchbook ،نذهب لهذا المسار ونبحث عن مجلد باسم libraries في حال عدم وجوده نقوم بإنشائه.
- نكتب بنافذة سطر أوامر تعليمة:
cd sketchbook/libraries
roscore
- في نافذة جديدة نكتب التعليمة التالية التي ستقوم بتوليد مكتبة ros_lib :
rosrun rosserial_arduino make_library.py
يجب أن نرى الآن أنه أصبحت مكتبة ros_lib ضمن قائمة مكاتب الأردوينو.
المثال الأول: Blinking LED
لنبدأ الآن بأبسط مثال وهو وميض الضوء Blinking LED. سنقوم في هذا الكود بإنشاء عقدة تقوم بمتابعة موضوع (topic) مسؤول عن تغيير حالة الليد الموصول مع المنفذ رقم 13، و يمكننا أن نجد هذا الكود في مكتبة الـ ros_lib عبر اختيار ros_lib -> Blink.
#include <ros.h> #include <std_msgs/Empty.h> ros::NodeHandle nh; void messageCb( const std_msgs::Empty& toggle_msg){ digitalWrite(13, HIGH-digitalRead(13)); } ros::Subscriber<std_msgs::Empty> sub(“toggle _led”, &messageCb ); void setup() { pinMode(13, OUTPUT); nh.initNode(); nh.subscribe(sub); } void loop() { nh.spinOnce(); delay(1); }
لنشرح الكود:
#include <ros.h>
تضمين مكتبة الـROS ضمن برنامج الأردوينو.
#include <std_msgs/Empty.h>
تضمين مكتبة الرسائل التي سيتم التعامل بها بين الـpublisher والـsubscriber. سنكتفي في هذا الكود بكتابة عقدة متابعة ولا حاجة لنا بكتابة عقدة ناشرة لأنه سيتم استخدام رسالة Empty (خالية المحتوى)، وقد تم استخدام الرسائل من هذا النوع لعدم وجود معلومات حقيقية سيتم تداولها.
يمكن تمثيل العملية التي تتم بالمخطط التالي:
ros::NodeHandle nh
هي الآلية التي يتواصل بها البرنامج مع النظام. وتقوم بإنشاء هذا البرنامج كعقدة في ROS .
void messageCb( const std_msgs::Empty& toggle_msg){
digitalWrite(13, HIGH-digitalRead(13));
}
إنشاء تابع استدعاء للموضوع المتعلق بتشغيل و إطفاء الليد فعند ورود قيمة إلى هذا التابع يُنفَّذ هذا التابع.
ros::Subscriber<std_msgs::Empty> sub(“toggle _led”, &messageCb )
إنشاء متابع باسم toggle_led أما البارامتر الثاني هو تابع الاستدعاء.
pinMode(13, OUTPUT)
تعريف القطب 13 على أنه مخرج.
nh.initNode()
تهيئة العقدة.
nh.spinOnce()
يقوم بالتحقق فيما إذا كان هناك استدعاء للخدمة callbacks/service calls وتكمن فائدته في قدرته على التحكم في معدل التحديثات في الـROS. تتبع الـspinOnce لمفهوم أكثر تعقيداً يستخدمه الـROS.
nh.subscribe(sub)
استدعاء عقدة المتابع.
لإجراء تشغيل للكود نفتح نافذة سطر أوامر ونكتب:
roscore
نجري تشغيل لتطبيق الـrosserial client الذي يقوم بتمرير الرسائل من الأردوينوإلى نظام الـROS.
rosrun rosserial_python serial_node.py /dev/ttyUSB0
dmesg
لتشغيل الليد نكتب التعليمة:
rostopic pub toggle_led std_msgs/Empty –once
ونرى كما في الصورة بأن الليد يعمل ثم ينطفئ .
بشكل عام إذا أردنا كتابة الـpublisher على شكل كود يمكن أخذ الكود التالي كقالب:
#include <ros.h> ros::NodeHandle nh; std_msgs::String str_msg; ros::Publisher pub("any_topic", &str_msg); void setup(){ ... nh.advertise(pub); ... } void loop() { pub.publish( &str_msg ); nh.spinOnce(); }
أي علينا بالبداية:
- تضمين مكتبة الـros.
- إنشاء عقدة للتواصل مع نظام ROS.
- إنشاء عقدة ناشرة (publisher node) نمرر لها برامترين الأول يرمز إلى اسم الموضوع(topic) والبارامتر الثاني يمثل تابع الاستدعاء(callback function).
- استدعاء الناشر الذي تم إنشاؤه في الخطوة السابقة.
المثال الثاني: Motor Controller
سننتقل الان لكود آخر أكثر صعوبة، لنفترض أنه لدينا روبوت بعجلتين نريد التحكم بهذا الروبوت عن طريق نظام الـROS .مانحتاجه من عتاد صلب هو:
- شريحة أردوينو.
- Motor Driver(دارة قيادة محرك).
- محركات DC.
يعتمد تصميم Motor Driver على شريحة متكاملة L298 تحوي على 2 H-bridge ،تحوي على أربعة أقطابInput تستخدم لتفعيل الترانزستورات وقطبي Enable عند تفعيله يُفعَّل الجسر التابع له ومخرجين Out1 و Out2 لوصل المحرك بين طرفيهما. يُبيّن الشكل التالي البنية الداخلية للشريحة المتكاملة L298:
يعتمد مبدأ هذه الشريحة على استخدام H-bridge للتحكم بجهة التيار، فإذا كان الهدف التحكم بجهة دوران المحرك نقوم بعكس القطبية بين المداخل فمثلاً نريد دوران المحرك إلى اليمين (فرضياً) فنقوم بتفعيل الترانزستورات 1&4 وإذا أردنا دورانه بالجهة المعاكسة نفعل الترانزستورات 3&2 كما الشكل التالي.
نقوم بوصل المدخل الأول والثاني وقطب التمكين الأول إلى أحد أقطاب لوحة الأردوينو والمخرج الأول إلى المحرك الأول ونقوم بتوصيل المدخل الثالث والرابع وقطب التمكين الثاني إلى أحد أقطاب الأردوينو والمخرج الثاني إلى المحرك الثاني.
ما نريده هنا هو التحكم بسرعة المحرك لذا علينا تغيير جهد المدخل عن طريق(Pulse width modulation(PWMحيث تتراوح هذه القيمة بين 0 و255 والتي تكافئ الـduty التي تتراوح قيمتها بين 0%حتى 100%، فإذا كان المحرك يدور بسرعة أعظمية أي PWM=100 و إذا أردنا المحرك أن يتوقف عن الدوران PWM=0.
في نظام الـROS لإرسال قيم سرعات معينة إلى المحركات هناك موضوع يدعى cmd_vel .ونوع هذه الرسائل هي Twist موجودة ضمن حزمة تدعى geometry_msgs .
يُبيّن الشكل التالي المخطط الصندوقي للدارة:
//Code Authors: //* Ahmed A. Radwan (author) //* Maisa Jazba #include <ArduinoHardware.h> #include <ros.h> #include <geometry_msgs/Twist.h> #define EN_L 9 #define IN1_L 10 #define IN2_L 11 #define EN_R 8 #define IN1_R 12 #define IN2_R 13 double w_r=0, w_l=0; //wheel_rad is the wheel radius ,wheel_sep is double wheel_rad = 0.0325, wheel_sep = 0.295; ros::NodeHandle nh; int lowSpeed = 200; int highSpeed = 50; double speed_ang=0, speed_lin=0; void messageCb( const geometry_msgs::Twist& msg){ speed_ang = msg.angular.z; speed_lin = msg.linear.x; w_r = (speed_lin/wheel_rad) + ((speed_ang*wheel_sep)/(2.0*wheel_rad)); w_l = (speed_lin/wheel_rad) - ((speed_ang*wheel_sep)/(2.0*wheel_rad)); } ros::Subscriber<geometry_msgs::Twist> sub("cmd_vel", &messageCb ); void Motors_init(); void MotorL(int Pulse_Width1); void MotorR(int Pulse_Width2); void setup(){ Motors_init(); nh.initNode(); nh.subscribe(sub); } void loop(){ MotorL(w_l*10); MotorR(w_r*10); nh.spinOnce(); } void Motors_init(){ pinMode(EN_L, OUTPUT); pinMode(EN_R, OUTPUT); pinMode(IN1_L, OUTPUT); pinMode(IN2_L, OUTPUT); pinMode(IN1_R, OUTPUT); pinMode(IN2_R, OUTPUT); digitalWrite(EN_L, LOW); digitalWrite(EN_R, LOW); digitalWrite(IN1_L, LOW); digitalWrite(IN2_L, LOW); digitalWrite(IN1_R, LOW); digitalWrite(IN2_R, LOW); } void MotorL(int Pulse_Width1){ if (Pulse_Width1 > 0){ analogWrite(EN_L, Pulse_Width1); digitalWrite(IN1_L, HIGH); digitalWrite(IN2_L, LOW); } if (Pulse_Width1 < 0){ Pulse_Width1=abs(Pulse_Width1); analogWrite(EN_L, Pulse_Width1); digitalWrite(IN1_L, LOW); digitalWrite(IN2_L, HIGH); } if (Pulse_Width1 == 0){ analogWrite(EN_L, Pulse_Width1); digitalWrite(IN1_L, LOW); digitalWrite(IN2_L, LOW); } } void MotorR(int Pulse_Width2){ if (Pulse_Width2 > 0){ analogWrite(EN_R, Pulse_Width2); digitalWrite(IN1_R, LOW); digitalWrite(IN2_R, HIGH); } if (Pulse_Width2 < 0){ Pulse_Width2=abs(Pulse_Width2); analogWrite(EN_R, Pulse_Width2); digitalWrite(IN1_R, HIGH); digitalWrite(IN2_R, LOW); } if (Pulse_Width2 == 0){ analogWrite(EN_R, Pulse_Width2); digitalWrite(IN1_R, LOW); digitalWrite(IN2_R, LOW); } }
بعد حقن الكود في شريحة الأردوينو ننتقل إلى التحكم بالروبوت من طرف نظام ROS وذلك عن طريق Package موجود بالنظام يدعى teleop_twist_keyboard والتي تسمح بالتحكم بالسرعة الخطيّة للروبوت(الحركة إلى الأمام و الخلف) والسرعة الزاويّة على المحور z. فتقوم بإرسال رسائل إلى العجلات من نوع Twist عبر الموضوع cmd_vel .
نكتب في نافذة سطر الأوامر:
rosrun teleop_twist_keyboard teleop_twist_keyboard.py
عندها ستظهر نافذة بالشكل:
u:لرسم دائرة باتجاه اليسار.
i: المشي بخط مستقيم للأمام .
o:لرسم دائرة باتجاه اليمين.
j:الدوان عكس عقارب الساعة.
k:إيقاف كافة المحركات.
l:الدوران مع عقارب الساعة.
m:لرسم دائرة باتجاه اليسار بشكل خلفي.
, : السير بخط مستقيم إلى الخلف.
. :لرسم دائرة باتجاه اليسار بشكل خلفي.
رأينا في هذه المقالة أهمية إجراء ربط بين شريحة الأردوينو و نظام ROS ، لذا قمنا بالبداية بتنصيب برنامج الأردوينو ومن ثم الحزمة اللازمة للتواصل بين النظام والشريحة وهو البروتوكول rosserial ومن ثم المكتبة ros_lib لتمكين كتابة أكواد أردوينو للتخاطب مع نظام ROS، ومن ثم قمنا بعرض مثال وميض الليد لننتقل إلى كود أكثر صعوبة وهو تحريك روبوت بعجلتين.
السلام عليكم
فعلا الموضوع في غاية من الأهمية و أنا عندي بعض الأسئلة
كيف يمكن لي أن أستعمل برنامج ROS و كارت أردوينو و bras manipulateur للحصول علي روبوت يستطيع حمل أشياء بفرده
و شكرا
وعليكم السلام ورحمة الله
أظن ستجد بعض الأفكار في هذه المقابلة لفريق قام باستخدام ROS في شيء مشابه جداً
https://atadiat.com/ar/engineering-spotlight-multi-agent-robots-team-interview/