5. Ros Workshop - arieldo/MorBot GitHub Wiki

Ros Workshop can be done ONLY on the jetbot

In this workshop, you will learn how to create a new ROS package named jetbot_control_node in the morbot_ws workspace.

This package implements ros cmd_vel geometry_msgs/Twist topics and JetBot Motion liberis to drive the robot via Ros.

This package can be a good stepping stone to developing Ros and JetBot projects.

You will also copy From the MorBot git repository or create a jetbot_controller.py script in the package's scripts folder and install the necessary rospy and geometry_msgs dependencies.

Table of Contents

  1. Prerequisites
  2. Scenarios
  3. Workshop scenario
  4. JetBot control package
  5. Understand the jetbot_controller.py
  6. Running the jetbot_controller node
  7. Adding Launch File to jetbot_control_node
  8. Building the workshop scenario

Create a New ROS Package for JetBot Control Node

Prerequisites

  • JetBot environment set up Jetson Nano and Linux Setup
  • ROS environment set up on your jetson , IF not Check out HowTo ROS
  • Basic knowledge of ROS concepts, such as nodes, topics, and messages ,IF not Check out ROS 101
  • Basic knowledge of Publisher and Subscriber in Python for ROS ,IF not Check out ROS PubSubPy
  • Basic knowledge of Creating new Packages in ROS
  • Basic knowledge of Python programming language

dependencies :

  • rospy:

    rospy is a Python library for the Robot Operating System (ROS) that enables Python programmers to easily interface with the ROS system. With rospy, you can create ROS nodes, subscribe and publish to topics, call and provide services, and interact with the ROS parameter server, among other things. It simplifies the process of developing Python-based ROS applications and helps to manage communication between various nodes in a distributed robot system.

  • geometry_msgs:

    geometry_msgs package contains messages for common geometric primitives such as points, vectors, and poses. These messages are used to interact with the ROS geometry library, which provides a variety of geometry-related functionality, including conversions between rotation matrices, quaternions, and Euler angles; a 2D transform library; and a 2D polygon library.

scenarios

One ros workspace can have many projects that utilize the same package but with different purposes

To better organize different projects we will Create the scenarios folder inside your workspace directory (~/MorBot/morbot_ros/morbot_ws/src):

cd ~/MorBot/morbot_ros/morbot_ws/src
mkdir scenarios

workshop scenario

The workshop scenario is a hands-on learning experience, The main goal of a workshop scenario is to provide practical experience and deepen the understanding of ROS concepts, ultimately enabling participants to apply the knowledge in real-world robotics applications.

In this workshop, we will create a new package named workshop inside the scenarios folder.

cd ~/MorBot/morbot_ros/morbot_ws/src/scenarios
catkin_create_pkg workshop rospy geometry_msgs

Jetbot control package

The jetbot_control_node package is a ROS package that implements the jetbot_control_node node. This node is responsible for controlling the JetBot robot. It subscribes to the /cmd_vel topic and publishes the appropriate motor speeds to the JetBot robot.

/cmd_vel is a commonly used ROS topic name for sending velocity commands to a mobile robot. The topic is generally used with messages of the geometry_msgs/Twist type, which represents velocities in free space.

The jetbot_control_node package can be used in a lot of applications and there it will sit in the src folder inside your workspace directory (~/MorBot/morbot_ros/morbot_ws/src) (And Not in a specific scenario)

  1. Create a new package named jetbot_control_node inside your workspace directory (~/MorBot/morbot_ros/morbot_ws/src):
    cd ~/MorBot/morbot_ros/morbot_ws/src
    catkin_create_pkg jetbot_control_node rospy geometry_msgs
  1. Create a new directory named scripts inside your package directory (~/MorBot/morbot_ros/morbot_ws/src/jetbot_control_node):
    cd ~/MorBot/morbot_ros/morbot_ws/src/jetbot_control_node
    mkdir scripts 
  1. Create a new source file inside the scripts directory. For example, create a Python file named jetbot_controller.py:
    cd scripts
    touch jetbot_controller.py

Make the script executable:

    cd ~/MorBot/morbot_ros/morbot_ws/src/jetbot_control_node/scripts
    chmod +x jetbot_controller.py

4. understand the jetbot_controller.py

This Python script for controlling a JetBot robot using the ROS framework. The script subscribes to the /cmd_vel topic, which provides linear and angular velocity commands, and then sets the robot's motor speeds accordingly.

The script uses the JetBot Python library to control the robot's motors. The library provides a Robot class that can be used to control the robot's motors. The Robot class has a set_motors() method that can be used to set the motor speeds. The set_motors() method takes two arguments: the left motor speed and the right motor speed. The motor speeds are specified as floating-point values between -1.0 and 1.0, where -1.0 is full speed backward, 0.0 is stopped, and 1.0 is full speed forward.

#!/usr/bin/env python3

import rospy
from geometry_msgs.msg import Twist
from jetbot import Robot

print("Start jetbot controller")
class JetBotController:
    def __init__(self):
        # Initialize the ROS node
        rospy.init_node('jetbot_controller', anonymous=True)

        # Create a Robot object
        self.robot = Robot()

        # Subscribe to the '/cmd_vel' topic and define the callback function
        rospy.Subscriber('/cmd_vel', Twist, self.cmd_vel_callback)
        rospy.spin()

    # Callback function for the '/cmd_vel' topic
    def cmd_vel_callback(self, msg):
        # Extract linear and angular velocity from the message
        linear_x = msg.linear.x
        angular_z = msg.angular.z

        # Calculate motor speeds based on linear and angular velocities
        left_motor_speed = linear_x - angular_z
        right_motor_speed = linear_x + angular_z

        # Set motor speeds
        self.robot.set_motors(left_motor_speed, right_motor_speed)

if __name__ == '__main__':
    try:
        # Create a JetBotController object
        jetbot_controller = JetBotController()
    except rospy.ROSInterruptException:
        # Handle the ROSInterruptException gracefully
        pass

let's break down jetbot_controller.py

a. Import the necessary modules:

    #!/usr/bin/env python3

    import rospy 
    from geometry_msgs.msg import Twist 
    from jetbot import Robot 
  • rospy: A Python library for ROS
  • geometry_msgs.msg: A Python library for ROS messages
  • jetbot: A Python library for controlling the JetBot robot

b. Create a class named JetBotController:

    class JetBotController:
        def __init__(self):
            # Initialize the ROS node
            rospy.init_node('jetbot_controller', anonymous=True)

            # Create a Robot object
            self.robot = Robot()

            # Subscribe to the '/cmd_vel' topic and define the callback function
            rospy.Subscriber('/cmd_vel', Twist, self.cmd_vel_callback)
            rospy.spin()

Define the JetBotController class:

  • init : The constructor initializes the ROS node, creates a Robot object, subscribes to the /cmd_vel topic, and starts the rospy.spin() loop to keep the node alive and process incoming messages.

c. Create a callback function for the /cmd_vel topic:

    # Callback function for the '/cmd_vel' topic
    def cmd_vel_callback(self, msg):
        # Extract linear and angular velocity from the message
        linear_x = msg.linear.x
        angular_z = msg.angular.z

        # Calculate motor speeds based on linear and angular velocities
        left_motor_speed = linear_x - angular_z
        right_motor_speed = linear_x + angular_z

        # Set motor speeds
        self.robot.set_motors(left_motor_speed, right_motor_speed)
  • cmd_vel_callback : A callback function that gets triggered when a new message is received on the /cmd_vel topic. The function extracts linear and angular velocities from the message, calculates the motor speeds, and then sets the motor speeds for the JetBot robot.

d. Create a main() function that creates a JetBotController object:

    if __name__ == '__main__':
        try:
            # Create a JetBotController object
            jetbot_controller = JetBotController()
        except rospy.ROSInterruptException:
            # Handle the ROSInterruptException gracefully
            pass
  • main() : The main function creates a JetBotController object.

  • In this code snippet, the try block attempts to create an instance of the JetBotController class. This class is responsible for setting up the ROS node and initializing the JetBot robot. The try block ensures that the program will attempt to execute the code inside it without causing the entire program to crash if an exception occurs.

  • The except rospy.ROSInterruptException: block catches any ROSInterruptException that might be raised during the execution of the code inside the try block. This specific exception is raised by ROS when there is an interruption to the normal execution of the node, such as a keyboard interrupt or a shutdown request from the ROS system. By using the except block, the program can handle this exception gracefully, allowing the script to exit without causing a crash or unexpected behavior.

    In this case, the handling of the exception is minimal, as it simply uses the pass statement to do nothing and exit the block. This means that if a ROSInterruptException is caught, the program will exit the try and except blocks and terminate gracefully without any additional actions.

functional version of jetbot controller class-based code:

#!/usr/bin/env python3

import rospy
from geometry_msgs.msg import Twist
from jetbot import Robot

def cmd_vel_callback(msg, robot):
    # Extract linear and angular velocity from the message
    linear_x = msg.linear.x
    angular_z = msg.angular.z

    # Calculate motor speeds based on linear and angular velocities
    left_motor_speed = linear_x - angular_z
    right_motor_speed = linear_x + angular_z

    # Set motor speeds
    robot.set_motors(left_motor_speed, right_motor_speed)

def main():
    print("Start jetbot controller")

    # Initialize the ROS node
    rospy.init_node('jetbot_controller', anonymous=True)

    # Create a Robot object
    robot = Robot()

    # Subscribe to the '/cmd_vel' topic and define the callback function
    rospy.Subscriber('/cmd_vel', Twist, cmd_vel_callback, callback_args=robot)
    rospy.spin()

if __name__ == '__main__':
    try:
        main()
    except rospy.ROSInterruptException:
        # Handle the ROSInterruptException gracefully
        pass
  1. Build the package:
    cd ~/MorBot/morbot_ros/morbot_ws
    catkin_make
    source devel/setup.bash

7. Try Running the node:

  1. Launch a new terminal

    roscore
  2. Launch a new terminal

    • rosrun is a command-line tool in the ROS used to run individual nodes or packages within a ROS environment. It simplifies launching nodes without needing to create and configure launch files.
    cd ~/MorBot/morbot_ros/morbot_ws/src/jetbot_control_node/scripts
    rosrun jetbot_control_node jetbot_controller.py
  1. Test the node by publishing a Twist message to the /cmd_vel topic:

    Caution!!!! JetBot will physically move , make sure it has enough space to move around.

  • Launch a new terminal
   rostopic pub /cmd_vel geometry_msgs/Twist "linear:
  x: 0.5
  y: 0.0
  z: 0.0
angular:
  x: 0.0
  y: 0.0
  z: 0.0"
  1. To stop the node, press Ctrl+C in the terminal where the node is running.

Attention! The robot will not stop automatically after the node terminates!

You must send a new message with zero speed to halt the robot:

   rostopic pub /cmd_vel geometry_msgs/Twist "linear:
  x: 0.0
  y: 0.0
  z: 0.0
angular:
  x: 0.0
  y: 0.0
  z: 0.0"

Your jetbot_control_node package is now set up with the jetbot_controller.py script in the scripts folder and all necessary rospy and geometry_msgs dependencies.

In the future, you can extend this package by adding more scripts or nodes to control various aspects of the JetBot robot. Remember to modify the package.xml file in the jetbot_control_node folder if you need to add more dependencies.

Adding teleoperate

We using the package teleop_twist_keyboard that allows you to control your robot's movements by issuing commands from the keyboard. It publishes geometry_msgs/Twist messages to the /cmd_vel topic. VERY COOL :)

  1. Install the teleop_twist_keyboard package:
    cd ~/MorBot/morbot_ros/morbot_ws/src
    git clone https://github.com/ros-teleop/teleop_twist_keyboard.git
  1. Build the package:
    cd ~/MorBot/morbot_ros/morbot_ws
    catkin_make
    source devel/setup.bash
  1. Run the teleop_twist_keyboard node:
  • Ensure that you have roscore actively running in one terminal, and jetbot_controller.py executing in a separate terminal.

  • Launch a new terminal

    rosrun teleop_twist_keyboard teleop_twist_keyboard.py
  1. Test the node by pressing the keys to control the robot's movements:

    Caution!!!! JetBot will physically move , make sure it has enough space to move around.

    • i - forward
    • k - backward
    • j - left
    • l - right
    • u - forward-left
    • o - forward-right
    • m - backward-left
    • . - backward-right
    • , - stop
  2. To stop the node, press Ctrl+C in the terminal where the node is running.

Adding Launch File to jetbot_control_node

ROS launch files are XML files used to configure and start multiple nodes, parameters, and other settings required for a specific robot application. They provide a convenient way to start a complex system with a single command. Launch files typically have a ".launch" extension and use the roslaunch command-line tool to execute them. They simplify the process of starting and managing multiple nodes, allowing for greater flexibility and organization in robot software development.

To add a new launch file to your package, follow these steps:

  1. Add a new directory named launch inside your package directory (~/MorBot/morbot_ros/morbot_ws/src/jetbot_control_node):
    cd ~/MorBot/morbot_ros/morbot_ws/src/jetbot_control_node
    mkdir launch 
  1. Create a new launch file inside the launch directory. For example, create a launch file named jetbot_controller.launch:
    cd launch
    touch jetbot_controller.launch
  1. Open the launch file and write the XML code to configure the nodes and parameters you want to launch:
   <launch>
    <node name="jetbot_controller" pkg="jetbot_control_node" type="jetbot_controller.py" output="screen" />
</launch>
  1. Save the launch file and close the editor.

  2. Build your package again using the catkin_make command:

    cd ~/MorBot/morbot_ros/morbot_ws
    catkin_make
  1. Source the workspace's setup.bash file to make the new launch file available in your ROS environment:
    source devel/setup.bash
  1. Run the launch file using the roslaunch command:
    roslaunch jetbot_control_node jetbot_controller.launch
  1. To stop the launch file, press Ctrl+C in the terminal where the launch file is running.

  2. Test the node by publishing a Twist message to the /cmd_vel topic:

    Caution!!!! JetBot will physically move , make sure it has enough space to move around.

    • Launch a new terminal
   rostopic pub /cmd_vel geometry_msgs/Twist "linear:
  x: 0.5
  y: 0.0
  z: 0.0
angular:
  x: 0.0
  y: 0.0
  z: 0.0"
  1. To stop the node, press Ctrl+C in the terminal where the node is running.

Attention! The robot will not stop automatically after the node terminates!

You must send a new message with zero speed to halt the robot:

   rostopic pub /cmd_vel geometry_msgs/Twist "linear:
  x: 0.0
  y: 0.0
  z: 0.0
angular:
  x: 0.0
  y: 0.0
  z: 0.0"

OR use teleop :

  • Launch a new terminal
    rosrun teleop_twist_keyboard teleop_twist_keyboard.py

Now, you have successfully added nodes and launch files to your ROS package. You can continue to develop your package by adding more nodes, launch files, or other resources as needed. Remember to build your package and source the setup.bash file after making changes.

building the workshop scenario

cd ~/MorBot/morbot_ros/morbot_ws/src/scenarios/workshop

Add scripts to your workshop scenario

  1. Create a new directory named scripts inside your package directory (~/MorBot/morbot_ros/morbot_ws/src/scenarios/workshop):
    cd ~/MorBot/morbot_ros/morbot_ws/src/scenarios/workshop
    mkdir scripts 
  1. Create a new source file inside the scripts directory. For example, create a Python file named jetbot_motion_control.py:
    cd scripts
    touch jetbot_motion_control.py

Make the script executable:

    cd ~/MorBot/morbot_ros/morbot_ws/src/scenarios/workshop/scripts
    chmod +x jetbot_motion_control.py
  1. understand the jetbot_motion_control.py

The script starts by initializing the ROS node with rospy.init_node(). It then creates a Publisher object that publishes to the /cmd_vel topic. The queue_size=10 parameter sets the outgoing message queue size.

The script enters a loop that continues until the node is shut down. Inside the loop, it creates a Twist message and sets the linear and angular velocities. The linear velocity along the x-axis is set to 0.5 (usually meters/second), and the angular velocity around the z-axis is set to 0.1 (usually radians/second).

#!/usr/bin/env python
import rospy
from geometry_msgs.msg import Twist

def driver():
    # Initialize the Publisher Node with name 'jetbot_motion_control'
    rospy.init_node('jetbot_motion_control', anonymous=True)
    
    # Create a Publisher object, publishing to the '/cmd_vel' topic
    pub = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
    
    # Set the publishing rate (Hz)
    rate = rospy.Rate(10) 

    while not rospy.is_shutdown():
        # Initialize a Twist message
        twist_msg = Twist()
        
        # Set the linear and angular velocities
        twist_msg.linear.x = 0.5
        twist_msg.angular.z = 0.1

        # Publish the message
        pub.publish(twist_msg)

        # Sleep for the remaining time of the rate
        rate.sleep()

if __name__ == '__main__':
    try:
        driver()
    except rospy.ROSInterruptException:
        pass

Adding Launch File to workshop

To add a new launch file to your package, follow these steps:

  1. Add a new directory named launch inside your package directory (~/MorBot/morbot_ros/morbot_ws/src/scenarios/workshop):
    cd ~/MorBot/morbot_ros/morbot_ws/src/scenarios/workshop
    mkdir launch 
  1. Create a new launch file inside the launch directory. For example, create a launch file named workshop_jetbot_controller.launch:
    cd launch
    touch workshop_jetbot_controller.launch
  1. Open the launch file and write the XML code to configure the nodes and parameters you want to launch:
    <launch>
    <node name="jetbot_controller" pkg="jetbot_control_node" type="jetbot_controller.py" output="screen" />
    <node name="jetbot_motion_control" pkg="workshop" type="jetbot_motion_control.py" output="screen" />
    </launch>
  1. Save the launch file and close the editor.

  2. Build your package again using the catkin_make command:

    cd ~/MorBot/morbot_ros/morbot_ws
    catkin_make
  1. Source the workspace's setup.bash file to make the new launch file available in your ROS environment:
    source devel/setup.bash
  1. Run the launch file using the roslaunch command:
    roslaunch workshop workshop_jetbot_controller.launch
  1. To stop the launch file, press Ctrl+C in the terminal where the launch file is running.

    Caution!!!! JetBot will physically move , make sure it has enough space to move around.

  • To stop the node, press Ctrl+C in the terminal where the node is running.

Next - Now you redy to build AI scenarios for jetbot :

As part of the ROS Workshop, we will build engaging AI-inspired demo projects using NVIDIA Jetson and ROS. These demos are designed to showcase the integration of deep learning models and robotic control to create interactive and intelligent behaviors in small-scale robots.

These demos not only provide hands-on experience with cutting-edge technologies but also inspire creativity and technical skill development in robotics and AI. Each project is crafted to integrate seamlessly with ROS, enabling participants to implement and expand upon these scenarios in their robotic applications.

⚠️ **GitHub.com Fallback** ⚠️