Skip to content

MOGI-ROS/KogRob_HW_23_24

 
 

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

23 Commits
 
 
 
 
 
 
 
 

Repository files navigation

Kognitív robotika projekt feladat

Kognitív robotika tárgynak féléves projekt feladata, ahol ROS Noetic környezetben fejlesztettem egy mobil robotot.

A projektet készítette:

  • Czémán Róbert

Tartalomjegyzék

  1. Feladatleírás
  2. Telepítési útmutató
  3. Szimuláció futtatása
  4. Versenypálya megtervezése
    4.1. Gazebo szimuláció
  5. Versenyautó megtervezése
    5.1. RViz szimuláció
  6. Alaklmazott szenzorok
    6.1. Kamera
  7. Kormányzás
  8. Képfeldolgozás
    8.1. Képfeldolgozás lépései
    8.2. Nehézségek a képfeldolgozás során
    8.3 .A problémák megoldása
    8.4. Az alkalmazott megoldások hátrányai
  9. Végeredmény

Feladatleírás

A feladat megvalósítása során a következő pontoknak kellett eleget tennünk:

  • méretarányosan kicsinyített versenypálya készítése,
  • versenyautó modell készítése,
  • a robot autonóm vezetése saját ROS node segítségével.

Telepítési útmutató

  1. A repositoryt az alábbi paranccsal tudjuk megszerezni:
git clone https://github.com/czrobi2001/KogRob_HW_23_24.git
  1. WSL használata esetén: XServer telepítése (grafikus alkalmazás futtatása miatt)

    • a telepítés megtehető például a következő linkre kattintva: XServer
    • XServer konfigurálása: Az Extra settings oldalon pipáljuk be a Disable access control opciót, valamint az Additional parameters for VcXsrx felirítú mezőbe gépeljük be a következők:
    -nowgl
  2. Szükséges függőségek (dependency) telepítése:

    • Pythonhoz a scipy könytár az alábbi parancs segítségével:
    pip install scipy
    • Az alábbi ROS package-ek:
    • ros-noetic-actionlib
    • ros-noetic-rospy
    • ros-noetłc-theora-image-transport
    • ros-noetic-urdf
    • ros-noetic-xacro
    • ros-noetic-roslaunch
    • ros-noetic-joint-state-publisher
    • ros-noetic-joint-state-publishér-gui
    • ros-noetic-robot-state-publisher
    • ros-noetic-rviz
    • ros-noetic-ackermann-steering-controller
    • ros-noetic-controller-manager
    • ros-noetic-joint-state-controller
    • ros-noetic-ros-control
    • ros-noetic-ros-controllers
    • ros-noetic-control-toolbox
    • ros-noetic-gazebo-ros-control
    • ros-noetic-joint-limits-interface
    • ros-noetic-gazebo-ros
    • ros-noetic-rqt-robot-steering
    • ros-noetic-hector-trajectory-server

    Ezek telepíthetők, az alábbi paranccsal:

    rosdep install -y --from-paths src --ignore-src --rosdistro noetic -r
  3. Legvégül futtassuk le a workspace gyökérkönyvtárában a catkin_make parancsot.

  4. A neurális háló modell generálása a train_network.py futtatásával, hogy a képfeldolgozáshoz rendelkezésre álljon a tanított háló.

A lépések teljesítésével már képesek leszünk a szimulációt futtatni. Ennek a lépéseit a követkeező fejezet tartalmazza.

Szimuláció futtatása

A szimuláció elindításhoz először a mobil robotot kell megnyitni gazebo-ban, amit az alábbi paranccsal tehetünk meg.

roslaunch line_follower spawn_robot.launch

Majd miután elindult a szimuláció elindíthatjuk a follow_curve.py scriptet, ami a képfeldogozást végzi.

rosrun line_follower line_follower_cnn.py

Ha az irányításhoz használt paraméterekre is kíváncsiak vagyunk, akkor egy 3. terminál ablakba írjuk be a következőt:

rqt

Miután megnyílt az rqt a Plugins > Topics > Topic Monitor menüpontra kattintás után keressük ki a cmd_vel topicot és pipáljuk be. Ezen belül a linear és angular opciókat lenyitva láthatók a pontos értékek.

Versenypálya megtervezése

A versenypályát Solidworks-ben egy letöltött, és importált kép segítségével terveztem meg, aminek kontúrját körberajzoltam Besier görbékkel, és kiexportáltam egy .stl fájlt.

A pálya kontrúja alt text

Blenderbe beimportálva készítettem egy a gazebo által is kezelhető collada mesht, ami tartalmazza a blenderben beállított színeket is. Ahhoz, hogy a Gazebo megnyitáskor lássa a modellt, az alábbi sort kell a .bashrc-hez hozzá adni.

export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:~/bme_catkin_ws/src/KogRob_HW_23_24/gazebo_models

Gazebo szimuláció

A modellt a szimulációs környezetben, vagyis a gazebo-ban is megtekinthetjük, ehhez az alábbi parancsot futtassuk:

roslaunch line_follower world.launch 

A szimuláció elindításához egy .world kiterejesztésű fájlra van szükségünk, ami tartalmazza a világ, szimulációhoz szükséges fizikai beállításait, valamint a hozzáadott további modelleket.

alt text

A kocsi beimportálása a világba a spawn_robot.launch fájl elindításával történik, ahol argumentumként a robot kezdeti pozícióját is megadhatjuk.

Versenyautó megtervezése

A versenyautó tervezésnék ötletét internetes forrásból vettem, ami egy kis lego kocsi, amit Solidworks-ben az egyszerűbb kezelhetőség érdekében módosítottam.

alt text

Ezekután blenderben beállítottam a megfelelő színeket, majd exportáltam egyenként a mozgó komponenseket. A mobil robot vázát illetve a szimulációhoz szükséges paraméterek beállítását a mogi_bot.xacro fájlban tettük meg, a robot irányításáért és a kamera képért felelős gazebo plug-in-ket a mogi_bot.gazebo fájlban adtuk hozzá.

RViz szimuláció

A robot modellt megtekinthetjük RViz-ben az alábbi parancs segítségével:

roslaunch line_follower_race_car check_urdf.launch

Alkalmazott szenzorok

A képfeldogozáshoz egy kamera került elhelyezésre a versenykocsi elején, aminek paramétereit az órán használtak alapján állítottuk be.

Kamera

A kamerát az alábbi plugin valósítja meg.

<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
  <alwaysOn>true</alwaysOn>
  <updateRate>0.0</updateRate>
  <cameraName>head_camera</cameraName>
  <imageTopicName>image_raw</imageTopicName>
  <cameraInfoTopicName>camera_info</cameraInfoTopicName>
  <frameName>camera_link_optical</frameName>
  <hackBaseline>0.07</hackBaseline>
  <distortionK1>0.0</distortionK1>
  <distortionK2>0.0</distortionK2>
  <distortionK3>0.0</distortionK3>
  <distortionT1>0.0</distortionT1>
  <distortionT2>0.0</distortionT2>
</plugin>

Kormányzás

A kormányzás megtervezése volt az egyik fő feladat a projekt során. Fontos volt a megfelelő típus kiválasztása, mivel a pálya és az autó adottságai miatt több szempontnak is meg kellett felelni. Ezek közül például kiemelném azt, hogy az autónak képesnek kell lennie nagyon kis íven is elfordulnia.

Végül a feladatot a skid-steer kormányzással valósítottuk meg. Az erre alkalmazott plugin:

<gazebo>
  <plugin name="ros_force_based_move" filename="libgazebo_ros_force_based_move.so">
    <commandTopic>cmd_vel</commandTopic>
    <odometryTopic>odom</odometryTopic>
    <odometryFrame>odom</odometryFrame>
    <torque_yaw_velocity_p_gain>10000.0</torque_yaw_velocity_p_gain>
    <force_x_velocity_p_gain>10000.0</force_x_velocity_p_gain>
    <force_y_velocity_p_gain>10000.0</force_y_velocity_p_gain>
    <robotBaseFrame>base_footprint</robotBaseFrame>
    <odometryRate>50.0</odometryRate>
    <publishOdometryTf>true</publishOdometryTf>
  </plugin>
</gazebo>

Képfeldolgozás

Képfeldolgozás lépései

A robot irányításáért a line_follower_cnn.py nevű Python script felel.

  1. tanító képek mentése, és címkézése save_training_images.py segítségével
  • a gazebo szimulációban készített kameraképek kimentése
  • a képek címkézése, kiválogatása jobb, bal, előre, állj, lassíts és semmi képekre,amik a neurális háló tanító bemenetei lesznek.
  1. neurális háló tanítása

    Az alkalmazott neurális háló LeNet jellegű konvolúciós neruális háló, ami 128x128 képet vár bemenetként, és 6 kimenetet szolgáltat, amik:

    • Előre
    • Jobbra
    • Balra
    • Ne mozdulj!
    • Sebesség korlát
      if label == 'forward':
          label = 0
      elif label == 'right':
          label = 1
      elif label == 'left':
          label = 2
      elif label == 'pedestrian':
          label = 3
      elif label == 'speed_limit':
          label = 4
      else:
          label = 5

    A LeNet neurális hálóról bővebben: LeNet

    Neurális háló tanításához az órán is használt Python scriptet használtam, aminek futtatásával a címkézett tanító minták alapján meghatározza a modell paramétereit.

    A tanításhoz az alábbi sort kell lefuttatni parancsorban, a scriptet tartalmazó mappán belül:

    python3 train_network.py
  2. iteráció, amíg a modell nem elég pontos, és nem elég alacsony a veszteség a tanítás előrehaladtával

    A tanítás addig folytatódott, amíg a mobil robot minden kanyart hibátlanul nem vett, ahol elakadt rátanítás volt szükséges. Az 1. és 2. pontok között iteráltam addig, amíg nem kaptam egy megfelelő modellt.

  3. robot irányításához szükséges paraméterek meghatározása

    • ezek a paraméterek a robot sebessége az x-tengelye mentén (linear.x) és az elfordulása a z-tengelye mentén (angular.z)
    • a paramétereket, amiket feltételben vitsgálunk, a neurális háló kimenetei
        # last change reaches defined value change the speed/rotation
        if prediction == 0: # Forward
            self.cmd_vel.linear.x = 0.5
            self.cmd_vel.angular.z = 0
        elif prediction == 1: # Right
            self.cmd_vel.angular.z = -1
            self.cmd_vel.linear.x = 0
        elif prediction == 2: # Left
            self.cmd_vel.angular.z = 1
            self.cmd_vel.linear.x = 0
        elif prediction == 3: # Pedestrian
            self.cmd_vel.angular.z = 0.0
            self.cmd_vel.linear.x = 0.0
        elif prediction == 4: # Speed_limit
            self.cmd_vel.linear.x = 0.2
        else: # Nothing
            self.cmd_vel.angular.z = 0.0
            self.cmd_vel.linear.x = 0.0
  4. a meghatározott paraméterek közlése

    • a paramétereket a cmd_vel topic-ba küldjük Twist üzenet formájában

Nehézségek a képfeldolgozás során

Sok-sok kísérletezést követően eljutottam oda, hogy a robot képes végighaladni a teljes pályán hiba nélkül, egész jó tempóban. A korábbi verziókban az alábbi hibák álltak fenn:

  1. a kanyarokat nagyon lassan veszi be
  2. kanyar szélén nem ismeri fel a háló a kanyarodást
  3. nem elegendő pixel mérte esetén információ vesztés áll fent, emiatt a még az erőforrás zsempontjából megnegedhető pixel méret a 128x128

A problémák megoldása

Az előző részben említett problémákra végül a következő megoldásokat eszközöltem:

  1. minden mozgást meghatározó feltételben pluszban vizsgálok egy változót, aminek értékét figyelem aszerint, hogy mennyi idő telt el az utolsó háló kimenet változás óta. Ha ez meghaladja a beállított értéket, növelem a beavatkozást addig, amíg nem változik a háló kimenete.
  2. a problémát az idézte elő, hogy nem volt elég tanító minta minden esethez, így rá kellett tanítani a hálóra az új képekkel.

Az alkalmazott megoldások hátrányai

  1. az meghatározott időértékek alapvetően a jelenlegi pálya alapján lettek kikísérletezve, így nem garantálható, hogy minden más esetben megfelleően fog működni
  2. változtatva a beavatkozás mértékét új pálya ívekre futhat a robot az eddig megszokottól, így lehetséges, hogy újabb tanítás lesz szükséges az új képekkel
  3. egy kimenetet szolgáltat a neurális háló, amit ebben az esetben jobb lenne több kimnetre terjeszteni. Egyiken megmondani a kanyarodás mértékét, másikon pedig a képen detektált táblát, mert jelenleg egy kimeneten van ez lekezelve, és ahhoz hogy az elvártaknak megfeleljen a robot mozgása, jelentősen több tanítóképpel kellene felvenni.

Végeredmény

Az elkészült projekt demonstrációs videója:

About

No description, website, or topics provided.

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Languages

  • Python 68.6%
  • CMake 31.4%