ROS LKW Wagen. Teil 6. Kilometerzähler mit Radgebern, Raumkarte, Lidar

Beiträge in der Reihe:
8. Wir steuern von der Telefon-ROS-Steuerung, GPS-Knoten
7. Roboterlokalisierung: Gmapping, AMCL, Referenzpunkte auf der Raumkarte
6. Kilometerzähler mit Radgebern, Raumkarte, Lidar
5. Wir arbeiten in Rviz und Pavillon: Xacro, neue Sensoren.
4. Erstellen Sie eine Robotersimulation mit den Editoren rviz und pavillon.
3. Beschleunigen, Kamera wechseln, Gang fixieren
2. Software
1. Eisen

Letztes Mal haben wir das Projekt in Form von separaten XACRO-Modulen entworfen, eine virtuelle Videokamera und ein IMU (Gyroskop) hinzugefügt.

In diesem Beitrag werden wir mit Kilometerzählern von optischen Encodern arbeiten, die auf Radwellen montiert sind, eine Raumkarte laden und sie auf einem echten Roboterwagen fahren.

Kilometerzähler und tf


Was Odometrie und tf ist und wie sie normalerweise in ROS implementiert werden, ist in der Ressource bereits gut beschrieben, daher verweisen wir hier beispielsweise auf die relevanten Artikel in der Theorie.
Ausgehend von der theoretischen Basis werden wir mit der Praxis arbeiten.

Beginnen wir mit der Arbeit an einem Wagenroboter, indem wir ihn über VNC verbinden.

Wechseln Sie in den Ordner rosbots_driver und erstellen Sie einen Dateiknoten. Diese Datei generiert eine Kilometerzähler und empfängt sie von optischen Encodern, die sie wiederum an arduino uno und dann an raspberry pi senden.

cd /home/pi/rosbots_catkin_ws/src/rosbots_driver/scripts/rosbots_driver touch diff-tf.py 

Wir haben den Code in die Datei eingefügt:

diff_tf.py
 #!/usr/bin/env python """ diff_tf.py - follows the output of a wheel encoder and creates tf and odometry messages. some code borrowed from the arbotix diff_controller script A good reference: http://rossum.sourceforge.net/papers/DiffSteer/ Copyright (C) 2012 Jon Stephan. """ import rospy #import roslib #roslib.load_manifest('differential_drive') from math import sin, cos, pi from geometry_msgs.msg import Quaternion from geometry_msgs.msg import Twist from geometry_msgs.msg import Vector3 from nav_msgs.msg import Odometry import tf from tf.broadcaster import TransformBroadcaster from std_msgs.msg import Int16, Int32, Int64, UInt32 ############################################################################# class DiffTf: ############################################################################# ############################################################################# def __init__(self): ############################################################################# rospy.init_node("diff_tf") self.nodename = rospy.get_name() rospy.loginfo("-I- %s started" % self.nodename) #### parameters ####### #Wheel radius : 0.0325 # wheel circum = 2* 3.14 * 0.0325 = 0.2041 # One rotation encoder ticks : 8 ticks # For 1 meter: 8 * ( 1 / 0.2041) = 39 ticks self.rate = rospy.get_param('~rate',10.0) # the rate at which to publish the transform self.ticks_meter = float(rospy.get_param('ticks_meter', 190)) # The number of wheel encoder ticks per meter of travel self.base_width = float(rospy.get_param('~base_width', 0.11)) # The wheel base width in meters self.base_frame_id = rospy.get_param('~base_frame_id','base_link') # basefootprint /the name of the base frame of the robot self.odom_frame_id = rospy.get_param('~odom_frame_id', 'odom') # the name of the odometry reference frame self.encoder_min = rospy.get_param('encoder_min', -2147483648) self.encoder_max = rospy.get_param('encoder_max', 2147483648) self.encoder_low_wrap = rospy.get_param('wheel_low_wrap', (self.encoder_max - self.encoder_min) * 0.3 + self.encoder_min ) self.encoder_high_wrap = rospy.get_param('wheel_high_wrap', (self.encoder_max - self.encoder_min) * 0.7 + self.encoder_min ) self.t_delta = rospy.Duration(1.0/self.rate) self.t_next = rospy.Time.now() + self.t_delta # internal data self.enc_left = None # wheel encoder readings self.enc_right = None self.left = 0 # actual values coming back from robot self.right = 0 self.lmult = 0 self.rmult = 0 self.prev_lencoder = 0 self.prev_rencoder = 0 self.x = 0 # position in xy plane self.y = 0 self.th = 0 self.dx = 0 # speeds in x/rotation self.dr = 0 self.yaw = 0.01 self.pitch = 0.01 self.roll = 0.01 self.then = rospy.Time.now() self.quaternion_1 = Quaternion() # subscriptions rospy.Subscriber("wheel_ticks_left", UInt32, self.lwheelCallback) rospy.Subscriber("wheel_ticks_right", UInt32, self.rwheelCallback) #rospy.Subscriber("imu_data", Vector3, self.imu_value_update) self.odomPub = rospy.Publisher("odom", Odometry,queue_size=10) self.odomBroadcaster = TransformBroadcaster() ############################################################################# def spin(self): ############################################################################# r = rospy.Rate(self.rate) while not rospy.is_shutdown(): self.update() r.sleep() ############################################################################# def update(self): ############################################################################# now = rospy.Time.now() if now > self.t_next: elapsed = now - self.then self.then = now elapsed = elapsed.to_sec() # calculate odometry if self.enc_left == None: d_left = 0 d_right = 0 else: d_left = (self.left - self.enc_left) / self.ticks_meter d_right = (self.right - self.enc_right) / self.ticks_meter self.enc_left = self.left self.enc_right = self.right # distance traveled is the average of the two wheels d = ( d_left + d_right ) / 2 # this approximation works (in radians) for small angles th = ( d_right - d_left ) / self.base_width # calculate velocities self.dx = d / elapsed self.dr = th / elapsed if (d != 0): # calculate distance traveled in x and y x = cos( th ) * d y = -sin( th ) * d # calculate the final position of the robot self.x = self.x + ( cos( self.th ) * x - sin( self.th ) * y ) self.y = self.y + ( sin( self.th ) * x + cos( self.th ) * y ) if( th != 0): self.th = self.th + th # publish the odom information quaternion = Quaternion() quaternion.x = 0.0 quaternion.y = 0.0 quaternion.z = sin( self.th / 2 ) quaternion.w = cos( self.th / 2 ) ''' try: quaternion.z = self.quaternion_1[2] quaternion.w = self.quaternion_1[3] except: quaternion.z = sin( self.th / 2 ) quaternion.w = cos( self.th / 2 ) pass ''' self.odomBroadcaster.sendTransform( (self.x, self.y, 0), (quaternion.x, quaternion.y, quaternion.z, quaternion.w), rospy.Time.now(), self.base_frame_id, self.odom_frame_id ) odom = Odometry() odom.header.stamp = now odom.header.frame_id = self.odom_frame_id odom.pose.pose.position.x = self.x odom.pose.pose.position.y = self.y odom.pose.pose.position.z = 0 odom.pose.pose.orientation = quaternion odom.child_frame_id = self.base_frame_id odom.twist.twist.linear.x = self.dx odom.twist.twist.linear.y = 0 odom.twist.twist.angular.z = self.dr self.odomPub.publish(odom) def imu_value_update(self, imu_data): orient = Vector3() orient = imu_data self.yaw = orient.x self.pitch = orient.y self.roll = orient.z try: self.quaternion_1 = tf.transformations.quaternion_from_euler(self.yaw, self.pitch, self.roll) #print self.quaternion_1[0] #print self.quaternion_1[1] #print self.quaternion_1[2] #print self.quaternion_1[3] except: rospy.logwarn("Unable to get quaternion values") pass ############################################################################# def lwheelCallback(self, msg): ############################################################################# enc = msg.data if (enc < self.encoder_low_wrap and self.prev_lencoder > self.encoder_high_wrap): self.lmult = self.lmult + 1 if (enc > self.encoder_high_wrap and self.prev_lencoder < self.encoder_low_wrap): self.lmult = self.lmult - 1 self.left = 1.0 * (enc + self.lmult * (self.encoder_max - self.encoder_min)) self.prev_lencoder = enc ############################################################################# def rwheelCallback(self, msg): ############################################################################# enc = msg.data if(enc < self.encoder_low_wrap and self.prev_rencoder > self.encoder_high_wrap): self.rmult = self.rmult + 1 if(enc > self.encoder_high_wrap and self.prev_rencoder < self.encoder_low_wrap): self.rmult = self.rmult - 1 self.right = 1.0 * (enc + self.rmult * (self.encoder_max - self.encoder_min)) self.prev_rencoder = enc ############################################################################# ############################################################################# if __name__ == '__main__': """ main """ diffTf = DiffTf() diffTf.spin() 


Speichern Sie die Datei und machen Sie sie ausführbar:
CTRL+X
chmod +x diff-tf.py


Führen Sie nun auf dem Roboter die zweiten Knoten aus - Treiber und diff-tf:
1. Terminal:

 python diff_tf.py 

2. Platz:

 rosrun rosbots_driver part2_cmr.py 

Im 3. Terminal werden wir überprüfen, ob es neue Themen zu odom und tf gibt:



Lassen Sie uns mit dem Befehl rostopic echo odom sehen, was im Thema veröffentlicht wird (und ob es überhaupt veröffentlicht wird).
Die Ausgabe erfolgt ungefähr wie folgt:



Ohne die laufenden Knoten auf dem Roboter zu schließen, starten wir jetzt den Steuercomputer mit den grafischen Umgebungen rviz und pavillon.

* Ein Image (virtuelle VMWare-Maschine mit Ubuntu 16.04 + ROS Kinetic), das zuvor zum Download angeboten wurde, enthält alles, was Sie benötigen.

Führen Sie das Modell auf dem Steuercomputer (im Folgenden als „Computer“ bezeichnet) in rviz aus:

 roslaunch rosbots_description rviz.launch 

Das geladene Robotermodell, mit dem in früheren Beiträgen gearbeitet wurde, wird geladen:



Fügen Sie rviz zwei Anzeigen hinzu, indem Sie auf Hinzufügen klicken. Die Anzeige mit Kilometerzähler und die Anzeige mit tf aktivieren die Kontrollkästchen, um sie zu visualisieren.

In dem Fenster, in dem das Robotermodell dargestellt ist, werden charakteristische Grafiken angezeigt:


* Um es besser sichtbar zu machen, können Sie die Robotmodel-Anzeige ausschalten.

Wir steuern den Roboter über die Tastatur des Computers und sehen, wie sich die Visualisierung von tf und Kilometerzähler ändert.

Ohne rviz im 2. Terminal zu schließen, starten wir die Steuerung über die Tastatur:

 rosrun teleop_twist_keyboard teleop_twist_keyboard.py /cmd_vel:=/part2_cmr/cmd_vel 

Bei der Steuerung des Roboters werden im Fenster mit der Visualisierung angezeigt: roter Pfeil (Visualisierung des Odom-Themas), Vektorlinien (tf-Thema).

Wenn der rote Pfeil des Odom-Themas die Bewegungsrichtung des Roboters anzeigt, zeigen die Vektorlinien tf, wie sich die einzelnen Elemente des Roboters im Raum befinden:

das Video


Um fortzufahren, müssen Sie die Kilometerzähler „einstellen“.
Schließen Sie dazu den rviz-Editor und starten Sie ihn erneut, ohne das Modell mit dem folgenden Befehl zu visualisieren:

 rosrun rviz rviz 

Dies ist notwendig, damit nur base_link und odom von den Vektoren des tf-Themas übrig bleiben:



In rviz ist eine Zelle 1 Meter. In der Realität muss der Roboter daher auch 1 Meter passieren, damit die Daten vergleichbar sind.

Wir passieren 1 Meter am Roboter und steuern ihn über die Tastatur. In rviz muss der Roboter auch 1 Meter fahren - eine Zelle.

Wenn der Roboter länger fährt als in rviz oder umgekehrt, eine kürzere Strecke als in der Realität, müssen Sie die zuvor erstellte Datei diff_tf.py bearbeiten, nämlich diesen Block:

diff_tf.py
  #### parameters ####### #Wheel radius : 0.0325 # wheel circum = 2* 3.14 * 0.0325 = 0.2041 # One rotation encoder ticks : 8 ticks # For 1 meter: 8 * ( 1 / 0.2041) = 39 ticks self.rate = rospy.get_param('~rate',10.0) # the rate at which to publish the transform self.ticks_meter = float(rospy.get_param('ticks_meter', 190)) # The number of wheel encoder ticks per meter of travel self.base_width = float(rospy.get_param('~base_width', 0.11)) # The wheel base width in meters 


Karte


Um irgendwohin zu gelangen, benötigen Sie eine Karte. Für die Zwecke unseres Roboters benötigen wir eine Raumkarte.
Lass uns mit ihr arbeiten.

Um eine Karte auf rviz hochzuladen, müssen Sie im Projekt (rosbots_description) auf dem Computer (nicht auf dem Roboter) einen Kartenordner erstellen und zwei Dateien darin ablegen, aus denen die Karte besteht: map.pgm und map.yaml.
* In einem Ordner können sich mehrere Kartendateien befinden, Sie können jedoch nur eine in den Assistenten hochladen.

Eine Karte in ROS besteht aus zwei Dateien, von denen eine ein PGM-Bild ist, wobei jedes Pixel entweder:

  • Leerraum ist frei;
  • Schwarzraum wird von einem Hindernis besetzt;
  • Grauraum wurde noch nicht erforscht.

Die zweite .yaml-Datei ist eine Datei mit den Einstellungen der Karte, in der die Abmessungen, die Pixelbelegung mit verschiedenen Typen (oben aufgeführt) und andere Parameter angegeben sind.

Führen Sie den Knoten auf dem Computer aus, auf dem die Karte veröffentlicht wird:

 rosrun map_server map_server /home/pi/catkin_ws/src/rosbots_description/maps/rail_lab.pgm 0.05 

Führen Sie im benachbarten Terminal das Modell in rviz aus:

 roslaunch rosbots_description rviz.launch 

Fügen Sie in rviz eine Kartenanzeige hinzu.

In rviz stellte sich heraus, dass der Roboter unverhältnismäßig groß war und sich außerhalb der Karte befand:



Um dies zu beheben, müssen Sie eine Karte ausführen, bei der die Zellengröße 1 Meter beträgt. Starten Sie die Karte mit Parameter 1 am Ende neu:

 rosrun map_server map_server /home/pi/catkin_ws/src/rosbots_description/maps/rail_lab.pgm 1 

Jetzt können Sie die Karte in rviz fahren und den Roboter über die Tastatur steuern:

das Video


Also, was wurde erreicht :

  • Empfangen von Kilometerzählerdaten von optischen Radcodierern des Roboters und Senden an Themen zur Anzeige in rviz;
  • Konfigurieren Sie die Roboter-Kilometerzähler so, dass sie der zurückgelegten Strecke live und virtuell entsprechen.
  • Laden Sie eine Raumkarte und zeigen Sie sie an.

Trotz der Tatsache, dass die Karte angezeigt wird und der Roboter mit einer „abgestimmten“ Kilometerzähler darauf fahren kann, ist der Roboter in Wirklichkeit blind. Er sieht keine Hindernisse und wird über sie stolpern. Das zweite Minus ist die in rviz geladene virtuelle Raumkarte, mit der Sie alleine in alle Richtungen fahren können, auch dort, wo die Hindernisse deutlich sichtbar sind.

Wie kann der Roboter Hindernisse in der Realität und virtuell "sehen"?

Mit einer virtuellen Umgebung ist einfacher. Alles hier basiert auf dem Pavillon-Emulator-Editor. Und in früheren Beiträgen wurde dies erwähnt.

Es ist komplizierter mit der Realität. Wir benötigen ein Element (Sensor), das Hindernisse anzeigt und dies dem System meldet.

Eine Möglichkeit besteht darin, Lidar auf den Roboter zu setzen.

Lidar RPlidar A1


Wir werden die kostengünstige Budgetlösung verwenden und den Lidar auf den Roboter setzen. Möglicherweise ist diese Lösung teurer als die Verwendung des gleichen Kinect, aber wie die Praxis gezeigt hat, ist sie hinsichtlich Geschwindigkeit, Genauigkeit und einfacher Installation effektiver (weniger umständlich). Außerdem ist es einfacher, mit Lidar zu arbeiten Es sind keine Überlegungen erforderlich, wie das Gerät mit Strom versorgt und mit dem Projekt verbunden werden kann (https://habr.com/en/company/tod/blog/210252/).

Wir benötigen das ros-Paket, um mit lidar arbeiten zu können - wiki.ros.org/rplidar .
Mit Hilfe des Lidars erstellen wir eine Karte des Raumes und verwenden sie auch für die Navigation.

Wie man rplidar in ROS installiert, enthält viele Artikel, zum Beispiel hier .

Wir werden das Wissen grauhaariger alter Männer nutzen und Pakete mit Lidar im System des Roboters installieren:

 cd /home/pi/rosbots_catkin_ws/src git clone https://github.com/robopeak/rplidar_ros.git cd .. catkin_make 

Installieren Sie auf dem Computer das Paket für die Arbeit mit der Karte:

 cd /home/pi/rosbots_catkin_ws/src git clone https://github.com/tu-darmstadt-ros-pkg/hector_slam </code> cd .. catkin_make 

Führen Sie das Paket auf dem Roboter aus und prüfen Sie, ob das Lidar funktioniert:

 sudo chmod a+rw /dev/ttyUSB0 roslaunch rplidar_ros rplidar.launch 

* Der erste Befehl ermöglicht den Zugriff auf den USB-Port, an dem das Lidar angeschlossen ist.

Wenn alles reibungslos gelaufen ist, werden Zeilen an die Konsole ausgegeben:

 [ INFO] [1570900184.874891236]: RPLIDAR running on ROS package rplidar_ros. SDK Version:1.9.0 RPLIDAR S/N: ---------------- [ INFO] [1570900187.397858270]: Firmware Ver: 1.24 [ INFO] [1570900187.398081809]: Hardware Rev: 5 [ INFO] [1570900187.401749476]: RPLidar health status : 0 [ INFO] [1570900188.014285166]: current scan mode: Express, max_distance: 12.0 m, Point number: 4.0K , angle_compensate: 1 

Hier konfigurieren wir sofort ein kleines Lidar, weil Die offizielle Website sagt, dass es (Lidar) besser funktionieren kann.

Wir müssen die Ausgabe erreichen, wenn das Scannen nicht 4,0 KB Punkte beträgt, die standardmäßig ausgegeben werden, sondern 8,0 KB. Diese Option verbessert die Scanqualität geringfügig.

Dazu setzen wir im rplidar-Paket einen weiteren Parameter - den Scan-Modus:

 cd /rosbots_catkin_ws/src/rplidar_ros/launch nano nano rplidar.launch 

Und danach

 <param name="angle_compensate" type="bool" value="true"/> 
Fügen Sie die Zeile hinzu:

 <param name="scan_mode" type="string" value="Boost"/> 

Die zweite Zeile, die hier behoben werden muss:

 <param name="frame_id" type="string" value="laser"/> 

Ersetzen Sie den Laserwert durch base_link.

* Wenn Sie nun den Knoten mit dem Befehl roslaunch rplidar_ros rplidar.launch neu starten, ist die Ausgabe anders:

 [ INFO] [1570900188.014285166]: current scan mode: Boost, max_distance: 12.0 m, Point number: 8.0K , angle_compensate: 1 

Schau mal rein. welches Lidar in Rviz anzeigt.

Führen Sie dazu den Roboter aus:

 roslaunch rplidar_ros rplidar.launch 

Auf einem Computer:

 roslaunch rosbots_description rviz.launch 

Fügen Sie in rviz die LaserScan-Anzeige hinzu und wählen Sie das Scan-Thema aus. Weiterhin wird ersichtlich, dass Nachrichten in das Thema fallen:



Im Fenster mit der Visualisierung des Roboters stellte sich heraus, dass der Roboter ein Riese war. Mit seiner Größe werden wir es später herausfinden. Nun erstellen wir eine Raumkarte.

Erstellen Sie dazu ein Paket mit einem Knoten:

 catkin_create_pkg my_hector_mapping rospy cd my_hector_mapping mkdir launch cd launch nano hector.launch 

hector.launch
 <?xml version="1.0"?> <launch> <node pkg="tf" type="static_transform_publisher" name="laser_link" args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /laser 50" /> <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen"> <!-- Frame names --> <param name="map_frame" value="map" /> <param name="odom_frame" value="base_link" /> <!-- Map size / start point --> <param name="map_resolution" value="0.050"/> <param name="map_size" value="1024"/> <param name="map_start_x" value="0.5"/> //  <param name="map_start_y" value="0.5" /> <param name="map_multi_res_levels" value="2" /> <!-- Map update parameters --> <param name="update_factor_free" value="0.4"/> <param name="update_factor_occupied" value="0.9" /> <param name="map_update_distance_thresh" value="0.4"/> <param name="map_update_angle_thresh" value="0.06" /> <param name="laser_z_min_value" value="-1.0" /> <param name="laser_z_max_value" value="1.0" /> <!-- Advertising config --> <param name="advertise_map_service" value="true"/> <param name="scan_subscriber_queue_size" value="5"/> <param name="scan_topic" value="scan"/> </node> </launch> 


 cd ~/rosbots_catkin_ws catkin_make 

Lass es uns laufen.

Auf dem Roboter:

1. Terminal: roslaunch rplidar_ros rplidar.launch
2. rosrun rosbots_driver part2_cmr.py

Auf einem Computer:

1. Terminal: roslaunch my_hector_mapping hector.launch
2. roslaunch rosbots_description rviz.launch
3. rosrun teleop_twist_keyboard teleop_twist_keyboard.py /cmd_vel:=/part2_cmr/cmd_vel

In den Anzeigen müssen Sie eine Karte hinzufügen und als fester Rahmen base_link auswählen. Dann können Sie in Echtzeit beobachten, wie der Lidar den Raum um ihn herum "beleuchtet":



Im aktuellen Schritt müssen Sie zum Erstellen einer Karte durch den Raum fahren und in verschiedenen Winkeln „anhalten“, damit das Lidar sie auf der Karte markiert.

Also Lehrbücher empfehlen. Wir empfehlen jedoch, den Roboter aufzunehmen, mit ihm zu gehen und ihn vor sich zu halten. Die Geschwindigkeit beim Erstellen einer Karte ist also in dem Sinne höher, dass Sie nicht abgelenkt werden müssen und schauen müssen, wo der Roboter ohne Sichtkontakt im nächsten Raum gefahren ist.

Wenn der Roboter während einer Fahrt um seine Achse gedreht wird, hinterlässt der Lidar außerdem charakteristische schwarze Artefakte an den Stellen, an denen es tatsächlich keine Hindernisse gibt:



Speichern Sie die Karte nach dem Erstellen mit dem folgenden Befehl:

 rosrun map_server map_saver -f map-1 

Das Erstellen der perfekten Karte mit einem Budget-Lidar ist ein Mythos. Daher werden wir dem Lidar in Photoshop helfen. Wir werden die schwarzen Artefakte von der Karte entfernen, wo es wirklich keine Hindernisse gibt, und die Wände an schwarzen Linien ausrichten:



Vergessen Sie nicht, die Karte im PNG-Format zu speichern.

Jetzt wiederholen wir auf dem Computer die Befehle, die am Anfang des Beitrags standen, aber mit einer neuen Karte:
1. Terminal: rosrun map_server maserver /home/pi/catkin_ws/src/rosbots_description/maps/map-1.pgm 0.05
2. roslaunch rosbots_description rviz.launch

Ergebnis in rviz:



Die neue Karte wurde geladen, wie das Robotermodell darauf, aber der Roboter befindet sich außerhalb der Karte.

Wir werden später darüber sprechen, aber lassen Sie uns zunächst Folgendes zusammenfassen:

  • Lidar RP-Lidar A1 beherrschen
  • Erstellen einer Raumkarte mit einem Lidar, Anpassen und Laden in den visuellen Editor von rviz.

Dateien zum Herunterladen: Raumkarte .

Source: https://habr.com/ru/post/de471028/


All Articles