Dies ist der zweite Artikel des setUP-Teams über unsere Erfahrungen bei der Erstellung autonomer Roboter für Eurobot Open-Wettbewerbe und deren Verwendung von ROS.
Der erste Artikel befasst sich mit der Mechanik und der allgemeinen Architektur von Robotern.Roboter bewegen sich auf einem flachen Feld und die meisten Hindernisse sind im Voraus bekannt. Schleichende Gegner können jedoch versuchen, unsere Ressourcen zu stehlen (und wir möchten manchmal ein paar Dutzend zusätzliche Punkte essen), während wir so schnell wie möglich zum gewünschten Punkt fahren und die Hindernisse nicht berühren möchten. Von einer externen Kamera auf dem Feld erhalten wir Daten über die Position des Feindes und wissen, wo er sich jetzt befindet. Es reicht jedoch nicht aus, seine Position zu kennen - Sie müssen in der Lage sein, diese Informationen zu verwenden.
Heute werden wir versuchen, von Punkt A nach Punkt B zu fahren, ohne den Schwanz einer Katze entlanggefahren zu sein, die auf dem Feld eingeschlafen ist. Insbesondere werden wir erklären, wie wir eine Route erstellen, die Geschwindigkeit des Roboters steuern und wie alles auf unserem Computer gestartet wird.

Ich versuche mit ein bisschen Blut auszukommen
Wenn Sie dieses Problem lösen, können Sie vorgefertigtes Material verwenden, das von Fachleuten geschrieben wurde. Dann wird das nächste „Fahrrad“ nicht mehr erfunden. Wir verwendeten eine Allradplattform, und obwohl versucht wurde, einen vorgefertigten lokalen Hobel von ROS zu verwenden, war dies aus mehreren Gründen nicht vielversprechend. Unten sehen Sie, wie viel Material der Designer eines Standard-Segelflugzeugs benötigt:
class TrajectoryPlanner{ friend class TrajectoryPlannerTest;
Dies ist ein Beispiel für die Initialisierung von Parametern zur Regelung der Geschwindigkeit und der gesamten Flugbahn.Wichtige Parameter für eine vollständige Berechnung:
- Parameter world_model.
- Kostenkartenparameter: Ein Link zu einer Karte, die Hindernisse enthält, sowie deren "virtuelle Erweiterung" unter Berücksichtigung der möglichen Kollision.
Von den Vorteilen des Standardstacks können Sie die Verfügbarkeit der Dokumentation und die Fähigkeit hervorheben, Informationen in den Foren zu finden.
Sie können mehr auf der offiziellen Website mit Dokumentation lesenEs ist wichtig zu erwähnen, dass ROS-Pakete für zweirädrige Plattformen geschrieben wurden und unter Omni optimiert wurden, indem der verfügbare Drehwinkel beim Bewegen auf 360 Grad erhöht wurde, was sicherlich eine Krücke ist.
Nach der Analyse des Projekts stellten wir fest, dass das Lernen und Ergänzen schwierig sein würde und dass es viele schwere Chips gibt, die wir nicht benötigen. Es scheint, lassen Sie sie sein, aber wir verwendeten Odroid xu4 (der Prozessor, von dem noch auf Samsung s5 war), und die Leistungsergebnisse waren deprimierend, und der Raum für etwas leistungsfähigeres (und die Himbeere 4 und der Jetson Nano-Prozessor rauchen nervös beiseite im Vergleich zu mit ihm) nein. Ich musste den Standardstapel aufgeben und versuchen, den globalen Planer, den lokalen Planer und den Flugbahnregler selbst zu erstellen

Globaler Planer, lokaler Planer, Flugbahnregler und alles in allem
Globale und lokale Segelflugzeuge werden benötigt, um eine Wegbeschreibung zum Ziel zu erhalten. Warum ist eine Trennung notwendig? Warum kannst du nicht einfach
A * nehmen und damit fahren? In der Regel kann der globale Planer beim Erstellen einer Route die gesamte Karte in seiner Arbeit verwenden, sodass der Algorithmus so schnell wie möglich sein sollte, möglicherweise sogar mit einigen Vereinfachungen. Um diese Vereinfachungen auszugleichen, verwenden sie auch den lokalen Planer, der auf der Grundlage des Ergebnisses des globalen Planers (oder nur eines begrenzten Bereichs um den Roboter) versucht, alle Nuancen zu berücksichtigen.
Nachdem wir die Route erstellt haben, wissen wir, wohin der Roboter gehen soll, aber wie kann er darüber informiert werden? Dazu gibt es einen Flugbahnregler. Er berechnet, mit welcher Geschwindigkeit und in welche Richtung sich der Roboter gerade bewegen soll, um nicht von der Flugbahn abzuweichen. In vielerlei Hinsicht ist dieses Paket dafür verantwortlich, wie schnell und schön der Roboter fährt.
Neben diesen drei Entitäten gibt es einen vierten - einen Kartenserver, mit dem Sie den Zustand der Welt bequem verarbeiten können. Es legt fest, wie wir die Karte beschreiben, welche Möglichkeiten wir beim Arbeiten mit der Karte haben und in vielerlei Hinsicht die Geschwindigkeit der Segelflugzeuge bestimmen.
Bevor Sie mit der Beschreibung des Navigationsstapels fortfahren, sollten Sie die Gründe erläutern, warum cost_map als Kartenserver ausgewählt wurde. Im Allgemeinen haben wir verschiedene Optionen für den Map-Handler
ausprobiert :
Occupancy_grid ,
Grid_map ,
Cost_map .
Gründe:
- Bequem mit der Karte interagieren.
- Es gibt verschiedene Iteratoren, die wir in verschiedenen Formen benötigen (kreisförmig, linear, rechteckig usw.).
- Sie können mehrere Kartenebenen mit unterschiedlichen Parametern speichern.
- Gutes Speichermanagement.
- Und vor allem Geschwindigkeit. Grid Map funktioniert mit doppeltem Typ und ist daher um ein Vielfaches langsamer als die Kartenserver, die int8 für die Arbeit verwenden.
Trotz der Tatsache, dass das Belegungsraster auch mit int8 funktioniert, kann es sich nicht der gleichen Benutzerfreundlichkeit rühmen, so dass ich es aufgeben musste.
Aus der Karte müssen wir wissen, wo sich die freien, gefährlichen und unwiderstehlichen Zonen befinden. Für jedes Objekt, das sich auf dem Feld befindet, können wir das Aufblasfeld anpassen - ein Wert, der abhängig vom Abstand zum Objekt die Durchlässigkeit der Zelle kennzeichnet. Inflation ist der Schwanz der Katze, man merkt es leicht nicht, aber dann werden Sie es sehr lange bereuen. Wir kartieren feindliche Roboter und fügen eine Gefahrenzone hinzu, die nur der lokale Planer berücksichtigt. Der globale Planer ignoriert alle Punkte, wenn sie kein Hindernis sind.
Globaler Planer
Das erste, was sie in der Navigation geschrieben haben, ist der globale Planer. Es basiert auf dem Theta * -Algorithmus. Kurz gesagt, dies ist ein modifiziertes
A * , bei dem der Schwerpunkt auf dem Finden des Elternknotens liegt, der direkt erreicht werden kann, d.h. Es gibt keine Hindernisse für sie. Auf diese Weise können wir bequeme und glatte Pfade erstellen, die im lokalen Planer verwendet werden.
Vergleich von A * und Theta *Für den globalen Planer haben wir eine Datei mit Parametern (params / path_planner.yaml), die Kartenthemen und Themen mit dem Standort aller Roboter beschreibt (für alle vier Roboter auf dem Feld, wobei "null" das Thema mit Daten zum aktuellen Roboter ist).
# 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
Es zeigt auch an:
- einen der Algorithmen, die Sie wählen können, um eine Route zu erstellen,
- Namen von Layern, auf denen wir die Route selbst bauen werden,
- Ein Thema über unsere Position, an der gefilterte Daten ausgegeben werden (in unserem Fall ist es eine Kombination aus Positionsdaten von der Kamera und der Kilometerzähler).
Der Pfadsuchalgorithmus selbst - Theta Star - ist in einer separaten Datei (src / global_planner.cpp) hervorgehoben, damit Sie bequem neue Algorithmen hinzufügen können:
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; }
Ein Algorithmus zum Entfernen zusätzlicher Punkte im RamerDouglasPeucker-Pfad ist ebenfalls einer separaten Datei zugeordnet.
Punkte werden vom Pfad entfernt, wenn der Abstand zu der Linie, die zwei benachbarte Punkte verbindet, nicht mehr gegeben ist.

Lokaler Planer
Er arbeitet für uns auf der Basis von Gefälle in einem potenziellen Feld. Als Eingabe der Pfad aus dem globalen Planer. Dies ist jedoch nicht alles, wozu er in der Lage ist. In local_planner gibt es interne Services zur Auswahl des Pfadkonstruktionsmodus. Insgesamt gibt es zwei Betriebsmodi: den Modus zum Verschieben von Punkten entlang des Verlaufs mithilfe mehrerer Kartenpassagen sowie den Modus zum Verschieben, bei dem das Inkrement sofort in zwei Koordinaten berechnet und der Punkt an den Rand der sicheren Zone verschoben wird. Wenn der Punkt in mehrere solcher Zonen fällt, verschieben wir uns zu den Stellen, an denen er sich kreuzt, weil er dort am sichersten ist.
Die Funktionsweise ist wie folgt: Wenn der Pfad der vorherigen Iteration kein Hindernis enthält, brechen wir den Pfad alle 2 cm und verschieben ihn dann entlang des Gefälles. Andernfalls verwenden wir die zweite lokale Planungsbetriebsart.
Die zweite Option ist recht leicht und belastet den Prozessor wie der globale Planer nicht sehr. Wir haben verschiedene Versionen dieses Algorithmus und verschiedene Manipulationen mit der Karte verwendet. Wir haben zum Beispiel versucht, ein Diagramm zu schreiben, in dem die Eckpunkte alle 10 cm gefunden und um maximal 4 cm verschoben werden. Anschließend wurde der Dijkstra-Algorithmus für das erhaltene Diagramm verwendet, um den kleinsten Abstand zu ermitteln. Der Endpunkt verwendet in diesem Fall den nächstgelegenen Versatzpunkt. Ein solcher Algorithmus war jedoch besser für globale Planer geeignet, und wir entschieden uns, diese Implementierung aufzugeben.
Wir haben auch versucht, die Pfadbildung von Grund auf mit der Gradientenabstiegsmethode durchzuführen. Diese Methode war die erste, für die wir uns entschieden haben zu schreiben. Es stellte sich heraus, dass es nicht speichereffizient (es belegte mehr als 400 MB reinen RAM, da es bei jedem Durchlauf eine Kostenkarte verwendete) und langsam war. Die Frequenzregelung wurde aufgrund einer schlechten Optimierung deaktiviert und die Geschwindigkeit betrug weniger als 30 Mal pro Sekunde, was uns nicht zusagte.
Aus diesem Grund haben wir uns entschlossen, den Gradientenabstieg in einem potenziellen Feld zu verwenden, das auf dem Pfad des globalen Planers basiert. Es stellte sich heraus, dass es sich um einen leichten und relativ einfachen Algorithmus handelt, der hinsichtlich Pfadqualität, Arbeitszeit und RAM-Verbrauch in der Größenordnung von 100-150 MB vollkommen zu uns passt. Dies ist ein Vielfaches weniger als in den ersten Entwicklungsiterationen.
Ein Beispiel für einen durch einen lokalen Planer versetzten PfadIm Gegensatz zu global_planner sind die Parameter in local_planner extrem klein, was auf die Einfachheit zurückzuführen ist, da alle wichtigen Aufgaben bei global_planner liegen:
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"
In diesem Fall konfigurieren wir:
- Radien der Sicherheitszonen für jeden Roboter.
- Maximaler Pfadversatz durch lokalen Planer.
- Der Name der Kartenebene, mit der wir arbeiten.
In einer eigenen Klasse wurden alle wichtigen Funktionen vergeben. In diesem Fall handelt es sich um eine rekursive Aufteilung des Pfades, die Erstellung eines Segelflugzeugs sowie virtueller Konstruktoren und Destruktoren.
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:
Die LocalPlanning-Klasse wurde von ihr geerbt, in der sich der gesamte Kern des Segelflugzeugs befindet, dh Punkte an den Rand der sicheren Zone verschoben werden und entschieden wird, was mit dem Pfad speziell zu tun ist.
Alle anderen Funktionen werden in einer separaten Datei fichi.hpp hervorgehoben und der Gradientenabstieg in potential_field.hpp. Unten finden Sie eine Momentaufnahme aus dieser Datei, in der die Funktionen zum Erstellen eines potenziellen Felds auf der cost_map-Karte aufgeführt sind:
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]) {
Flugbahnregler
Last but not least ist der Flugbahnregler. Er ist dafür verantwortlich, den lokalen Planerpfad in einen Pfad umzuwandeln und gibt die Geschwindigkeit für den aktuellen Schritt an.
Die erste Version, die wir beim Eurobot-Finale 2018 verwendet haben, ist eine Mischung aus Beschleunigungs- und Brems-PID-Regler, bei der der Vektor relativ zum Abstand zum Endpunkt auf den nächsten Wegspunkt normiert wird.
Kurz gesagt, der PID-Regler ist die Summe der drei Systemzustände, mit deren Hilfe manchmal auftretende System- und Zufallsfehler behoben werden können.
Diese Funktionen wurden empirisch ausgewählt und hängen vom Abstand zum Endpunkt im Pfad ab (er kann quadratisch, kubisch oder invers sein, aber dann haben wir uns für das Quadrat entschieden). Dies funktionierte, aber das einzige, was uns nicht zusagte, war, dass der Roboter bei Geschwindigkeiten über 0,7 Metern pro Sekunde nicht rechtzeitig bremsen konnte. Daher haben wir uns zu gegebener Zeit entschlossen, den gesamten Algorithmus neu zu erstellen.
Die erste Iteration auf dem Weg zur neuen Flugbahn war das Ersetzen des Vektors, zu dem wir wollten. Nun war es die Summe der Vektoren für die nächsten drei mit unterschiedlichen Koeffizienten. Die zweite Iteration schrieb Minimum Jerk. Kurz gesagt, dies ist eine Konstruktion eines Polynoms 5. Grades, wobei die x- und y-Koordinaten von der Ankunftszeit zu jedem Punkt abhängen.
Die Abbildung zeigt eine grafische Darstellung einer der Koordinaten über der Zeit sowie der Geschwindigkeit entlang dieser KoordinateDiese Art der Flugbahnregelung hat sich für uns bewährt, da bei der Auswahl verschiedener Koeffizienten weniger Manipulationen erforderlich sind, da alle Koeffizienten die Werte im Polynom sind, die auf der Grundlage von Ankunftszeit, aktueller Geschwindigkeit und Beschleunigung, Ausgangsgeschwindigkeit und Beschleunigung berechnet wurden.
Das Ergebnis der Umschreibung der Flugbahn war, dass es uns gelungen ist, die Durchschnittsgeschwindigkeit des Roboters zu verdoppeln.
Wie in den beiden vorherigen Fällen sind alle Hauptfunktionen zur einfachen Interaktion in einer separaten Datei hervorgehoben. Dieses Mal ist die PlannerTrajectory-Klasse für die Erstellung einer Trajektorie basierend auf MinimumJerk verantwortlich
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;
Das Foto zeigt alle deklarierten Variablen, die wir verwenden.Alles andere ist in einer anderen Datei hervorgehoben (include / trajectory_regulator.h): Punkte von Themen erhalten, entscheiden, ob zum nächsten Punkt gegangen werden soll (wenn es sich in einem Hindernis befindet, werden wir nicht gehen) und vieles mehr.
Migration zu ROS Melodic
Bis letztes Jahr haben wir die lte-Version von ROS-ROS Kinetic verwendet. Er passte uns im Allgemeinen, aber seine Unterstützung läuft im nächsten Jahr aus und viele der Pakete, die wir brauchen, wurden exklusiv für ROS Melodic herausgebracht. Und dann stellte sich heraus, dass der von uns verwendete costmap_server nicht unter Melodic steht.
Bei der Verarbeitung der Daten von den Karten ist ein Problem aufgetreten.
Wir haben die Grid-Karte gewählt, da der Stapel ähnlich ist, sich der Anfang der Karte jedoch an einer anderen Stelle befindet und die Werte der Karte selbst von 0 bis 1 variieren. Dies ist ein großes Problem im gesamten Navigationsstapel geworden. Wenn der globale Planer früher 50-mal pro Sekunde gestartet wurde (es gab Frequenzbeschränkungen, und daher wurde der Prozessor auch in der Hälfte eines Threads nicht zu häufig verwendet), ebnete er jetzt alle zwei Sekunden den Weg und hielt ihn für schlecht: Er lud einen Kern vollständig. In 2 Sekunden konnte der Roboter die gesamte Karte überqueren. Dies passte nicht zu uns und Versuche, diesen Prozess zu parallelisieren, scheiterten, weil dann keine Leistung mehr für andere Projekte übrig war (unter Berücksichtigung der Kosten für die Parallelisierung).
Wir haben uns entschlossen, den Stack erneut zu ändern und die Grid Map zugunsten des Occupancy Grids aufzugeben. Es ist ein neues Problem aufgetreten - die Unfähigkeit, mehrere Versionen von Karten gleichzeitig zu speichern (z. B. eine vollständige Karte mit allen Hindernissen und eine statische Karte mit nur dynamischen Hindernissen). Ich müsste die Hälfte des Codes ändern, was nicht besonders zuverlässig war. Daher haben wir uns entschlossen, nach alternativen Lösungen für dieses Problem zu suchen.
Cost Map Server
Nach langer Suche fanden wir die Fork Maps costmap_serverr:
https://github.com/lelongg/cost_map.git - sehr nützlich für unser Fork System.

Und anstatt nur die Gitterkarte zu warten, schaffen wir es jetzt, den wahrscheinlichen Ort des Feindes basierend auf der Vorhersage des Kalman-Filters für die Lieferung zu berechnen.

Eines der wichtigsten Dinge für einen Kartenserver ist eine Kartendatei, die zum erstmaligen Erstellen aller Layer verwendet wird, die anschließend nur aktualisiert werden. Es ist ein binäres PNG-Bild, in dem Schwarz ein Hindernis und Weiß eine freie Zone ist.

Es gibt auch eine Einstellungsdatei für die Konfiguration von cost_map_server. Es enthält Themen mit Feindpunkten, eine Inflationszone und die Größe des Quadrats, mit denen Sie auch die Gefahrenzone des Feindes auf die Karte setzen können.
########################### # 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
Alle Ebenen werden nur veröffentlicht, wenn jemand sie abonniert hat:
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); } }
Führen Sie auf Ihrem Computer
Um den gesamten Stapel zu starten, müssen Sie:
- Setzen Sie ROS
- roslaunch cost_map_server cost_map_server_alone.launch - um die Karte zu starten
- roslaunch global_planner global_planner.launch - Global Planer mit Parametern starten
- rosparam load $ (find local_planner) /param/param.yaml
- rosrun local_planner local_planning
- rosrun trajectory_regulator trajectory_regulator
- rosrun global_planner mover
- Rosrun Rviz
- Füge inflation_layer hinzu
- Senden Sie nun eine Nachricht an das Topic / gp / goal und wir senden den Roboter an den gewünschten Punkt
Nachdem Sie alle Elemente gestartet haben, steht Ihnen eine Simulation zur Verfügung, mit der Sie unseren Stapel auf Ihrem Computer starten können. Notwendige Gabel, , . , — . , eurobot, .
, , …
: t.me/SetUpSber
