هذه هي المقالة الثانية لفريق setUP حول تجربتنا في إنشاء روبوتات مستقلة لمسابقات Eurobot Open واستخدام ROS لهذا الغرض.
المقالة الأولى عن الميكانيكا والهندسة العامة للروبوتات.تنتقل الروبوتات إلى أرض مستوية وتُعرف معظم العقبات مقدمًا ، ومع ذلك ، يمكن للمعارضين الخبيثين محاولة سرقة مواردنا (ونريد أحيانًا تناول بضع عشرات من النقاط الإضافية) ، بينما نريد القيادة إلى النقطة المطلوبة بأسرع ما يمكن وعدم لمس العقبات. من كاميرا خارجية في الميدان ، نحصل على بيانات حول موقع العدو ونعرف أين هو الآن. ومع ذلك ، لا يكفي معرفة موقفه - يجب أن تكون قادرًا على استخدام هذه المعلومات.
سنحاول اليوم القيادة من النقطة "أ" إلى النقطة "ب" دون السفر على ذيل قطة سقطت نائمة على الحقل. على وجه الخصوص ، سنشرح كيف نبني طريقًا ونتحكم في سرعة الروبوت ، فضلاً عن كيفية بدء تشغيل كل شيء على جهاز الكمبيوتر الخاص بنا.

محاولة الحصول على القليل من الدماء
عند حل هذه المشكلة ، يمكنك أن تأخذ مواد جاهزة مكتوبة بواسطة محترفين ، فلن يكون هناك عذاب ولا اختراع لـ "الدراجة" التالية. استخدمنا منصة متعددة الاستخدامات ، لذلك على الرغم من وجود محاولة لاستخدام جهاز إستواء محلي جاهز من شركة ROS ، لعدة أسباب وجدوا أن هذا الأمر غير واعد. يمكنك أدناه معرفة عدد الأشياء التي يحتاج إليها مصمم طائرة شراعية قياسية:
class TrajectoryPlanner{ friend class TrajectoryPlannerTest;
هذا مثال على تهيئة معلمات تنظيم السرعات والمسار ككل.معلمات مهمة لإجراء عملية حسابية كاملة:
- المعلمة world_model.
- معلمة خريطة التكلفة: رابط لخريطة تحتوي على عوائق ، بالإضافة إلى "امتدادها الظاهري" ، مع مراعاة التصادم المحتمل.
من مزايا المكدس القياسي ، يمكنك تسليط الضوء على توافر الوثائق والقدرة على العثور على المعلومات في المنتديات.
يمكنك قراءة المزيد على الموقع الرسمي مع الوثائقمن المهم أن نذكر أن حزم ROS كانت مكتوبة للمنصات ذات العجلتين ، وفي ظل Omni تم تحسينها من خلال زيادة زاوية الدوران المتاحة عند تحريك ما يصل إلى 360 درجة ، وهو بالتأكيد عكاز.
بعد تحليل المشروع ، أدركنا أنه سيكون هناك صعوبة في الدراسة والتكميل ، وكذلك هناك العديد من الرقائق الثقيلة التي لا نحتاج إليها. قد يبدو ذلك ، فليكن ، لكننا استخدمنا Odroid xu4 (المعالج الذي كان لا يزال على Samsung s5) ، وكانت نتائج الأداء محبطة ، ومساحة لشيء أكثر قوة (وتوت العليق 4 ومعالج jetson nano يدخنان بشكل جانبي بالمقارنة مع معه) لا. اضطررت إلى التخلي عن المكدس القياسي ومحاولة إنشاء مخطط عالمي ، مخطط محلي ومنظم مسار أنفسنا

مسوي عالمي ، مخطط محلي ، منظم مسار وجميع الكل
هناك حاجة إلى الطائرات الشراعية العالمية والمحلية للحصول على الاتجاهات إلى الوجهة. لماذا الانفصال ضروري؟ لماذا لا يمكنك فقط أخذ
A * وركوبها؟ كقاعدة عامة ، يمكن للمخطط الشامل ، عند إنشاء مسار ، استخدام الخريطة بأكملها في عمله ، لذلك يجب أن تكون الخوارزمية بأسرع ما يمكن ، حتى مع بعض التبسيط. لتخفيف هذه التبسيط ، يستخدمون أيضًا المخطط المحلي ، الذي يحاول ، بناءً على نتيجة المخطط العالمي (أو مجرد منطقة محدودة حول الروبوت) ، مراعاة جميع الفروق الدقيقة.
بعد أن أنشأنا المسار ، نعرف أين يجب أن يذهب الروبوت ، لكن كيف يمكن إخبارك بهذا؟ للقيام بذلك ، هناك منظم المسار. يقوم بحساب السرعة والسرعة التي يتحرك فيها الروبوت في الوقت الحالي حتى لا ينحرف عن المسار. من نواح كثيرة ، هذه الحزمة هي المسؤولة عن مدى سرعة وجميلة سوف يذهب الروبوت.
بالإضافة إلى هذه الكيانات الثلاثة ، هناك خادم خرائط - رابع ، يسمح لك بمعالجة حالة العالم بسهولة. إنه يحدد كيفية وصفنا للخريطة ، وما هي الإمكانيات المتوفرة لدينا عند العمل مع الخريطة ، ومن نواح كثيرة ، تحديد سرعة الطائرات الشراعية.
قبل المتابعة مع وصف مكدس التنقل ، سيكون من الجيد تحديد أسباب اختيار cost_map كخادم خرائط. بشكل عام ، جربنا خيارات مختلفة لمعالج الخرائط:
Occupancy_grid و
Grid_map و
Cost_map ، لكننا
استقرنا على الأخير.
الأسباب:
- تتفاعل بشكل مريح مع الخريطة.
- هناك العديد من التكرارات التي نحتاجها في أشكال مختلفة (دائرية ، خطية ، مستطيلة ، إلخ).
- يمكنك تخزين طبقات خريطة متعددة بمعلمات مختلفة.
- إدارة ذاكرة جيدة.
- والأهم من ذلك ، السرعة. تعمل خريطة الشبكة بنوع مزدوج وبسبب هذا ، فإنها أبطأ عدة مرات من خوادم الخرائط التي تستخدم int8 للعمل.
على الرغم من حقيقة أن شبكة الإشغال تعمل أيضًا مع int8 ، إلا أنها لا يمكن أن تفتخر بنفس قابلية الاستخدام ، لذلك اضطررت إلى التخلي عنها.
من الخريطة ، نحتاج إلى معرفة أين توجد المناطق الحرة والخطيرة التي لا تقاوم. لكل كائن موجود في الحقل ، يمكننا ضبط حقل التضخم - وهي القيمة التي تحدد ، حسب المسافة إلى الكائن ، نفاذية الخلية. التضخم هو ذيل القط ، من السهل عدم ملاحظته ، ولكن بعد ذلك ستندم عليه لفترة طويلة جدًا. نقوم بتخطيط روبوتات العدو ونضيف منطقة خطر لا يأخذها سوى المخطط المحلي في الاعتبار. مخطط عالمي يتجاهل جميع النقاط ، إذا لم تكن عقبة.
مخطط عالمي
أول ما كتبوه في الملاحة هو المخطط العالمي. يعتمد على خوارزمية theta *. باختصار ، هذا هو
A * المعدلة ، حيث يتم التركيز على العثور على العقدة الأصل ، والتي يمكن الوصول إليها مباشرة ، أي لا توجد عقبات أمامها. هذا يسمح لنا ببناء مسارات مريحة وسلسة تستخدم في المخطط المحلي.
مقارنة بين A * و theta *بالنسبة للمخطط العام ، لدينا ملف به معلمات (params / path_planner.yaml) يصف موضوعات الخريطة ومواضيعها مع موقع جميع الروبوتات (لجميع الروبوتات الأربعة في الحقل ، حيث "null" هو الموضوع الذي يحتوي على بيانات حول الروبوت الحالي).
# small robot debug param list robot_id: "small" ########################### # cost_map_server params ## ########################### cost_map_server/big_robot_size: 0.45 cost_map_server/little_robot_size: 0.45 cost_map_server/cube_size: 0.11 cost_map_server/inscribed_radius: 0.3 cost_map_server/inflation_radius: 0.3 cost_map_server/inflation_exponential_rate: 0.6 cost_map_server/big_robot1: "/aruco/big_robot" cost_map_server/big_robot2: "/aruco/enemy_robot1" cost_map_server/small_robot1: "null" cost_map_server/small_robot2: "/aruco/enemy_robot2" cost_map_server/collision: "collision" cost_map_server/image_resource_name: "$(find cost_map_server)/param/image_resource.yaml" cost_map_server/min_diff_points: 0.01 ########################### ### path_planner params ### ########################### global_planner/path_layer: "inflation_layer" global_planner/path_force_layer: "obstacle_inflation_layer" global_planner/frame_id: "map" global_planner/current_position: "real_corr" global_planner/path_filter_epsilon: 0
كما يشير إلى:
- واحدة من الخوارزميات التي يمكنك اختيار بناء مسار ،
- أسماء الطبقات التي سنبني عليها الطريق نفسه ،
- موضوع حول موقفنا ، حيث يتم إصدار البيانات التي تمت تصفيتها (في حالتنا ، هو مزيج من بيانات الموقع من الكاميرا وقياس المسافات).
يتم تمييز خوارزمية البحث عن المسار نفسها - Theta Star - في ملف منفصل (src / global_planner.cpp) لتوفير الراحة لإضافة خوارزميات جديدة:
float cost_so_far[300][200]; PriorityPoint neighbors[8]; PriorityPoint current; int come_from[300][200][2]; double makePath_ThetaStar(std::vector<cost_map::Index> &path, PriorityPoint start, PriorityPoint goal, std::string layer, cost_map::CostMap &cost_map, double grid_cost, bool only_cost) { std::priority_queue<PriorityPoint, std::vector<PriorityPoint>, myCompare> openSet; size_t max_x = cost_map.getSize()[0]; size_t max_y = cost_map.getSize()[1]; std::fill_n(*cost_so_far, max_x * max_y, std::numeric_limits<float>::max()); cost_so_far[start.x][start.y] = 0; come_from[start.x][start.y][0] = start.x; come_from[start.x][start.y][1] = start.y; openSet.push(start); grid_cost=5; while (!openSet.empty()) { current = openSet.top(); openSet.pop(); if (current == goal) { break; } current.GetNeighbors(neighbors); float current_cost = cost_so_far[current.x][current.y]; int parent_carent[2] ={come_from[current.x][current.y][0], come_from[current.x][current.y][1]}; for (int i = 0; i < 8; i++) { if (!neighbors[i].OnMap(max_x, max_y)) { continue; } bool onLine = lineOfSight(parent_carent[0], parent_carent[1], neighbors[i].x, neighbors[i].y, cost_map, layer, grid_cost + 1); if (onLine) { float new_cost = cost_so_far[parent_carent[0]][parent_carent[1]] + HeuristicEvclid(parent_carent, neighbors[i], grid_cost*10); if (new_cost < cost_so_far[neighbors[i].x][neighbors[i].y]) { cost_so_far[neighbors[i].x][neighbors[i].y] = new_cost; neighbors[i].priority = HeuristicEvclid(neighbors[i], goal, grid_cost*10) + new_cost; openSet.push(neighbors[i]); come_from[neighbors[i].x][neighbors[i].y][0] = parent_carent[0]; come_from[neighbors[i].x][neighbors[i].y][1] = parent_carent[1]; } } else { float neighbor_price = cost_map.at(layer, cost_map::Index({neighbors[i].x, neighbors[i].y})) + neighbors[i].priority; float new_cost = current_cost + neighbor_price; if (new_cost < cost_so_far[neighbors[i].x][neighbors[i].y]) { cost_so_far[neighbors[i].x][neighbors[i].y] = new_cost; neighbors[i].priority =HeuristicEvclid(neighbors[i], goal, grid_cost*10) + new_cost; openSet.push(neighbors[i]); come_from[neighbors[i].x][neighbors[i].y][0] = current.x; come_from[neighbors[i].x][neighbors[i].y][1] = current.y; } } } } if (only_cost) { return cost_so_far[current.x][current.y]; } path.clear(); PriorityPoint temp_point; while (current != start) { path.push_back({current.x, current.y}); temp_point.x = come_from[current.x][current.y][0]; temp_point.y = come_from[current.x][current.y][1]; current = temp_point; } path.push_back({current.x, current.y}); return 0; }
يتم أيضًا تخصيص خوارزمية لإزالة النقاط الإضافية على مسار RamerDouglasPeucker لملف منفصل.
يزيل النقاط من المسار إذا كان خارج مسافة معينة من الخط الذي يصل بين نقطتين متجاورتين.

مخطط محلي
انه يعمل بالنسبة لنا على أساس النسب التدرج في مجال محتمل. كمدخلات ، المسار من المخطط العالمي. ومع ذلك ، هذا ليس كل ما هو قادر. في local_planner ، هناك خدمات داخلية لاختيار وضع بناء المسار. هناك إجمالي وضعين للتشغيل: وضع نقاط التحول على طول التدرج اللوني ، باستخدام تمريرات متعددة على الخريطة ، بالإضافة إلى وضع التحول ، حيث نحسب الزيادة على الفور في إحداثيتين وننقل النقطة إلى حافة المنطقة الآمنة. إذا سقطت النقطة في عدة مناطق من هذا القبيل ، فإننا ننتقل إلى أماكن تقاطعها ، لأنه هناك الأكثر أمانًا.
يكون وضع التشغيل كما يلي: إذا لم تكن هناك عقبة في المسار من التكرار السابق ، فسنقطع المسار كل 2 سم ، ثم نغيره على طول التدرج اللوني ، وإلا فإننا نستخدم وضع المخطط المحلي الثاني للعملية.
الخيار الثاني خفيف الوزن تمامًا ، مثل المخطط العام ، لا يقوم بتحميل المعالج كثيرًا. استخدمنا العديد من إصدارات هذه الخوارزمية ومعالجات مختلفة مع الخريطة. على سبيل المثال ، حاولنا كتابة رسم بياني توجد فيه القمم كل 10 سم ويتم إزاحتها بحد أقصى 4 سم ، وبعد ذلك تم استخدام خوارزمية ديكسترا على الرسم البياني الذي تم الحصول عليه للعثور على أصغر مسافة. تستخدم نقطة النهاية في هذه الحالة أقرب نقطة إزاحة. لكن مثل هذه الخوارزمية كانت أكثر ملاءمة للمخطط العالمي وقررنا التخلي عن هذا التنفيذ.
لقد حاولنا أيضًا استخدام بناء المسار من نقطة الصفر باستخدام طريقة النسب التدرج. كانت هذه الطريقة الأولى التي قررنا الكتابة. اتضح أن هذا الجهاز غير فعال في الذاكرة (فقد احتل أكثر من 400 ميغابايت من ذاكرة الوصول العشوائي الخالصة ، لأنه استخدم خريطة تكلفة مع كل تمريرة) وبطيئة. تم إيقاف التحكم في التردد بسبب ضعف التحسين وكانت السرعة أقل من 30 مرة في الثانية ، وهو ما لم يناسبنا.
نتيجة لذلك ، قررنا استخدام النسب التدرج في حقل محتمل استنادًا إلى مسار المخطط العالمي. لقد اتضح أنه خوارزمية خفيفة الوزن وبسيطة نسبيًا ، والتي تناسبنا تمامًا من حيث جودة المسار ووقت العمل وكمية ذاكرة الوصول العشوائي المستخدمة في منطقة 100-150 ميغابايت ، وهي أقل بعدة مرات مما كانت عليه في التكرارات الأولى من التطوير.
مثال على مسار يقابله المسوي المحليعلى عكس global_planner ، فإن المعلمات في local_planner صغيرة للغاية ، ويرجع ذلك إلى بساطتها ، لأن جميع المهام الأكثر أهمية تكمن في global_planner:
grid_map_server/big_robot1 : 0.4 grid_map_server/big_robot2 : 0.4 grid_map_server/small_robot1 : 0.4 grid_map_server/small_robot2 : 0.4 local_planner/radius : 0.15 global_planner/frame_id : "map"
في هذه الحالة ، نقوم بتكوين:
- نصف قطر المناطق الآمنة لكل من الروبوتات.
- إزاحة المسار الأقصى بواسطة المسوي المحلي.
- اسم طبقة الخريطة التي نعمل معها.
في فصل منفصل تم تخصيص جميع الوظائف الأكثر أهمية. في هذه الحالة ، إنه انهيار متكرر للمسار ، وإنشاء طائرة شراعية وبناة افتراضية ومدمرات.
class Planner { public: Planner(double inflation_radius_, std::string frame_id_) { inflation_radius = inflation_radius_; for (int i = 0; i < 300; i++) { for(int j = 0; j < 200; j++) our_map[i][j] = 3000.0; } OurPath->poses.resize(50); geometry_msgs::Pose pose; pose.position.x = 0.0; pose.position.y = 0.0; for( int i = 0; i < 50; i++) { OurPath->poses[i].pose = pose; } frame_id = frame_id_; } virtual ~Planner() { } virtual void UpdatePath() = 0; ros::Publisher move_pub; ros::Publisher BigEnemyPub; ros::Publisher LittleEnemyPub; ros::Publisher local_path_publisher; protected:
تمت توارث فئة LocalPlanning منه ، حيث يوجد قلب الطائرة الشراعية بالكامل ، أي تحويل النقاط إلى حافة المنطقة الآمنة وتحديد ما يجب فعله بالمسار على وجه التحديد.
يتم تمييز كل الوظائف الأخرى في ملف منفصل fichi.hpp ، ونسب متدرج في potential_field.hpp. يوجد أدناه لقطة من هذا الملف ، والتي تُظهر وظائف إنشاء حقل محتمل على خريطة cost_map:
double CalcAttractivePotential(grid_map::Index index, double goalx, double goaly) { return sqrt(pow(index[0] - goalx, 2) + pow(index[1] - goaly, 2)); } void CalcPotential(double startx, double starty, double goalx, double goaly, cost_map::CostMap &cost_map, double (&our_map)[300][200]) {
منظم المسار
أخيرًا وليس آخرًا ، منظم المسار. وهو مسؤول عن تحويل مسار المخطط المحلي إلى مسار ويعطي السرعة للخطوة الحالية.
الإصدار الأول ، الذي استخدمناه في نهائي Eurobot 2018 ، عبارة عن مزيج من وحدة التحكم في التسارع ومكابح الفرامل ، حيث يتم ضبط ناقل الحركة إلى النقطة التالية على الطريق ، بالنسبة إلى المسافة إلى نقطة النهاية.
وحدة التحكم PID ، باختصار ، هي مجموع الحالات الثلاث للنظام التي تساعد في إصلاح الأخطاء والأخطاء التي تحدث في بعض الأحيان.
تم تحديد هذه الوظائف بشكل تجريبي وتعتمد على المسافة إلى نقطة النهاية في المسار (يمكن أن تكون من الدرجة الثانية أو المكعبة أو العكسية ، ولكن بعد ذلك استقرنا على الدرجة الثانية). لقد نجح ذلك ، ولكن الشيء الوحيد الذي لم يناسبنا هو أن الروبوت لم يتمكن من الفرامل في الوقت المناسب بسرعة تفوق 0.7 متر في الثانية. لذلك ، عندما حان الوقت ، قررنا إعادة بناء الخوارزمية بأكملها.
التكرار الأول في الطريق إلى المسار الجديد كان استبدال المتجه الذي كنا بصدده. الآن كان مجموع ناقلات الثلاثة التالية مع معاملات مختلفة. التكرار الثاني كان يكتب الحد الأدنى من الهزة. باختصار ، هذا بناء متعدد الحدود من الدرجة الخامسة ، حيث تعتمد إحداثيات x و y على وقت الوصول إلى كل نقطة.
يوضح الشكل رسم بياني لأحد الإحداثيات مقابل الوقت ، وكذلك السرعة على طول هذا الإحداثيهذا النوع من منظم المسار يناسبنا أكثر ، لأنه يتطلب معالجة أقل مع اختيار معاملات مختلفة ، لأن جميع المعاملات هي القيم في كثير الحدود ، والتي تم حسابها على أساس وقت الوصول والسرعة الحالية والتسارع وسرعة الإخراج والتسارع.
كانت نتيجة إعادة كتابة المسار أننا تمكنا من مضاعفة متوسط سرعة الروبوت.
كما في الحالتين السابقتين ، يتم تسليط الضوء على جميع الوظائف الرئيسية في ملف منفصل لسهولة التفاعل. هذه المرة ، تكون فئة PlannerTrajectory مسؤولة عن إنشاء مسار يعتمد على MinimumJerk
typedef struct State { double velocity; double acceleration; State(double v_, double a_) : velocity(v_), acceleration(a_) {} State() { velocity = 0; acceleration = 0; } }; class PlannerTrajectory { private: nav_msgs::Path global_path; cost_map::CostMap *costmap_ptr; geometry_msgs::PoseStamped Goal_pred; std::vector<double> trajectory_x; std::vector<double> trajectory_y; double average_velocity = 80;
تظهر الصورة جميع المتغيرات المعلنة التي نستخدمها.يتم تمييز كل شيء آخر في ملف آخر (include / trajectory_regulator.h): تلقي نقاط من الموضوعات ، وتحديد ما إذا كنت تريد الانتقال إلى النقطة التالية (إذا كانت في عقبة ، فلن نذهب) والمزيد.
يهاجر إلى ROS ميلوديك
حتى العام الماضي ، استخدمنا الإصدار lte من ROS - ROS الحركية. لقد كان مناسبًا لنا عمومًا ، لكن دعمه وصل إلى نهايته في العام المقبل ، والعديد من الحزم التي نحتاجها بدأت في الخروج حصريًا لـ ROS Melodic. ثم اتضح أن costmap_server استخدمناها ليست تحت Melodic.
حدثت مشكلة أثناء معالجة البيانات من البطاقات.
لقد اخترنا خريطة الشبكة ، نظرًا لأن المكدس متشابه ، ولكن بداية الخريطة في مكان مختلف ، وقيم الخريطة نفسها تختلف من 0 إلى 1. لقد أصبحت هذه مشكلة كبيرة في مكدس التنقل بأكمله. إذا تم في وقت سابق تشغيل المخطط العالمي 50 مرة في الثانية (كانت هناك قيود على التردد ، وبالتالي لم يتم استخدام المعالج أكثر من اللازم ، حتى في نصف مؤشر ترابط واحد) ، فقد مهد الآن الطريق كل ثانيتين واعتبره سيئًا: لقد تم تحميل نواة واحدة تمامًا. في غضون ثانيتين ، كان بإمكان الروبوت عبور الخريطة بالكامل. هذا لم يناسبنا ، ومحاولات موازاة هذه العملية انتهت بالفشل ، لأنه لم يعد هناك أداء لمشاريع أخرى (مع مراعاة تكاليف الموازاة).
قررنا تغيير المكدس مرة أخرى ، والتخلي عن خريطة الشبكة لصالح شبكة الإشغال. ظهرت مشكلة جديدة - عدم القدرة على تخزين عدة إصدارات من الخرائط في نفس الوقت (على سبيل المثال ، كاملة ، مع كل العقبات ، وخريطة ثابتة ، مع عقبات ديناميكية فقط). أود أن أقوم بتغيير نصف الكود الذي لم يكن موثوقًا به بشكل خاص. لذلك ، قررنا البحث عن حلول بديلة لهذه المشكلة.
خادم خريطة التكلفة
بعد بحث طويل ، وجدنا خرائط شوكة costmap_serverr:
https://github.com/lelongg/cost_map.git - مفيدة للغاية لنظام الشوكة لدينا.

والآن ، بدلاً من خدمة خريطة الشبكة فقط ، للتسليم ، نجحنا في حساب الموقع المحتمل للعدو بناءً على التنبؤ بفلتر Kalman.

أحد أهم الأشياء لخادم الخرائط هو ملف الخريطة ، والذي يُستخدم لإنشاء أولي لجميع الطبقات ، والتي يتم تحديثها لاحقًا فقط. إنها صورة ثنائية بابوا نيو غينيا ، حيث يكون الأسود عقبة والأبيض منطقة حرة.

يوجد أيضًا ملف إعدادات لتكوين cost_map_server. أنه يحتوي على مواضيع مع نقاط العدو ، ومنطقة التضخم وحجم المربع ، والتي يمكن أن تستخدم أيضا لوضع منطقة العدو الخطرة على الخريطة.
########################### # cost_map_server params ## ########################### cost_map_server/big_robot_size: 0.4 cost_map_server/little_robot_size: 0.4 cost_map_server/cube_size: 0.11 cost_map_server/inscribed_radius: 0.25 cost_map_server/inflation_radius: 0.25 cost_map_server/inflation_exponential_rate: 0.6 cost_map_server/big_robot1: "/aruco/robot1" cost_map_server/big_robot2: "/aruco/robot2" cost_map_server/small_robot1: "/aruco/robot3" cost_map_server/small_robot2: "/aruco/robot4" cost_map_server/collision: "collision" cost_map_server/image_resource_name: "$(find cost_map_server)/param/image_resource.yaml" cost_map_server/min_diff_points: 0.01
يتم نشر جميع الطبقات فقط إذا اشترك شخص ما فيها:
void PublishChanges() { nav_msgs::OccupancyGrid msg; cost_map_msgs::CostMap cost_map_msg; if (obstacle_inflation_publisher.getNumSubscribers() > 0) { cost_map::toOccupancyGrid(costmap, "obstacle_layer", msg); obstacle_inflation_publisher.publish(msg); } if (inflation_publisher.getNumSubscribers() > 0) { cost_map::toOccupancyGrid(costmap, "inflation_layer", msg); inflation_publisher.publish(msg); } if (cost_map_publisher.getNumSubscribers() > 0) { cost_map::toMessage(costmap, cost_map_msg); cost_map_publisher.publish(cost_map_msg); } }
تشغيل على جهاز الكمبيوتر الخاص بك
لبدء المكدس بالكامل ، يجب عليك:
- ضع روس
- cost_map_server cost_map_server_alone.launch - لبدء الخريطة
- roslaunch global_planner global_planner.launch - إطلاق المسوي العالمي مع المعلمات
- rosparam load $ (find local_planner) /param/param.yaml
- rosrun local_planner local_planning
- rosrun trajectory_regulator
- rosrun global_planner المحرك
- rosrun rviz
- إضافة تضخم
- الآن أرسل رسالة إلى الموضوع / gp / الهدف ، نرسل الروبوت إلى النقطة المطلوبة
نتيجة لإطلاق جميع العناصر ، سيكون لديك محاكاة جاهزة لإطلاق مجموعتنا على جهاز الكمبيوتر الخاص بك. شوكة اللازمةفي البداية ، احتجنا إلى نظام الملاحة الذي سيساعدنا على قيادة الروبوت بشكل جميل وسريع وبدقة على عجلات متعددة الاستخدامات. أثناء الاستعداد للمسابقة ، لم تُجرح قطة واحدة ، والروبوت وسيم. نتيجة لذلك ، لدينا مجموعة تنقل خفيفة الوزن للمسابقات المماثلة لـ eurobot ، والتي نحن راضون تمامًا عنها.بالنسبة لنا ، هذه المكدس أفضل من المعيار ، لكن ...Telegram: t.me/SetUpSber مستودع كل إبداعاتنا