Skip to content
This repository was archived by the owner on Dec 28, 2022. It is now read-only.

Tutorial 1

Winston Hartnett edited this page Feb 15, 2022 · 5 revisions

Wallstopper

Setup

As always, you should start in the pe-tutorials repository. Remember to git pull or clone it with:

git clone --recursive https://www.github.com/uchicago-robotics/pe-tutorials.git

The --recursive flag makes git setup repositories we're using inside of pe-tutorials.

Exercise 1

Make sure to consult the ROS2 tutorials if you're unsure about terminology.

Create a ROS2 Package

First we need to create a new package for our nodes:

cd src
ros2 pkg create --build-type ament_python tutorial_1
cd .. && colcon build
source ./setup.bash

The ros2 pkg create subcommand will make a new ROS2 Python package called tutorial_1 in src. cd into tutorial_1 and note the files and directories ROS2 has made:

  • package.xml: tells ROS2 about our package's dependencies and extra information about its author
  • setup.py: Python-specific setup file; we use this to specify which Python programs we have in tutorial_1
  • tutorial_1/: our main source folder; all our Python scripts will go here

Our First Publisher

We're going to make a Python executable that publishes the location of a point (x, y, z coordinates) twice a second. Make a new file in the tutorial_1/tutorial_1 folder called point_location_sender.py:

#!/usr/bin/env python3
import rclpy
from rclpy.node import Node

from geometry_msgs.msg import PointStamped
from std_msgs.msg import Header
from geometry_msgs.msg import Point

The first line (#!/usr/bin/env python3) is called a shebang and tells ROS2 to interpret our file as Python code. rclpy is a core ROS2 Python library that manages nodes. PointStamped is a ROS2 message that bundles time and geometry information (Header) with point information (Point).

Messages

If we want to see what PointStamped contains, do:

ros2 interface show geometry_msgs/msg/PointStamped

Which shows:

std_msgs/Header header
Point point

Each line has an entry prefixed by a type like Header or Point followed by a name. In this case, the PointStamped message has two entries: a Header and Point. The Header contains some time and data content information. We want to know more about Point, so do:

ros2 interface show geometry_msgs/msg/Point

Which gives:

float64 x
float64 y
float64 z

Which is the floating point (i.e. decimal) coordinates of a point in 3D space.

Back to the File

First, let's add a SendPointLocation class, a main function, and a Python entry point:

class SendPointLocation(Node):
    def __init__(self):
        super().__init__('send_point_location')

def main(args=None):
    pass

if __name__ == "__main__":
    main()

Let's break this down:

  • In ROS2 Python, nodes are modeled as classes. Publishers, subscribers, services, and clients are all subclasses of the Node class. Make sure you understand Python's object-oriented style.
    • We make sure to setup SendPointLocation as a Node with super().__init__('send_point_location')
  • Our main function does nothing for now
  • The magic code below main just tells Python to run main when executing point_location_sender

Sending Point Locations

We want our SendPointLocation to send (publish) the PointStamped message. Under __init__ add:

self.publisher_ = self.create_publisher(PointStamped, 'my_point', 10)
self.timer = self.create_timer(0.5, self.timer_callback)

We'll use self.publisher_ to publish messages to the /my_point topic. The timer runs the self.timer_callback function (which we have yet to define) every 0.5s. Under SendPointLocation make a timer_callback function:

def timer_callback(self):
    my_header = Header(stamp = self.get_clock().now().to_msg(), frame_id = "odom")
    my_point = Point(x=1.0, y=2.0, z=3.0)
    my_point_stamped = PointStamped(header = my_header, point = my_point)

    self.publisher_.publish(my_point_stamped)
    self.get_logger().info(f"Published point {my_point_stamped.point}")
  • my_header is a header with some information about time and our coordinate frame
  • my_point is the point (1.0, 2.0, 3.0)
  • my_point_stamped is the message that bundles both my_header and my_point
    • If we printed this with print(my_point_stamped) we would see something like:
      header:
          stamp:
              sec: 1724321
              nanosec: 21721
          frame_id: odom
      point:
          x: 1.0
          y: 2.0
          z: 3.0
      
  • We send my_point_stamped into the aether with self.publisher_.publish and then log some info to the ROS2 logs.

Main

Now we need to register SendPointLocation with ROS2. Under main add:

rclpy.init(args=args)

send_point_location = SendPointLocation()

rclpy.spin(send_point_location)

# Optional
send_point_location.destroy_node()

rclpy.shutdown()
  • First, we setup ROS2 communication with init
  • We make a new SendPointLocation node and
  • The ROS2 spin function starts running send_point_location
    • This takes over our program until killed
  • We can optionally destroy our node with destroy_node, but Python will automatically destroy it if we don't
  • Finally, we make sure to close ROS2 communications for our program

Code Summary

#!/usr/bin/env python3
import rclpy
from rclpy.node import Node

from geometry_msgs.msg import PointStamped
from std_msgs.msg import Header
from geometry_msgs.msg import Point

class SendPointLocation(Node):
    def __init__(self):
        super().__init__('send_point_location')
        self.publisher_ = self.create_publisher(PointStamped, 'my_point', 10)
        self.timer = self.create_timer(0.5, self.timer_callback)

    def timer_callback(self):
        my_header = Header(stamp = self.get_clock().now().to_msg(), frame_id = "odom")
        my_point = Point(x=1.0, y=2.0, z=3.0)
        my_point_stamped = PointStamped(header = my_header, point = my_point)

        self.publisher_.publish(my_point_stamped)
        self.get_logger().info(f"Published point {my_point_stamped.point}")

def main(args=None):
    rclpy.init(args=args)
    send_point_location = SendPointLocation()
    rclpy.spin(send_point_location)

    send_point_location.destroy_node() # Optional
    rclpy.shutdown()

if __name__ == "__main__":
    main()

Our First Subscriber

Next to the point_location_sender.py file, make a new point_location_receiver.py:

#!/usr/bin/env python3
import rclpy
from rclpy.node import Node

from geometry_msgs.msg import PointStamped

class ReceivePointLocation(Node):
    def __init__(self):
        super().__init__('receive_point_location')
        self.subscriber_ = self.create_subscription(PointStamped, 'my_point', self.subscriber_callback, 10)

    def subscriber_callback(self, msg):
        self.get_logger().info(f"Received point: {msg.point.x} {msg.point.y} {msg.point.z}")

def main(args=None):
    rclpy.init(args=args)
    receive_point_location = ReceivePointLocation()
    rclpy.spin(receive_point_location)
    rclpy.shutdown()

if __name__ == "__main__":
    main()

This is similar to our publisher's code. This time, we use self.create_subscription to receive messages from the /my_point topic. Our subscriber_callback function just logs the x, y, and z coordinates of any received points.

Running a Python Package

Before we can run our ROS2 node, we need to tell ROS2 about our package.

Editing package.xml

ROS2 needs to know which dependencies (i.e. other packages) our program depends on. These are specified in package.xml in the pe-tutorials/src/tutorial_1 folder. Notice that we are importing stuff from a few Python packages at the top of our files:

  • rclpy
  • geomtry_msgs
  • std_msgs

These packages are all managed by ROS2 so we must specify them in the package.xml file. You can search for information about ROS2 packages at the Package Index. Note that not all Python imports uses ROS2 packages, so not every import is specified in package.xml.

After the <license>... field, add our dependencies with:

<exec_depend>rclpy</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>

Specifying Entry Point

We also need to connect the ros2 launch command to our Python programs in setup.py. Add two entries under the entry_points dictionary like so:

entry_points={
        'console_scripts': [
                'sender = tutorial_1.point_location_sender:main',
                'receiver = tutorial_1.point_location_receiver:main'
        ],
},

These new entries consist of four parts that tell ROS2 how to run our nodes: launch_name = package_name.file_name:function_to_run.

Running

Now we can run our package's nodes. Go back to pe-tutorials and run colcon build to build all our workspace's packages. If you want to build specific packages, use colcon build --packages-select tutorial_1. Then, do source ./setup.bash so we can access our new node from ros2 commands.

Run our publisher node with:

ros2 run tutorial_1 sender

We could also run it with:

ros2 run tutorial_1 point_location_sender.py

And our receiver node in a separate tab:

ros2 run tutorial_1 receiver

You should see the receiver printing out some points!

Exercise 2

Setup

Navigate to the wallstopper directory in pe-tutorials/src/.

Description

In this exercise, you will move a turtlebot towards a brick wall and stop it just before it collides. You must use the laser scan data from the robot's LiDAR to guide the robot's movements.

You should look at these topics by using ros2 topic type [TOPIC] to show their message types and then look at the message types with ros2 interface show [MSG] as above:

  • /cmd_vel: When you publish to this, you set the robot's velocity. linear.x is the forward velocity. angular.z is the angular velocity.
  • scan: LiDAR scans; ranges is a list of 360 numbers where each number is the distance to the closest obstacle in one-degree increments. The first entry is what's directly in front of the robot.

Running

Run the simulation world with:

cd launch/ && ros2 launch wallstopper_world.launch.py

Credits

This tutorial uses materials from the UChicago Intro to Robotics course (available here).

Clone this wiki locally