Main Content

Explore Basic Behavior of the TurtleBot

This example helps you to explore basic autonomy with the TurtleBot®. The described behavior drives the robot forward and changes its direction when there is an obstacle. You will subscribe to the laser scan topic and publish the velocity topic to control the TurtleBot.

Prerequisites: Communicate with the TurtleBot

Connect to the TurtleBot

Make sure you have a TurtleBot running either in simulation through Gazebo® or on real hardware. Refer to Get Started with Gazebo and Simulated TurtleBot or Get Started with a Real TurtleBot for the startup procedure. This example uses the Gazebo-simulated Turtlebot.

In the downloaded virtual machine, click the Gazebo House shortcut to start up the world.

Initialize ROS. Connect to the TurtleBot by replacing ipaddress with the IP address of the TurtleBot.

ipaddress = "http://192.168.178.133:11311";
rosinit(ipaddress)
Initializing global node /matlab_global_node_05319 with NodeURI http://192.168.178.1:51558/

Create a publisher for the robot's velocity and create a message for that topic. Communicate using structure format messages for improved performance.

robot = rospublisher("/cmd_vel","DataFormat","struct");
velmsg = rosmessage(robot);

Receive Scan Data

Make sure that you start the lidar and camera if you are working with real TurtleBot hardware. The command to start the lidar and camera is:

 roslaunch turtlebot3_bringup turtlebot3_core.launch
 roslaunch turtlebot3_bringup turtlebot3_lidar.launch
 roslaunch turtlebot3_bringup turtlebot3_rpicamera.launch

You must execute the command in a terminal on the TurtleBot. The TurtleBot uses the LDS-01 Lidar to construct a laser scan that is published on the /scan topic. For the remainder of this example, the term laser scan refers to data published on this topic.

Subscribe to the topic /scan.

laser = rossubscriber("/scan","DataFormat","struct");

Wait for one laser scan message to arrive and then display it.

scan = receive(laser,3)
scan = struct with fields:
       MessageType: 'sensor_msgs/LaserScan'
            Header: [1×1 struct]
          AngleMin: 0
          AngleMax: 6.2832
    AngleIncrement: 0.0175
     TimeIncrement: 0
          ScanTime: 0
          RangeMin: 0.1200
          RangeMax: 3.5000
            Ranges: [360×1 single]
       Intensities: [360×1 single]

figure
rosPlot(scan);

If you see an error, it is possible that the laser scan topic is not receiving any data. If you are running in simulation, try restarting Gazebo. If you are using hardware, make sure that you started the lidar and camera properly.

Run the following lines of code, which plot a live laser scan feed for ten seconds. Move an object in front of the TurtleBot and bring it close enough until it no longer shows up in the plot window. The laser scan has a limited range because of hardware limitations. The LDS-01 lidar has a minimum sensing range of 0.12 meters and a maximum range of 3.5 meters. Any objects outside these limits will not be detected by the sensor.

tic;
while toc < 10
  scan = receive(laser,3);
  rosPlot(scan);
end

Simple Obstacle Avoidance

Based on the distance readings from the laser scan, you can implement a simple obstacle avoidance algorithm. You can use a simple while loop to implement this behavior.

Set some parameters that will be used in the processing loop. You can modify these values for different behavior.

spinVelocity = 0.6;       % Angular velocity (rad/s)
forwardVelocity = 0.1;    % Linear velocity (m/s)
backwardVelocity = -0.02; % Linear velocity (reverse) (m/s)
distanceThreshold = 0.6;  % Distance threshold (m) for turning

Run a loop to move the robot forward and compute the closest obstacles to the robot. When an obstacle is within the limits of the distanceThreshold, the robot turns. This loop stops after 20 seconds of run time. CTRL+C (or Control+C on the Mac) also stops this loop.

  tic;
  while toc < 20
      % Collect information from laser scan
      scan = receive(laser);
      rosPlot(scan);
      data = rosReadCartesian(scan);
      x = data(:,1);
      y = data(:,2);
      % Compute distance of the closest obstacle
      dist = sqrt(x.^2 + y.^2);
      minDist = min(dist);     
      % Command robot action
      if minDist < distanceThreshold
          % If close to obstacle, back up slightly and spin
          velmsg.Angular.Z = spinVelocity;
          velmsg.Linear.X = backwardVelocity;
      else
          % Continue on forward path
          velmsg.Linear.X = forwardVelocity;
          velmsg.Angular.Z = 0;
      end   
      send(robot,velmsg);
  end

Disconnect from the Robot

Clear the workspace of publishers, subscribers, and other ROS related objects when you are finished with them.

clear

Use rosshutdown once you are done working with the ROS network. Shut down the global node and disconnect from the TurtleBot.

rosshutdown
Shutting down global node /matlab_global_node_05319 with NodeURI http://192.168.178.1:51558/

More Information

The laser scan has a minimum range at which it no longer sees objects in its way. That minimum is somewhere around 0.12 meters from the lidar.

The laser scan cannot detect glass walls. Following is an image from the camera:

Here is the corresponding laser scan:

The trash can is visible, but you cannot see the glass wall. When you use the TurtleBot in areas with windows or walls that the TurtleBot might not be able to detect, be aware of the limitations of the laser scan.

Next Steps

Refer to the next example: Control the TurtleBot with Teleoperation