دليل البدء السريع لنظام التشغيل ROS (نظام تشغيل الروبوت)
مقدمة ROS (مع تسميات توضيحية) من Open Robotics على Vimeo.
ما هو ROS؟
يُعد نظام تشغيل الروبوت (ROS) إطار عمل مفتوح المصدر يستخدم على نطاق واسع في أبحاث الروبوتات والصناعة. يوفر ROS مجموعة من المكتبات والأدوات لمساعدة المطورين على إنشاء تطبيقات الروبوت. تم تصميم ROS للعمل مع منصات روبوتية متنوعة، مما يجعله أداة مرنة وقوية لعلماء الروبوتات.
الميزات الرئيسية لـ ROS
-
هندسة معيارية: يتمتع ROS بهندسة معيارية، مما يسمح للمطورين ببناء أنظمة معقدة من خلال الجمع بين مكونات أصغر قابلة لإعادة الاستخدام تسمى العقد. تؤدي كل عقدة عادةً وظيفة محددة، وتتواصل العقد مع بعضها البعض باستخدام الرسائل عبر المواضيع أو الخدمات.
-
برامج وسيطة للاتصالات: يوفر ROS بنية تحتية قوية للاتصالات تدعم الاتصال بين العمليات والحوسبة الموزعة. يتحقق ذلك من خلال نموذج النشر والاشتراك لتدفقات البيانات (المواضيع) ونموذج الطلب والاستجابة لاستدعاءات الخدمة.
-
تجريد الأجهزة: يوفر نظام التشغيل الروبوتي (ROS) طبقة من التجريد فوق الأجهزة، مما يمكّن المطورين من كتابة تعليمات برمجية غير مرتبطة بالأجهزة. يتيح ذلك استخدام نفس التعليمات البرمجية مع إعدادات أجهزة مختلفة، مما يسهل التكامل والتجريب.
-
الأدوات والمرافق: يأتي نظام ROS مزودًا بمجموعة غنية من الأدوات والمرافق للتصور وتصحيح الأخطاء والمحاكاة. على سبيل المثال، يتم استخدام RViz لتصور بيانات المستشعر ومعلومات حالة الروبوت، بينما يوفر Gazebo بيئة محاكاة قوية لاختبار الخوارزميات وتصميمات الروبوت.
-
النظام البيئي الواسع: النظام البيئي ROS واسع ويتنامى باستمرار، مع توفر العديد من الحزم لتطبيقات الروبوتات المختلفة، بما في ذلك الملاحة والمناولة والإدراك والمزيد. يساهم المجتمع بنشاط في تطوير وصيانة هذه الحزم.
تطور إصدارات ROS
منذ تطويره في عام 2007، تطور نظام ROS من خلال إصدارات متعددة، يقدم كل منها ميزات وتحسينات جديدة لتلبية الاحتياجات المتزايدة لمجتمع الروبوتات. يمكن تصنيف تطوير ROS إلى سلسلتين رئيسيتين: ROS 1 و ROS 2. يركز هذا الدليل على إصدار الدعم طويل الأجل (LTS) من ROS 1، المعروف باسم ROS Noetic Ninjemys، ويجب أن يعمل الكود أيضًا مع الإصدارات السابقة.
ROS 1 مقابل ROS 2
في حين أن ROS 1 قدم أساسًا قويًا لتطوير الروبوتات، فإن ROS 2 يعالج أوجه القصور فيه من خلال تقديم:
- أداء في الوقت الفعلي: دعم مُحسَّن للأنظمة في الوقت الفعلي والسلوك الحتمي.
- الأمان: ميزات أمان محسّنة للتشغيل الآمن والموثوق في البيئات المختلفة.
- قابلية التوسع: دعم أفضل لأنظمة الروبوتات المتعددة وعمليات النشر واسعة النطاق.
- دعم عبر الأنظمة الأساسية: توافق مُوَسَّع مع أنظمة تشغيل مختلفة تتجاوز Linux، بما في ذلك Windows و macOS.
- اتصال مرن: استخدام DDS لاتصال أكثر مرونة وكفاءة بين العمليات.
رسائل ومواضيع ROS
في نظام ROS، يتم تسهيل الاتصال بين العقد من خلال الرسائل و المواضيع. الرسالة هي بنية بيانات تحدد المعلومات المتبادلة بين العقد، بينما الموضوع هو قناة مسماة يتم عبرها إرسال الرسائل واستقبالها. يمكن للعقد نشر الرسائل في موضوع أو الاشتراك في الرسائل من موضوع، مما يمكنها من التواصل مع بعضها البعض. يتيح نموذج النشر والاشتراك هذا الاتصال غير المتزامن وفصل العقد. عادةً ما ينشر كل مستشعر أو مشغل في نظام روبوتي البيانات في موضوع، والذي يمكن بعد ذلك استهلاكه بواسطة عقد أخرى للمعالجة أو التحكم. لغرض هذا الدليل، سنركز على رسائل الصور والعمق والسحابة النقطية ومواضيع الكاميرا.
إعداد Ultralytics YOLO مع ROS
تم اختبار هذا الدليل باستخدام بيئة ROS هذه، وهي نسخة من مستودع ROS الخاص بـ ROSbot. تتضمن هذه البيئة حزمة Ultralytics YOLO، وحاوية Docker لسهولة الإعداد، وحزم ROS شاملة، وعوالم Gazebo للاختبار السريع. وهي مصممة للعمل مع Husarion ROSbot 2 PRO. ستعمل أمثلة التعليمات البرمجية المتوفرة في أي بيئة ROS Noetic/Melodic، بما في ذلك المحاكاة والعالم الحقيقي.
تثبيت التبعيات
بصرف النظر عن بيئة ROS، ستحتاج إلى تثبيت التبعيات التالية:
-
حزمة ROS Numpy: هذا مطلوب للتحويل السريع بين رسائل صور ROS ومصفوفات numpy.
pip install ros_numpy
-
حزمة Ultralytics:
pip install ultralytics
استخدم Ultralytics مع ROS sensor_msgs/Image
في sensor_msgs/Image
نوع الرسالة يشيع استخدامه في نظام ROS لتمثيل بيانات الصور. يحتوي على حقول للترميز والارتفاع والعرض وبيانات البكسل، مما يجعله مناسبًا لنقل الصور التي تلتقطها الكاميرات أو المستشعرات الأخرى. تُستخدم رسائل الصور على نطاق واسع في التطبيقات الروبوتية لمهام مثل الإدراك البصري، اكتشاف الكائنات، والملاحة.
استخدام الصورة خطوة بخطوة
يوضح مقتطف التعليمات البرمجية التالي كيفية استخدام حزمة Ultralytics YOLO مع ROS. في هذا المثال، نشترك في موضوع الكاميرا، ونعالج الصورة الواردة باستخدام YOLO، وننشر الكائنات المكتشفة في مواضيع جديدة للكشف و التجزئة.
أولاً، قم باستيراد المكتبات الضرورية وقم بإنشاء نموذجين: أحدهما لـ تقسيم وواحد لـ اكتشاف. تهيئة عقدة ROS (بالاسم ultralytics
) لتمكين الاتصال بـ ROS master. لضمان اتصال مستقر، نقوم بتضمين وقفة قصيرة، مما يمنح العقدة وقتًا كافيًا لإنشاء الاتصال قبل المتابعة.
import time
import rospy
from ultralytics import YOLO
detection_model = YOLO("yolo11m.pt")
segmentation_model = YOLO("yolo11m-seg.pt")
rospy.init_node("ultralytics")
time.sleep(1)
تهيئة موضوعين ROS: واحد لـ اكتشاف وواحد لـ تقسيم. سيتم استخدام هذه الموضوعات لنشر الصور المشروحة، مما يجعلها في متناول مزيد من المعالجة. يتم تسهيل الاتصال بين العقد باستخدام sensor_msgs/Image
الرسائل.
from sensor_msgs.msg import Image
det_image_pub = rospy.Publisher("/ultralytics/detection/image", Image, queue_size=5)
seg_image_pub = rospy.Publisher("/ultralytics/segmentation/image", Image, queue_size=5)
أخيرًا، قم بإنشاء مشترك يستمع إلى الرسائل على /camera/color/image_raw
topic ويستدعي دالة رد نداء لكل رسالة جديدة. تتلقى دالة رد النداء هذه رسائل من النوع sensor_msgs/Image
، ويحولها إلى مصفوفة numpy باستخدام. ros_numpy
، يعالج الصور باستخدام نماذج YOLO التي تم إنشاؤها مسبقًا، ويضع عليها التعليقات التوضيحية، ثم يعيد نشرها إلى المواضيع الخاصة بها: /ultralytics/detection/image
للكشف و /ultralytics/segmentation/image
لتقسيم الصور.
import ros_numpy
def callback(data):
"""Callback function to process image and publish annotated images."""
array = ros_numpy.numpify(data)
if det_image_pub.get_num_connections():
det_result = detection_model(array)
det_annotated = det_result[0].plot(show=False)
det_image_pub.publish(ros_numpy.msgify(Image, det_annotated, encoding="rgb8"))
if seg_image_pub.get_num_connections():
seg_result = segmentation_model(array)
seg_annotated = seg_result[0].plot(show=False)
seg_image_pub.publish(ros_numpy.msgify(Image, seg_annotated, encoding="rgb8"))
rospy.Subscriber("/camera/color/image_raw", Image, callback)
while True:
rospy.spin()
رمز كامل
import time
import ros_numpy
import rospy
from sensor_msgs.msg import Image
from ultralytics import YOLO
detection_model = YOLO("yolo11m.pt")
segmentation_model = YOLO("yolo11m-seg.pt")
rospy.init_node("ultralytics")
time.sleep(1)
det_image_pub = rospy.Publisher("/ultralytics/detection/image", Image, queue_size=5)
seg_image_pub = rospy.Publisher("/ultralytics/segmentation/image", Image, queue_size=5)
def callback(data):
"""Callback function to process image and publish annotated images."""
array = ros_numpy.numpify(data)
if det_image_pub.get_num_connections():
det_result = detection_model(array)
det_annotated = det_result[0].plot(show=False)
det_image_pub.publish(ros_numpy.msgify(Image, det_annotated, encoding="rgb8"))
if seg_image_pub.get_num_connections():
seg_result = segmentation_model(array)
seg_annotated = seg_result[0].plot(show=False)
seg_image_pub.publish(ros_numpy.msgify(Image, seg_annotated, encoding="rgb8"))
rospy.Subscriber("/camera/color/image_raw", Image, callback)
while True:
rospy.spin()
تصحيح الأخطاء
قد يكون تصحيح أخطاء عُقد ROS (نظام تشغيل الروبوت) أمرًا صعبًا نظرًا لطبيعة النظام الموزعة. يمكن أن تساعد العديد من الأدوات في هذه العملية:
rostopic echo <TOPIC-NAME>
: يتيح لك هذا الأمر عرض الرسائل المنشورة في موضوع معين، مما يساعدك على فحص تدفق البيانات.rostopic list
: استخدم هذا الأمر لسرد جميع الموضوعات المتاحة في نظام ROS، مما يمنحك نظرة عامة على تدفقات البيانات النشطة.rqt_graph
: تعرض أداة التصور هذه الرسم البياني للاتصال بين العقد، مما يوفر رؤى حول كيفية ترابط العقد وكيفية تفاعلها.- للحصول على تصورات أكثر تعقيدًا، مثل التمثيلات ثلاثية الأبعاد، يمكنك استخدام RViz. برنامج RViz (تصور ROS) هو أداة تصور ثلاثي الأبعاد قوية لنظام ROS. يتيح لك تصور حالة الروبوت الخاص بك وبيئته في الوقت الفعلي. باستخدام RViz، يمكنك عرض بيانات المستشعر (مثل
sensors_msgs/Image
)، وحالات نموذج الروبوت، وأنواع أخرى مختلفة من المعلومات، مما يسهل تصحيح وفهم سلوك نظام الروبوت الخاص بك.
نشر الفئات التي تم الكشف عنها باستخدام std_msgs/String
تتضمن رسائل ROS القياسية أيضًا std_msgs/String
الرسائل. في العديد من التطبيقات، ليس من الضروري إعادة نشر الصورة المشروحة بأكملها؛ بدلاً من ذلك، يلزم فقط الفئات الموجودة في عرض الروبوت. يوضح المثال التالي كيفية استخدام std_msgs/String
الرسائل لإعادة نشر الفئات التي تم الكشف عنها على /ultralytics/detection/classes
topic. هذه الرسائل أخف وزنًا وتوفر معلومات أساسية، مما يجعلها ذات قيمة لتطبيقات مختلفة.
مثال على حالة استخدام
ضع في اعتبارك روبوت مستودع مزود بكاميرا وكائن نموذج الكشف. بدلاً من إرسال صور مشروحة كبيرة عبر الشبكة، يمكن للروبوت نشر قائمة بالفئات المكتشفة كـ std_msgs/String
الرسائل. على سبيل المثال، عندما يكتشف الروبوت كائنات مثل "صندوق" و "منصة نقالة" و "رافعة شوكية"، فإنه ينشر هذه الفئات إلى /ultralytics/detection/classes
topic. يمكن بعد ذلك استخدام هذه المعلومات بواسطة نظام مراقبة مركزي لتتبع المخزون في الوقت الفعلي، أو تحسين تخطيط مسار الروبوت لتجنب العقبات، أو تشغيل إجراءات معينة مثل التقاط صندوق تم اكتشافه. يقلل هذا النهج من النطاق الترددي المطلوب للاتصال ويركز على نقل البيانات الهامة.
سلسلة استخدام خطوة بخطوة
يوضح هذا المثال كيفية استخدام حزمة Ultralytics YOLO مع ROS. في هذا المثال، نشترك في موضوع الكاميرا، ونعالج الصورة الواردة باستخدام YOLO، وننشر الكائنات المكتشفة في موضوع جديد /ultralytics/detection/classes
باستخدام std_msgs/String
الرسائل. الـ ros_numpy
تُستخدم الحزمة لتحويل رسالة ROS Image إلى مصفوفة numpy للمعالجة باستخدام YOLO.
import time
import ros_numpy
import rospy
from sensor_msgs.msg import Image
from std_msgs.msg import String
from ultralytics import YOLO
detection_model = YOLO("yolo11m.pt")
rospy.init_node("ultralytics")
time.sleep(1)
classes_pub = rospy.Publisher("/ultralytics/detection/classes", String, queue_size=5)
def callback(data):
"""Callback function to process image and publish detected classes."""
array = ros_numpy.numpify(data)
if classes_pub.get_num_connections():
det_result = detection_model(array)
classes = det_result[0].boxes.cls.cpu().numpy().astype(int)
names = [det_result[0].names[i] for i in classes]
classes_pub.publish(String(data=str(names)))
rospy.Subscriber("/camera/color/image_raw", Image, callback)
while True:
rospy.spin()
استخدم Ultralytics مع صور عمق ROS
بالإضافة إلى صور RGB، يدعم نظام ROS صور العمق، والتي توفر معلومات حول المسافة بين الكائنات والكاميرا. تعتبر صور العمق ضرورية للتطبيقات الروبوتية مثل تجنب العوائق ورسم الخرائط ثلاثية الأبعاد وتحديد الموقع.
صورة العمق هي صورة يمثل فيها كل بكسل المسافة من الكاميرا إلى الجسم. على عكس صور RGB التي تلتقط اللون، تلتقط صور العمق معلومات مكانية، مما يمكّن الروبوتات من إدراك الهيكل ثلاثي الأبعاد لبيئتها.
الحصول على صور العمق
يمكن الحصول على صور العمق باستخدام أجهزة استشعار مختلفة:
- كاميرات مجسمة: استخدم كاميرتين لحساب العمق بناءً على تباين الصورة.
- كاميرات وقت الرحلة (ToF): قم بقياس الوقت الذي يستغرقه الضوء للعودة من الجسم.
- مستشعرات الضوء المنظم: قم بإسقاط نمط وقياس تشوهه على الأسطح.
استخدام YOLO مع صور العمق
في نظام ROS، يتم تمثيل صور العمق بواسطة sensor_msgs/Image
نوع الرسالة، والذي يتضمن حقولًا للترميز والارتفاع والعرض وبيانات البكسل. غالبًا ما يستخدم حقل الترميز لصور العمق تنسيقًا مثل "16UC1"، مما يشير إلى عدد صحيح غير موقع 16 بت لكل بكسل، حيث تمثل كل قيمة المسافة إلى الكائن. تُستخدم صور العمق بشكل شائع جنبًا إلى جنب مع صور RGB لتوفير رؤية أكثر شمولاً للبيئة.
باستخدام YOLO، من الممكن استخراج ودمج المعلومات من كل من صور RGB وصور العمق. على سبيل المثال، يمكن لـ YOLO اكتشاف الأجسام داخل صورة RGB، ويمكن استخدام هذا الاكتشاف لتحديد المناطق المقابلة في صورة العمق. يتيح ذلك استخراج معلومات عمق دقيقة للأجسام المكتشفة، مما يعزز قدرة الروبوت على فهم بيئته في ثلاثة أبعاد.
كاميرات RGB-D
عند العمل مع صور العمق، من الضروري التأكد من محاذاة صور RGB والعمق بشكل صحيح. توفر كاميرات RGB-D، مثل سلسلة Intel RealSense، صور RGB وعمق متزامنة، مما يسهل دمج المعلومات من كلا المصدرين. في حالة استخدام كاميرات RGB وعمق منفصلة، فمن الضروري معايرتها لضمان المحاذاة الدقيقة.
الاستخدام التدريجي للعمق
في هذا المثال، نستخدم YOLO لتقسيم صورة وتطبيق القناع المستخرج لتقسيم الكائن في صورة العمق. يتيح لنا ذلك تحديد مسافة كل بكسل من الكائن محل الاهتمام من المركز البؤري للكاميرا. من خلال الحصول على معلومات المسافة هذه، يمكننا حساب المسافة بين الكاميرا والكائن المحدد في المشهد. ابدأ باستيراد المكتبات الضرورية، وإنشاء عقدة ROS، وإنشاء نموذج تقسيم وموضوع ROS.
import time
import rospy
from std_msgs.msg import String
from ultralytics import YOLO
rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolo11m-seg.pt")
classes_pub = rospy.Publisher("/ultralytics/detection/distance", String, queue_size=5)
بعد ذلك، حدد دالة رد الاتصال التي تعالج رسالة صورة العمق الواردة. تنتظر الدالة رسائل صورة العمق وصورة RGB، وتحولها إلى مصفوفات numpy، وتطبق نموذج التجزئة على صورة RGB. ثم تستخرج قناع التجزئة لكل كائن تم اكتشافه وتحسب متوسط مسافة الكائن من الكاميرا باستخدام صورة العمق. تحتوي معظم المستشعرات على مسافة قصوى، تُعرف بمسافة القطع، تتجاوزها القيم الممثلة على أنها غير محدودة (np.inf
). قبل المعالجة، من المهم تصفية هذه القيم الخالية وتعيين قيمة لها 0
. أخيرًا، ينشر الكائنات التي تم الكشف عنها جنبًا إلى جنب مع متوسط المسافات إلى /ultralytics/detection/distance
topic.
import numpy as np
import ros_numpy
from sensor_msgs.msg import Image
def callback(data):
"""Callback function to process depth image and RGB image."""
image = rospy.wait_for_message("/camera/color/image_raw", Image)
image = ros_numpy.numpify(image)
depth = ros_numpy.numpify(data)
result = segmentation_model(image)
all_objects = []
for index, cls in enumerate(result[0].boxes.cls):
class_index = int(cls.cpu().numpy())
name = result[0].names[class_index]
mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
obj = depth[mask == 1]
obj = obj[~np.isnan(obj)]
avg_distance = np.mean(obj) if len(obj) else np.inf
all_objects.append(f"{name}: {avg_distance:.2f}m")
classes_pub.publish(String(data=str(all_objects)))
rospy.Subscriber("/camera/depth/image_raw", Image, callback)
while True:
rospy.spin()
رمز كامل
import time
import numpy as np
import ros_numpy
import rospy
from sensor_msgs.msg import Image
from std_msgs.msg import String
from ultralytics import YOLO
rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolo11m-seg.pt")
classes_pub = rospy.Publisher("/ultralytics/detection/distance", String, queue_size=5)
def callback(data):
"""Callback function to process depth image and RGB image."""
image = rospy.wait_for_message("/camera/color/image_raw", Image)
image = ros_numpy.numpify(image)
depth = ros_numpy.numpify(data)
result = segmentation_model(image)
all_objects = []
for index, cls in enumerate(result[0].boxes.cls):
class_index = int(cls.cpu().numpy())
name = result[0].names[class_index]
mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
obj = depth[mask == 1]
obj = obj[~np.isnan(obj)]
avg_distance = np.mean(obj) if len(obj) else np.inf
all_objects.append(f"{name}: {avg_distance:.2f}m")
classes_pub.publish(String(data=str(all_objects)))
rospy.Subscriber("/camera/depth/image_raw", Image, callback)
while True:
rospy.spin()
استخدم Ultralytics مع ROS sensor_msgs/PointCloud2
في sensor_msgs/PointCloud2
نوع الرسالة هي بنية بيانات مستخدمة في نظام التشغيل الروبوتي (ROS) لتمثيل بيانات السحابة النقطية ثلاثية الأبعاد. يعتبر هذا النوع من الرسائل جزءًا لا يتجزأ من تطبيقات الروبوتات، مما يتيح مهام مثل رسم الخرائط ثلاثية الأبعاد والتعرف على الكائنات وتحديد الموقع.
السحابة النقطية عبارة عن مجموعة من نقاط البيانات المحددة داخل نظام إحداثيات ثلاثي الأبعاد. تمثل نقاط البيانات هذه السطح الخارجي لجسم أو مشهد، يتم التقاطه عبر تقنيات المسح ثلاثي الأبعاد. كل نقطة في السحابة لها X
, Y
، و Z
الإحداثيات، التي تتوافق مع موقعها في الفضاء، وقد تتضمن أيضًا معلومات إضافية مثل اللون والشدة.
الإطار المرجعي
عند العمل مع sensor_msgs/PointCloud2
، من الضروري مراعاة الإطار المرجعي للمستشعر الذي تم الحصول منه على بيانات السحابة النقطية. يتم التقاط السحابة النقطية في البداية في الإطار المرجعي للمستشعر. يمكنك تحديد هذا الإطار المرجعي من خلال الاستماع إلى. /tf_static
topic. ومع ذلك، اعتمادًا على متطلبات التطبيق الخاصة بك، قد تحتاج إلى تحويل السحابة النقطية إلى إطار مرجعي آخر. يمكن تحقيق هذا التحويل باستخدام tf2_ros
الحزمة، التي توفر أدوات لإدارة إطارات الإحداثيات وتحويل البيانات بينها.
الحصول على سحب النقاط
يمكن الحصول على السحب النقطية باستخدام أجهزة استشعار مختلفة:
- LIDAR (الكشف عن الضوء والمدى): يستخدم نبضات الليزر لقياس المسافات إلى الأجسام وإنشاء خرائط ثلاثية الأبعاد عالية الدقة.
- كاميرات العمق: التقاط معلومات العمق لكل بكسل، مما يسمح بإعادة بناء المشهد ثلاثي الأبعاد.
- كاميرات مجسمة: تستخدم كاميرتين أو أكثر للحصول على معلومات حول العمق من خلال التثليث.
- ماسحات الضوء المهيكلة: تقوم بإسقاط نمط معروف على سطح ما وقياس التشوه لحساب العمق.
استخدام YOLO مع السحب النقطية
لدمج YOLO مع sensor_msgs/PointCloud2
رسائل النوع، يمكننا استخدام طريقة مماثلة لتلك المستخدمة لخرائط العمق. من خلال الاستفادة من معلومات الألوان المضمنة في سحابة النقاط، يمكننا استخراج صورة ثنائية الأبعاد، وإجراء تجزئة على هذه الصورة باستخدام YOLO، ثم تطبيق القناع الناتج على النقاط ثلاثية الأبعاد لعزل الكائن ثلاثي الأبعاد محل الاهتمام.
للتعامل مع السحب النقطية، نوصي باستخدام Open3D (pip install open3d
)، وهي مكتبة Python سهلة الاستخدام. توفر Open3D أدوات قوية لإدارة هياكل بيانات السحابة النقطية وتصورها وتنفيذ العمليات المعقدة بسلاسة. يمكن لهذه المكتبة تبسيط العملية بشكل كبير وتعزيز قدرتنا على معالجة وتحليل السحب النقطية بالاقتران مع تجزئة YOLO.
الاستخدام التدريجي للسحب النقطية
استيراد المكتبات الضرورية وتهيئة نموذج YOLO للتجزئة.
import time
import rospy
from ultralytics import YOLO
rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolo11m-seg.pt")
إنشاء دالة pointcloud2_to_array
، والذي يحول sensor_msgs/PointCloud2
رسالة إلى مصفوفتي numpy. الـ sensor_msgs/PointCloud2
الرسائل تحتوي على n
نقاط تستند إلى width
و height
للصورة التي تم الحصول عليها. على سبيل المثال، 480 x 640
سيكون للصورة 307,200
نقاط. تتضمن كل نقطة ثلاثة إحداثيات مكانية (xyz
) واللون المقابل في RGB
التنسيق. يمكن اعتبارها قناتين منفصلتين للمعلومات.
ترجع الدالة xyz
الإحداثيات و RGB
القيم بتنسيق دقة الكاميرا الأصلية (width x height
). تحتوي معظم المستشعرات على مسافة قصوى، تُعرف بمسافة القطع، والتي تتجاوز القيم التي يتم تمثيلها على أنها مالانهاية (inf) (np.inf
). قبل المعالجة، من المهم تصفية هذه القيم الخالية وتعيين قيمة لها 0
.
import numpy as np
import ros_numpy
def pointcloud2_to_array(pointcloud2: PointCloud2) -> tuple:
"""
Convert a ROS PointCloud2 message to a numpy array.
Args:
pointcloud2 (PointCloud2): the PointCloud2 message
Returns:
(tuple): tuple containing (xyz, rgb)
"""
pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
nan_rows = np.isnan(xyz).all(axis=2)
xyz[nan_rows] = [0, 0, 0]
rgb[nan_rows] = [0, 0, 0]
return xyz, rgb
بعد ذلك، اشترك في /camera/depth/points
topic لاستقبال رسالة السحابة النقطية وتحويل sensor_msgs/PointCloud2
رسالة إلى مصفوفات numpy تحتوي على إحداثيات XYZ وقيم RGB (باستخدام pointcloud2_to_array
). قم بمعالجة صورة RGB باستخدام نموذج YOLO لاستخراج الكائنات المجزأة. لكل كائن تم اكتشافه، استخرج قناع التجزئة وقم بتطبيقه على كل من صورة RGB وإحداثيات XYZ لعزل الكائن في الفضاء ثلاثي الأبعاد.
تعتبر معالجة القناع واضحة ومباشرة لأنه يتكون من قيم ثنائية، مع 1
مما يشير إلى وجود الكائن و 0
يشير إلى الغياب. لتطبيق القناع، ما عليك سوى ضرب القنوات الأصلية في القناع. هذه العملية تعزل بشكل فعال الكائن محل الاهتمام داخل الصورة. أخيرًا، قم بإنشاء كائن سحابة نقطية Open3D وتصور الكائن المجزأ في الفضاء ثلاثي الأبعاد بالألوان المرتبطة.
import sys
import open3d as o3d
ros_cloud = rospy.wait_for_message("/camera/depth/points", PointCloud2)
xyz, rgb = pointcloud2_to_array(ros_cloud)
result = segmentation_model(rgb)
if not len(result[0].boxes.cls):
print("No objects detected")
sys.exit()
classes = result[0].boxes.cls.cpu().numpy().astype(int)
for index, class_id in enumerate(classes):
mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
mask_expanded = np.stack([mask, mask, mask], axis=2)
obj_rgb = rgb * mask_expanded
obj_xyz = xyz * mask_expanded
pcd = o3d.geometry.PointCloud()
pcd.points = o3d.utility.Vector3dVector(obj_xyz.reshape((ros_cloud.height * ros_cloud.width, 3)))
pcd.colors = o3d.utility.Vector3dVector(obj_rgb.reshape((ros_cloud.height * ros_cloud.width, 3)) / 255)
o3d.visualization.draw_geometries([pcd])
رمز كامل
import sys
import time
import numpy as np
import open3d as o3d
import ros_numpy
import rospy
from sensor_msgs.msg import PointCloud2
from ultralytics import YOLO
rospy.init_node("ultralytics")
time.sleep(1)
segmentation_model = YOLO("yolo11m-seg.pt")
def pointcloud2_to_array(pointcloud2: PointCloud2) -> tuple:
"""
Convert a ROS PointCloud2 message to a numpy array.
Args:
pointcloud2 (PointCloud2): the PointCloud2 message
Returns:
(tuple): tuple containing (xyz, rgb)
"""
pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
nan_rows = np.isnan(xyz).all(axis=2)
xyz[nan_rows] = [0, 0, 0]
rgb[nan_rows] = [0, 0, 0]
return xyz, rgb
ros_cloud = rospy.wait_for_message("/camera/depth/points", PointCloud2)
xyz, rgb = pointcloud2_to_array(ros_cloud)
result = segmentation_model(rgb)
if not len(result[0].boxes.cls):
print("No objects detected")
sys.exit()
classes = result[0].boxes.cls.cpu().numpy().astype(int)
for index, class_id in enumerate(classes):
mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
mask_expanded = np.stack([mask, mask, mask], axis=2)
obj_rgb = rgb * mask_expanded
obj_xyz = xyz * mask_expanded
pcd = o3d.geometry.PointCloud()
pcd.points = o3d.utility.Vector3dVector(obj_xyz.reshape((ros_cloud.height * ros_cloud.width, 3)))
pcd.colors = o3d.utility.Vector3dVector(obj_rgb.reshape((ros_cloud.height * ros_cloud.width, 3)) / 255)
o3d.visualization.draw_geometries([pcd])
الأسئلة الشائعة
ما هو نظام تشغيل الروبوت (ROS)؟
إن نظام تشغيل الروبوت (ROS) هو إطار عمل مفتوح المصدر يُستخدم بشكل شائع في مجال الروبوتات لمساعدة المطورين على إنشاء تطبيقات روبوت قوية. وهو يوفر مجموعة من المكتبات والأدوات لبناء الأنظمة الروبوتية والتفاعل معها، مما يتيح تطويرًا أسهل للتطبيقات المعقدة. يدعم نظام ROS التواصل بين العقد باستخدام الرسائل عبر المواضيع أو الخدمات.
كيف يمكنني دمج Ultralytics YOLO مع ROS للكشف عن الكائنات في الوقت الفعلي؟
يتضمن دمج Ultralytics YOLO مع نظام التشغيل ROS إعداد بيئة ROS واستخدام YOLO لمعالجة بيانات المستشعر. ابدأ بتثبيت التبعيات المطلوبة مثل ros_numpy
و Ultralytics YOLO:
pip install ros_numpy ultralytics
بعد ذلك، قم بإنشاء عقدة ROS واشترك في موضوع صورة لمعالجة البيانات الواردة. فيما يلي مثال بسيط:
import ros_numpy
import rospy
from sensor_msgs.msg import Image
from ultralytics import YOLO
detection_model = YOLO("yolo11m.pt")
rospy.init_node("ultralytics")
det_image_pub = rospy.Publisher("/ultralytics/detection/image", Image, queue_size=5)
def callback(data):
array = ros_numpy.numpify(data)
det_result = detection_model(array)
det_annotated = det_result[0].plot(show=False)
det_image_pub.publish(ros_numpy.msgify(Image, det_annotated, encoding="rgb8"))
rospy.Subscriber("/camera/color/image_raw", Image, callback)
rospy.spin()
ما هي مواضيع ROS وكيف يتم استخدامها في Ultralytics YOLO؟
تسهل مواضيع ROS الاتصال بين العقد في شبكة ROS باستخدام نموذج النشر والاشتراك. الموضوع هو قناة مسماة تستخدمها العقد لإرسال واستقبال الرسائل بشكل غير متزامن. في سياق Ultralytics YOLO، يمكنك جعل عقدة تشترك في موضوع صورة، ومعالجة الصور باستخدام YOLO لمهام مثل الاكتشاف أو التجزئة، ونشر النتائج في مواضيع جديدة.
على سبيل المثال، اشترك في موضوع الكاميرا وقم بمعالجة الصورة الواردة للكشف:
rospy.Subscriber("/camera/color/image_raw", Image, callback)
لماذا نستخدم صور العمق مع Ultralytics YOLO في ROS؟
صور العمق في ROS، ممثلة بـ sensor_msgs/Image
، توفر المسافة بين الكائنات والكاميرا، وهو أمر بالغ الأهمية لمهام مثل تجنب العوائق ورسم الخرائط ثلاثية الأبعاد وتحديد الموقع. من خلال. استخدام معلومات العمق بالإضافة إلى صور RGB، يمكن للروبوتات فهم بيئتها ثلاثية الأبعاد بشكل أفضل.
باستخدام YOLO، يمكنك استخراج أقنعة التجزئة من صور RGB وتطبيق هذه الأقنعة على صور العمق للحصول على معلومات دقيقة ثلاثية الأبعاد عن الكائنات، مما يحسن قدرة الروبوت على التنقل والتفاعل مع محيطه.
كيف يمكنني تصور سحب النقاط ثلاثية الأبعاد مع YOLO في ROS؟
لتصور سحب النقاط ثلاثية الأبعاد في ROS باستخدام YOLO:
- تحويل
sensor_msgs/PointCloud2
الرسائل إلى مصفوفات numpy. - استخدم YOLO لتقسيم صور RGB.
- قم بتطبيق قناع التجزئة على السحابة النقطية.
إليك مثال باستخدام Open3D للتصور:
import sys
import open3d as o3d
import ros_numpy
import rospy
from sensor_msgs.msg import PointCloud2
from ultralytics import YOLO
rospy.init_node("ultralytics")
segmentation_model = YOLO("yolo11m-seg.pt")
def pointcloud2_to_array(pointcloud2):
pc_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud2)
split = ros_numpy.point_cloud2.split_rgb_field(pc_array)
rgb = np.stack([split["b"], split["g"], split["r"]], axis=2)
xyz = ros_numpy.point_cloud2.get_xyz_points(pc_array, remove_nans=False)
xyz = np.array(xyz).reshape((pointcloud2.height, pointcloud2.width, 3))
return xyz, rgb
ros_cloud = rospy.wait_for_message("/camera/depth/points", PointCloud2)
xyz, rgb = pointcloud2_to_array(ros_cloud)
result = segmentation_model(rgb)
if not len(result[0].boxes.cls):
print("No objects detected")
sys.exit()
classes = result[0].boxes.cls.cpu().numpy().astype(int)
for index, class_id in enumerate(classes):
mask = result[0].masks.data.cpu().numpy()[index, :, :].astype(int)
mask_expanded = np.stack([mask, mask, mask], axis=2)
obj_rgb = rgb * mask_expanded
obj_xyz = xyz * mask_expanded
pcd = o3d.geometry.PointCloud()
pcd.points = o3d.utility.Vector3dVector(obj_xyz.reshape((-1, 3)))
pcd.colors = o3d.utility.Vector3dVector(obj_rgb.reshape((-1, 3)) / 255)
o3d.visualization.draw_geometries([pcd])
توفر هذه الطريقة تصورًا ثلاثي الأبعاد للكائنات المقسمة، وهو أمر مفيد لمهام مثل الملاحة والتلاعب في تطبيقات الروبوتات.