Warning
This page is located in archive. Go to the latest version of this course pages.

P1 - Mobile Robot Exploration

The main task is to implement ROS modules based on the tasks: T1a-ctrl, T1c-map, T1d-plan, and T1e-expl and thus create an integrated solution for autonomous robotic exploration.

Deadline January 5th, 23:59 PST
Points 15
Label in BRUTE P1
Evaluation Solution is evaluated by a demonstration to an instructor
Resources P1-expl resource package


Assignment

Implement ROS nodes to solve the exploration tasks. The provided resource pack support deployment using both the V-REP and STDR simulators. Moreover, an R-VIZ setup file is provided to visualize the robot knowledge of the environment using the messages published by the individual ROS nodes.


Simulators

The simulators provide and process the following inputs and outputs, respectively

Message type ROS Topic Description
Outputs Laser scan (sensor_msgs/LaserScan) /robot0/laser_0 Range measurements from a sensor
Robot pose (nav_msgs/Odometry) /robot0/odom Robot pose provided by a simulator
Inputs Velocity command (geometry_msgs/Twist ) /robot0/cmd_vel Velocities to drive the robot

To run the V-REP simulator

  1. run V-REP
  2. open a scene, e.g., blocks.ttt
  3. launch the ROS node

roslaunch uir_tools uir_backend_vrep.launch

When running the V-REP simulator, calling rospy.Time.now() causes the V-REP simulation time to freeze. Therefore, when using V-REP subscribe to the ROS topic /clock to get the current ROS time.

To run the STDR simulator

  1. launch the ROS node

roslaunch uir_tools uir_backend_stdr.launch


RVIZ

The provided RVIZ setup file may be used to visualize the following topics

Message type Topic Description
Robot odometry (nav_msgs/Odometry) /robot0/odom Robot position and orientation provided by a simulator
Laser scans (sensor_msgs/LaserScan) /robot0/laser_0 Range measurements from a sensor
Path (nav_msgs/Path) /robot0/path Path to be followed by the robot
Occupancy map (nav_msgs/OccupancyGrid ) /gridmap Map of the robot surroundings
Point cloud (sensor_msgs/PointCloud2 ) /frontiers/cells Frontier cells detected by the robot
Point cloud (sensor_msgs/PointCloud2 ) /frontiers/clusters Clustered frontier cells


Expected Behavior


Evaluation

A demonstration of the working robotic exploration in STDR or V-REP simulator is evaluated by an instructor during the labs.


Suggested architecture

The individual nodes roughly correspond to T1a-ctrl, T1c-map, and T1d-plan paired with T1e-expl. The following text describes the recommended architecture of ROS modules, and extends the idea of robotic exploration.

Note, it is strongly recommended to first prepare the ROS interface and test whether the messages are correctly sent and received. Then, connect all the interfaces within the ROS framework and test all the modules together.


Path following module

The path following module drives the robot along a given path by publishing velocity commands.

Message type Topic
Inputs Path (nav_msgs/Path) /robot0/path Path to be followed by the robot
Robot odometry (nav_msgs/Odometry) /robot0/odom Robot position and orientation provided by a simulator
Outputs Velocity command (geometry_msgs/Twist ) /robot0/cmd_vel Velocities to drive the robot

Unlike in T1a-ctrl, where the left and right velocity is used control the robot, the simulators accept geometry_msgs/Twist. Therefore, for your convenience a simplistic path follower is already prepared in the resource pack's uir_path_follower node.


Mapping module

The mapping module incrementally builds a map of the robot surroundings from the robot sensoric measurements.

Message type Topic
Inputs Laser scans (sensor_msgs/LaserScan) /robot0/laser_0 Range measurements from a sensor
Robot pose (nav_msgs/Odometry) /robot0/odom Robot pose provided by a simulator
Outputs Occupancy map (nav_msgs/OccupancyGrid ) /gridmap Map of the robot surroundings


Exploration module

The exploration module selects the exploration goals and plans paths for the robot to explore.

Message type Topic
Inputs Occupancy map (nav_msgs/OccupancyGrid ) /gridmap Map of the robot surroundings
Robot pose (nav_msgs/Odometry) /robot0/odom Robot pose provided by a simulator
Outputs Point cloud (sensor_msgs/PointCloud2 ) /frontiers/cells Frontier cells detected by the robot (for visualization only)
Point cloud (sensor_msgs/PointCloud2 ) /frontiers/clusters Clustered frontier cells (for visualization only)
Path (nav_msgs/Path) /robot0/path Path followed by the robot

This node is based on the tasks T1d-plan and T1e-expl. In the frontier based approach, the path is to be planned to the closest location selected among the detected frontiers, i.e., the borders between the free and unknown space. Note, it is beneficial to cluster the observed frontiers cells to reduce the computational load of goal selection. Moreover, keep in mind that even in a simulator the path is not executed perfectly. Therefore, using a safety margin around the walls is advisable.


Appendix

Setup

To run the ROS nodes, it is strongly recommended to use either Ubuntu 16 with ROS Kinetic or Ubuntu 18 with ROS Melodic. Detailed installation instructions may be found on ROS web pages ROS Kinetic, ROS Melodic.

On the lab computers, ROS Kinetic is already preinstalled but two more libraries need to be installed before using it.

pip install rospkg
pip install netifaces
Moreover, it is necessary to source the main ROS setup script, which has to be done in each new terminal instance. Thus, it is recommended to add the following source command in your ~/.bashrc file
echo "source /opt/ros/kinetic/setup.bash" >> ~/.bashrc
or alternatively when running ROS Meloding
echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc

Finally, on Ubuntu 16 the STDR simulator is installed using

sudo apt-get install ros-kinetic-stdr-*
On Ubuntu 18, STDR has to be compiled from source, which can be found at https://github.com/stdr-simulator-ros-pkg/stdr_simulator.


ROS Basics

On Ubuntu 16 and 18 the ROS workspace is created as follows

cd ~/
mkdir rds_ws
mkdir rds_ws/src
cd rds_ws
catkin_make
 
# source the workspace
cd devel
devel_path=$(pwd)
echo "source $devel_path/setup.bash" >> ~/.bashrc
source setup.bash
 
# Add new (custom) package to the workspace
cd ~/rds_ws/src                 # Go to src folder in your workspace.
ln -s [path to your package]    # Create symlink to your package (or place the whole package directly to src).
cd ~/rds_ws
catkin_make                     # Compile the workspace.
 
rospack list                    # Make sure that your pack is known. (Sometimes this is necessary to refresh ROS. ) 
                                # Now, you should be able to use the package within ROS (rosrun or roslaunch).
 
# useful commands
rostopic list              # all current topics in the ROS system
rostopic info [topic name] # show info about topic - publishers, subscribers
rostopic echo [topic name] # writes msgs data on certain topic to stdout
rostopic hz [topic name]   # prints frequency of msgs on a certain topic
 
rosnode list               # all currently running nodes
rosnode info [node name]   # info about the node: published topics, subscribed topics
 
# useful tools
rqt_graph                  # visualize connection between the nodes (might not be 100% accurate)
rviz                       # spatial visualization of the msgs
rosrun tf view_frames      # creates pdf with a visualization of the whole transformation tree (all the /tf msgs in the system) 
rosbag record              # capture ROS msgs on selected topics (data can be played with selected speed afterwards) 
rosbag play [bagfile]      # play data saved in bagfile

The main study material for ROS is http://wiki.ros.org/ROS/Tutorials. A special attention should be given to ROS message-based communication presented in http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28python%29.

courses/b4m36uir/projects/p1-expl.txt · Last modified: 2019/11/18 18:27 by pragrmi1