Skip to content

Developer's Guide

Jens-Rene Giesen edited this page Sep 30, 2017 · 34 revisions

This is the Developer's Guide. It contains the technical details of the implementation. The guide assumes that you have read the User's Guide and have advanced programming skills. If you are not familiar with ROS (Robot Operating System) please read the ROS Documentation.

Building the Robot

Hardware

The robot used for this project is a Kobuki Turtlebot 2. It can receive commands from other devices using the Robot Operating System (ROS). The robot itself is shaped like a disk (see two figures below) and on top a platform can be attached to mount the computing unit and sensors.

Kobuki Turtlebot 2 front view

Kobuki Turtlebot 2 front view

Kobuki Turtlebot 2 back view

Kobuki Turtlebot 2 back view

Computing Unit

The computing unit used in the project is a Intel NUC with a Celeron Processor. To avoid tilting of the robot, when it accelerates, the robot was build as small as possible with only one platform attached. To make this working, some 3D-printed parts had to be added. One is a base plate to attach the NUC to the robot:

Front view

NUC front view

Bottom view

NUC bottom view

Back view (attached)

NUC back view (attached) NUC Base Plate stl-file

Adapter for the Astra

Another 3D-printed part is an adapter to attach a Kinect-like system called Astra. This adapter fits into the slot, which is normally for cable management, but by reversing the orientation of the platform, it can be used to attach the Astra this way:

NUC back view (attached) Astra mounting adapter stl-file

Stand-Off for the RPLIDAR

As laser scanner the RPLIDAR A2 is used, which has a coverage of 360 degree and one sample per degree. This had also be attached onto the robot, which as well needed a 3D-printed part, so it could measure without having the Astra in the field of view:

PRLIDAR mount PRLIDAR mount stl-file

Power and Wiring

The NUC is powered by the battery of the Turtlebot and is connected to the 12V output. For the data connection between the robot and the NUC, a USB-B cable is used. The Astra and the RPLIDAR are connected via USB to the NUC. The RPLIDAR is attached to a so called ”charging capable” USB-port, which is able to deliver the necessary current.

Parts list

Part Price
Intel® NUC-Kit NUC5CPYH 110€
TurtleBot 2 - Essentials Mobile Robot Platform 1.500€
Orbbec Astra / Astra2015R2 150$
PRLIDAR A2 500€

Initial Setup

The initial setup was already done by Kuboki. The robot only has to be connected to the same Wifi. To facilitate the startup, a .launch-file has been written, which contains the following:

<launch>

    <include file="$(find kobuki_node)/launch/robot_with_tf.launch"/>

    <include file="$(find turtlebot_bringup)/launch/includes/2dsensor/rplidar.launch"/>

    <!-- Forcing static transformations -->
        <!-- static_transform_publisher x y z yaw pich roll frame_id frame_child_id period[miliseconds]-->

    
        <node pkg="tf" type="static_transform_publisher" name="base_link_base_laser_link_tf" args="0.0 0.0 0.3 3.14159 0.0 0.0 /base_link /rplidar_laser_link 100" />

</launch>

It starts up the robot, after that the RPLIDAR and than creates a tf for the laser sensor, which is about 3cm above the ground.

Simulator

For the simulator the stage ros package has been used. For the robot model, a predefined Turtlebot model was used. Only the laser sensor parameters were changed to match the RPLIDAR. This is done in the turtlebot_model.inc at top in the ranger-section. The field of view (fov) is changed to 360, as well as the samples. The map in the simulator shows the 3rd floor of the SA building at the University of Duisburg-Essen, which is the place where the real robot was tested. The localization in the simulator is done by the fake amcl-package which provides a pseudo Monte Carlo localization.

Simulator

Localisation

For the localization of the real robot adaptive Monte Carlo localization is used (amcl). The corresponding ROS package can be used out of the box with the following parameters:

  • use_map_topic = false to get the map over the global frame
  • scan_topic = scan to set the correct topic for the laser scanner
  • initial_pose_(x,y,z) = 0.0
  • odom_frame_id = odom to set the odometry frame identifier
  • base_frame_id = base_link to set the base frame identifier
  • global_frame_id = map to set the global frame identifier

SLAM

The robot uses the gmapping package which provides a laser-based Simultaneous Localization And Mapping (SLAM). The gmapping algorithm reads laser scans and odometry of the robot and computes a map (for instance a building floorplan). For further information about gmapping please visit http://wiki.ros.org/gmapping. In the User's Guide you will find instructions how to use gmapping for this project.

Changed parameters

  • name="maxUrange" value="16.0" - As the robot is built for indoor use, the range of laser beams is cropped to this value.
  • name="temporalUpdate" value="3.0" - Every 3 seconds after the processed scan a new scan is performed.
  • map parameters - Changed the map size to the values listed below:
    • name="xmin" value="-50.0"
    • name="ymin" value="-50.0"
    • name="xmax" value="50.0"
    • name="ymax" value="50.0"
  • other parameters are equal to the default

Replacing/Modifying SLAM

  • The parameters for mapping can be found in the file 'slam_gmapping_pr2.launch' located in the 'launch' - folder. They can be changed as required. In some cases it has to be modified to the specific environment. So don't be afraid to play with the parameters.
  • In the 'src' - folder is the code for the gmapping. It can be changed if necessary or replaced with an other mapping algorithm. In case of replacing gmapping don't forget to change the launch-files 'mapping.launch' and lam_gmapping_pr2.launch' located in the 'launch' - folder.

Coverage

The coverage algorithm expects a map and the current position of the robot to provide the uncovered area. Historic positions are saved to determine the covered area.

Calculating the coverage area

After the covered algorithm received a map, it searches for walls and inflates them so that the robot can maintain a minimal distance to the walls. Gaps in walls that are smaller than the minimum are not flooded for the coverage. When the map is inflated and a initial position for the robot is known, a wavefront algorithm is executed to determine all the reachable area from the position of the robot which results in the coverage area. The difference between this area and the historic positions is published (i.e. sent to the zone generator).

While processing the map, the algorithm uses the same resolution as the map provides. The incoming positioning data is used to mark the area in a constant distance to the robot as covered.

Edge cases for incoming position data

If the coverage algorithm receives a position that is not part of the current coverage area, then this area is recalculated using the wavefront algorithm and the most recently received position as origin. The historic position data is not cleared: if this area intersects the new coverage area or if a further change of the position triggers the coverage area to go back to the first state, then the collected coverage markings are still considered.

If the received position is inside of a wall it is ignored. If the position is inside of the inflation radius of a wall, the shortest path from this position to a point outside of the inflation radius is added to the coverage area and then the remaining area is calculated using the described wavefront algorithm starting from that point outside of the inflation radius.

Navigation

For navigation the ROS navigation stack comes in to play. It is beeing configured and exposed via the launch/navigation_stack.launch file. For the meaning of the configuration files take a look at this part of the navigation stack setup tutorial in the ROS wiki.

With the navigation stack configured it is being used by the Planner node to sequentially drive to all expected points on the map. These points are provided by the Zone Generation node, which bases this points on the coverage data provided. Read on for more information about the Zone Generation & Planner logic.

Zone Generation

The zone generation works as follows

  1. Take in new coverage data and ensure that it contains at least 3 cells
  2. Overlay / aggregate the coverage grid with a more coarse-grained one, which are measurement-cells
    • Coverage cell-size 0.05, the measurement cells are an odd multiple of that which is the nearest but smaller than 1 quare meter => 0.95
    • Only cells with an overlap of at least 80% with the coverage-data is used for further computation
  3. Overlay / aggregate the measurement-cell-grid with a more coarse-grained one, which are zones
    • Zones are approximately 10 square meters in size, with a 2 x 5 layout
  4. Derive Nagivation-Data-Message contents
    • Only zone which overlapp measurement-cells are used
    • For each zone the overlapping measurement-cells are selected and their best-match point (see bellow) is published
  5. Publish Navgigation-Data-Message as well as other debugging related messages

To build the grid for measurement-cells and zones a special class was created wilson_ros/cell_grid_creator/CellGridCreator. This class takes in the cell specifications and does the grid calculation on demand. The resulting grid is a list of cells with a center and the best-match point. Where as the center-point explains it self, best-match point needs to be explained as follows: With the grid overlaying the original data-grid, a situation might occur, where the center of a cell does not align with an original-grid-cell. In this case position is chosen for the other origin-grid-cells that are covered, which is nearest to the center point.

Zone generator example

This image shows the cell and zone grid debug messages (red = zones, blue = measurement-grid). It also displays coverage data in green as well as two positions (one is the robot position, the second is the next goal send to the navgoagtion stack).

CellGridCreator

The CellGridCreator::createGrid() works as follows

  1. Ensure that the configured cell-size is a multiple of the original-grid-cell-size
  2. Search for the lowest & highest X/Y values
    • This may result in a smallest/biggest point that does not match an original-grid-cell, as the search is done for x and y separately
  3. Prepare a new grid, starting from the smallest Position (based on the values) until the grids contains the biggest Position (based on values)
  4. For each known original-grid-cell, search for the matching new grid that contains it and activate that new cell
    • So activated means: overlays at least 1 original-grid-cell
  5. Return only activated cells of the new grid in a single list

Topics

The zone generation node

  • Subscribes to topic
    • /cells (nav_msgs/GridCells), the coverage data
  • Publishes on
    • /navigation_data (custom message type msg/NavigationData.msg), the calculated zone & cell data
    • /navigation_cell_grid (nav_msgs/GridCells), the calculated cell grid (realtime)
    • /navigation_zone_grid (nav_msgs/GridCells), the calculated zone grid (realtime)
    • /navigation_cell_best_match (geometry_msgs/PoseArray), the calculated target pose for a cell
    • /navigation_zone_best_match (geometry_msgs/PoseArray), the center of the cell that is nearest to the zone center

Planner

The planner node in scripts/planner.py performs high level task planning with a SMACH state machine. The SimpleActionClient-API is used to send goal points to the move_base action server. The setup and configuration of the navigation stack is described in this tutorial. We use the default move_base action server, run rosrun move_base move_base to start it manually (it is started by default via the launch file launch/navigation_stack.launch or launch/navigation_sim.launch).

With the smach_viewer you can view the current state of the planning node:

WilsonROS SMACH State Machine

WaitForZone State

The state machine starts in the state WaitForZone. When there is no zone data (the deque is empty), the planner fetches the current result of the zone generator and stays in the WaitForZone state. Due to lack of deep object deserialization the nested data has to be deserialized explicitly. This data is not updated till the zone deque is completely empty. When there is zone data (the deque is not empty and contains deque's of waypoints), the state machine changes into the GotZone state.

GotZone State

This state is similar to the WaitForZone state. It process also a deque, but the deque contains Waipoints. These waypoints are our actual measurement points. If there is a waypoint in the deque, the state machine changes into the GotWaypoint state. If there is no waypoint (the deque is empty), the planner removes the current zone and changes into the WaitForZone state.

GotWaypoint State

This state is responsible for the actual measurement. It stays in this state, till the waypoint is reached (move_base action server returns GoalStatus SUCCEEDED), an error occurred or the timer limit was exceeded (default is 60s, increase this if you get a lot of false positives). Each time the planer sends a MoveBaseAction message to the move_base action server. The move_base action server is responsible for the actual movement to the goal point. If the waypoint is not reachable, the robot will stay at it's current position (probably the last successful reached waypoint) and does not start trying to move to the goal point. Currently, the only way to detect this, is to use a timeout. When the waypoint is estimated as reachable, but in reality is not, the robot will crash. To prevent this you have to set all parameters appropriate (e.g. radius of the robot).

When the waypoint is reached or the wait condition was not satisfied (error or timeout occurred), the planner removes the waypoint from the current zone. Then the state machine changes into the GotZone state.

For further help see this tutorial.