University of York RPRK lab sessions for MSc Intelligent Robotics ELE00118M Practical Robotics (PRAR). Available for download in: RPRK TurtleBot Lab Sessions || Google Drive. These lab sessions show how a general control "Turtlebot" class to control the RPRK robot is achieved by solving the lab tasks progressively. To see last version of the RPRK class, check RPRK Control Class.

Overview

The RPRK (Raspberry Pi Robotics Kit) lab sessions are designed for the MSc Intelligent Robotics course at the University of York, specifically for the ELE00118M Practical Robotics module, in the Autumn term. The kit allows students to build a mobile robot equipped with various sensors and actuators managed by a Raspberry Pi Model 4 and an Arduino Nano 33 BLE via the custom Arduino Robotics Board (ARB). These sessions guide students through the fundamentals of robotics, including sensor integration, motor control, and serial communications, culminating in the development of a robot that can navigate and map an environment autonomously.

This project is designed for students interested in the fields of robotics and software engineering, using Raspberry Pi, Arduino, Python, and C++. It contains a set of practical lab sessions that allow hands-on experience with real-world robotic systems programming and control.

The focus is on interfacing and controlling various robotic functionalities such as motor control, sensor integration, and visual processing using OpenCV. The project is structured in a way to guide the user from simple to more complex robotics applications, making it suitable for educational purposes or for anyone looking to enhance their robotics skills.

Directory Description

Getting Started

Software and Libraries

To run this project, you will need:

For the Arduino:

On the Raspberry Pi:

On your computer:

Hardware

The Raspberry Pi Robotics Kit (RPRK) is designed to help students build and program a mobile robot capable of solving a maze through localization and mapping. The robot uses various sensors, including wheel encoders, a front-facing camera, two side ultrasonic sensors, and a front infrared sensor, to navigate its environment. The kit includes:

Installation

  1. Download the contents of RPRK TurtleBot Lab Sessions || Google Drive

  2. Install the ARB Library on your Arduino:

    1. In the Arduino IDE, go to the menu bar and select Sketch > Include Library > Add .ZIP Library....

    2. Navigate to the directory where you have saved your "ARB.zip" file.

    3. Select the file and click on 'Open'. The IDE will then install the library.

    4. Verify Installation:

      • To check if the library has been successfully installed, go back to Sketch > Include Library. You should see the library named "ARB" at the bottom of the drop-down menu.

      • Click on it to include the library in your current sketch, which should automatically insert an include statement like #include <ARB.h> at the top of your sketch.

  3. Open a connection to the Raspberry Pi using PuTTY or directly through HDMI (Windows instructions). Further instructions in Connecting to the Raspberry Pi in RPRK and Lab 1:

    1. Connect to the Raspberry Pi with your laptop using the serial USB to UART HAT and a USB cable.

    2. Check what COM port the device is connected to using "Device Manager"

    3. Establish a Serial connection with PuTTY using the device COM port and baud rate 115200.

    Alternatively, you can connect a screen and keyboard using the micro HDMI and USB-A ports in the Raspberry Pi directly to the Raspberry Pi to access the terminal directly.

    1. Login using your login details for the Raspberry Pi in CLI. For the lab RPRK devices, the details are the following:

      • Username: pi

      • Password: raspberry

  4. Connect the Pi to a local WiFi network and check the device's IP address on the network.

    1. Type sudo raspi-config in the command line to open the configuration screen.

    2. Go to “2: Network Options” and then “N2 Wireless LAN” and enter the SSID and passphrase for your network. You must connect the Pi to the same network as your computer. For the lab network, use the following details:

      • SSID: robotlab

      • Password: vetzlentath

    3. Go to "Finish" and wait a few moments for the Raspberry Pi to connect.

    4. Type ifconfig on the terminal.

    5. Look for the section called wlan0. You should see your IP address there (e.g 144.32.70.210).

    6. Take note of your IP, it can be used to connect to the board through SSH or to transfer files with FTP. You can now close the serial PuTTY or direct connection.

  5. Connect through SSH using PuTTY (Windows instructions)

    1. Open PuTTY again. You must be connected to the same network as the Raspberry Pi.

    2. Establish an SSH connection using host name "username@ip_address" (e.g pi@144.32.70.210) and port 22, using the previously established IP address.

    3. To forward camera image data from the Pi to your computer, you must:

      • Have XMing installed in your device. Further instructions in Lab 6

      • Execute XMing before establishing a connection. It will run in the background.

      • In PuTTY, go to Connections > SSH > X11 and check the box that says 'Enable X-11 forwarding'.

    4. If you wish, save the session under your preferred name by going to Session > "Load, save or delete a stored session". Write your session name under Saved Sessions and click "Save".

    5. Click "Open" at the bottom-right of the window.

    6. Login using your login details for the Raspberry Pi in CLI. For the lab RPRK devices, the details are the following:

      • Username: pi

      • Password: raspberry

  6. View, add and modify files using WinSCP (Windows instructions). Further instructions in Lab 1

    1. Open WinSCP. You must be connected to the same network as the Raspberry Pi.

    2. Create a "New Site" with the following details:

      • File Protocol: SFTP

      • Host Name: The device's IP address for the network in format XXX.XX.XX.XXX (e.g 144.32.70.210). Refer to step 4 in Installation.

      • Port: 22

      • User Name: Your username for the Raspberry Pi. In lab devices: pi.

      • Password: Your password for the Raspberry Pi. In lab devices: raspberry.

    3. Click "Login". After a connection is established you should be able to see the files in the Pi.

  7. Upload all project files to the Raspberry Pi using WinSCP.

  8. Install Python dependencies with the CLI in SSH PuTTY:

    All of the Python libraries can be installed using pip:

    pip install numpy opencv-python picamera matplotlib ...

Usage

Running the Code

To run Arduino files, upload the respective .ino files to the Arduino Nano using the Arduino IDE.

For the Raspberry Pi, navigate to the specific lab or showcase directory and run the Python scripts through the terminal:

python3 <script_name>.py

Ensure that the ARBPi file and the Turtlebot files or other dependencies are located in the same folder when running a script that requires their functions.

Ensure that the Raspberry Pi and ARB are connected via UART, as the scripts and sketches often communicate over this channel.


ARB and ARBPi

The ARB (Arduino Robotics Board) and ARBPi libraries are crucial for communication between the Arduino and Raspberry Pi. They handle low-level operations like reading and writing to registers that control motors, read sensors, and manage other peripherals.

ARB library

The ARB (Arduino Robotics Board) library runs in the Arduino Nano and is designed to simplify the interaction between the hardware components on the ARB and the software controlling it, in conjunction with a Raspberry Pi. This library is integral for controlling the motors, sensors, and serial communication in your robotics projects. For a more detailed explanation, check ARB Documentation.

Key Components of the ARB Library

Header File (ARB.h):

Source File (ARB.cpp):

getRegister and putRegister Functions in the ARB Library

The getRegister and putRegister functions are crucial components of the ARB library, allowing for efficient data communication between the Arduino and other devices, such as the Raspberry Pi. These functions manage data within an array named reg_array, which acts as a collection of registers used to store and retrieve data dynamically during runtime.

getRegister Function

The getRegister function is designed to access data from the reg_array. Here's how it works:

putRegister Function

The putRegister function allows writing data to a specific register in the reg_array. Here’s a detailed look:

Example Usage

Here’s a basic example of how the ARB library functions might be used in an Arduino sketch:

// C++
#include <ARB.h>

void setup() {
    ARBSetup(true); // Initialize with serial communication enabled
}

void loop() {
    // Example of setting a register value
    putRegister(0, 120); // Put 120 in register 0

    // Example of reading a register value
    char val = getRegister(0);

    // Use the infrared sensor connected to I2C bus 1
    setI2CBus(1);
}

Here is how you might use both getRegister and putRegister in a practical scenario:

// C++
void setup() {
    ARBSetup(); // Initialize ARB without serial communication
}

void loop() {
    // Setting a register value to store a motor speed setting
    putRegister(10, 50);  // Assume register 10 is designated for motor speed

    // Later in the loop, or in another function, you retrieve this motor speed
    char motorSpeed = getRegister(10);

    // Use the motor speed to control a motor
    analogWrite(MOTOR_PWMA, motorSpeed);  // Assuming MOTOR_PWMA controls a motor's speed
}

A demo usage of the ARB library for serial communication can also be found in examples/serialComms.ino.

Overview of Example Files in the ARB Examples Directory

Each example in the ARB library's "examples" directory demonstrates specific functionalities of the Arduino Robotics Board. Here is a brief overview of what each example illustrates:

  1. BLEPeripheral (BLEPeripheral.ino) This example showcases how to set up and use a Bluetooth Low Energy (BLE) peripheral with the Arduino. It is essential for projects that require wireless data transmission or remote control via BLE.

  2. I2CMux (I2CMux.ino) Demonstrates the use of an I2C multiplexer with the ARB. This is critical for projects where multiple I2C devices must share the same I2C bus without addressing conflicts.

  3. motorControl (motorControl.ino) Provides a basic example of how to control motors using the ARB. It includes setting up the motor drivers and controlling the speed and direction of DC motors, which is fundamental for any mobile robotics project.

  4. pushButton (pushButton.ino) Shows how to read the state of push buttons using the ARB. It is useful for projects that require user input or a simple interface for triggering actions.

  5. serialComms (serialComms.ino) This example is about setting up and using serial communication between the ARB and another device, like a Raspberry Pi or a computer. It covers sending and receiving data over serial, which is vital for debugging and complex communications.

  6. uSonic (uSonic.ino) Focuses on using ultrasonic sensors with the ARB to measure distances. This is particularly useful in robotics for obstacle avoidance, navigation, and environment mapping.

Detailed Explanation of Key Examples

Let's dive deeper into two specific examples: motorControl and uSonic.

motorControl.ino

This script initializes and controls two DC motors connected to the ARB. It handles setting the direction and speed of each motor through PWM signals, which are essential for driving the motors in forward or reverse directions.

Key Snippets:

// C++
void setup() {
    pinMode(MOTOR_PWMA, OUTPUT);  // Set motor A PWM pin as output
    pinMode(MOTOR_DIRA, OUTPUT);  // Set motor A direction pin as output
}

void loop() {
    analogWrite(MOTOR_PWMA, 128);  // Set speed for motor A
    digitalWrite(MOTOR_DIRA, HIGH); // Set direction for motor A
    delay(1000);                    // Run for 1 second
    digitalWrite(MOTOR_DIRA, LOW);  // Change direction
    delay(1000);                    // Run in the opposite direction for 1 second
}

uSonic.ino

This script demonstrates how to use an ultrasonic sensor connected to the ARB to measure distances. The script calculates the distance by timing how long it takes for an ultrasonic pulse to return to the sensor.

Key Snippets:

// C++
void setup() {
    pinMode(USONIC1, INPUT);  // Set the ultrasonic sensor pin as input
}

void loop() {
    long duration, distance;
    digitalWrite(USONIC1, LOW);
    delayMicroseconds(2);
    digitalWrite(USONIC1, HIGH);
    delayMicroseconds(10);
    digitalWrite(USONIC1, LOW);
    duration = pulseIn(USONIC1, HIGH);
    distance = duration / 29 / 2;  // Calculate distance
    Serial.print("Distance: ");
    Serial.println(distance);
    delay(1000);
}

ARBPi library

Purpose and Functionality:

The ARBPi library runs in the Raspberry Pi and provides serial communication between the Raspberry Pi and the Arduino boards. The library offers a dual-interface, supporting both C++ and Python, thereby accommodating a wide range of programming preferences and project requirements. For a more detailed explanation, check ARB Documentation.

Technical Stack and Integration:

C++ Components: Core functionalities are implemented in C++, ensuring high performance and direct access to low-level system resources.

Python Interface: Python bindings are provided to leverage the ease of scripting and rapid development capabilities of Python, making it ideal for higher-level applications and quick testing.

Key Components:

C++ Source Files (ARBPi.cpp and ARBPi.h):

Python Module (ARBPi.py): Wraps the C++ library using Python’s ctypes module, providing Pythonic access to the underlying serial communication functions.

Compiled Library (libARBPi.so): A shared library compiled from the C++ code, enabling dynamic linking from Python or other C++ programs.

Test Files (serialtest, serialTest.cpp, and serialTest.py): Executable and scripts for testing the functionality of the library to ensure proper operation of serial communications.

Libraries and Dependencies:

Setup and Usage Instructions:

Compiling C++ Code:

To compile the C++ part of the library, you would use g++ with appropriate flags to link against necessary libraries, such as wiringPi:

g++ -o ARBPi ARBPi.cpp -lwiringPi

Running Python Scripts:

Ensure Python is installed along with ctypes. The Python script can be run by importing it to your code as follows:

# Python
from ARBPi import *

Initialization Process:

C++ and Python interfaces include an initialization function to set up the serial connection:

// C++
void ARBPiSetup() {
    serialDevice = serialOpen(SERIAL, 115200);
}
# Python
def ARBPiSetup(serialPath="/dev/ttyUSB0"):
    _ARBPi.ARBPiSetup(ctypes.c_char_p(serialPath.encode('ascii')))

Reading and Writing Registers:

To read a register:

// C++
char getRegister(int reg) {
    serialPutchar(serialDevice, reg);
    while(serialDataAvail(serialDevice) < 1) {}
    return serialGetchar(serialDevice);
}
# Python
def getRegister(reg):
    return int(_ARBPi.getRegister(ctypes.c_int(reg)))

To write to a register:

// C++
void putRegister(int reg, char data) {
    serialPutchar(serialDevice, reg + 128);
    serialPutchar(serialDevice, data);
}
# Python
def putRegister(reg, data):
    _ARBPi.putRegister(ctypes.c_int(reg), ctypes.c_byte(data))

These snippets illustrate the direct interaction with hardware through serial interfaces, encapsulating complex operations into simple, reusable API calls.


Lab Sessions

Lab 1: Robot Kit Assembly and RPi Programming

Lab Session 1 focuses on two primary areas: assembling the basic robot chassis from the York Robotics Kit and introducing students to programming on the Raspberry Pi in both C++ and Python. Here’s a detailed breakdown of how the lab is structured and how the provided code files relate to the tasks.

Aims and Objectives:

Hardware and Software Setup:

Lab Tasks and Associated Code Files:

Task 1: Assemble the Chassis of Your Robot

Task 2: Wire Together Serial Communications and an LED Light

Task 3: Communicate with the Raspberry Pi

Task 5: Write a C Program to Blink the LED Using pigpio

Task 6: Blink the LED Using Python and the pigpiod Daemon

Lab 2: Embedded Navigational Sensing

Aims and Objectives

Lab 2 builds on the foundational skills developed in Lab 1, focusing on interfacing additional sensors for navigational tasks. The main goals are to add a display and distance measurement sensors to the Raspberry Pi, learn to read sensor data, display it, and communicate these readings to other devices.

Files and Tasks in Lab 2

Lab 2 contains several tasks and associated files organized into two main directories: task1 and task2.

Task 1: Connect and Test Communication

Task 2: Sensor Data Acquisition

Lab 3-4: PWM and Motor Control

Lab Sessions 3-4 focus on advanced motor control techniques using Pulse Width Modulation (PWM) and interfacing with H-bridge circuits to control motors using the Raspberry Pi. The sessions are structured to guide students through the practical aspects of motor control in robotics, including driving motors in different directions, controlling speed, and implementing braking.

Main Concepts Covered:

Tasks and Files in Lab 3-4

The lab is divided into several tasks, structured to sequentially build the students' skills in motor control:

Task 4: PWM and Basic Motor Control

Task 5: Advanced Motor Control and User Interaction

Lab 5: Wheel Odometry

Lab Session 5 is centered around the integration and utilization of wheel encoders to enhance the movement control of a robot. This lab introduces the students to the practical aspects of using encoder feedback to precisely control the distance and speed of a robot's motion.

Learning Outcomes:

Key Tasks and Associated Files

The lab is structured around several key tasks that guide students through the process of integrating and programming wheel encoders:

Task 1: Wire up the Wheel Encoders to the Raspberry Pi

Students are expected to connect the outputs from a quadrature encoder to the Raspberry Pi, using the knowledge they've gained about encoder operation and interfacing.

Task 2: Read in the Encoder Counts

Building upon the initial setup, this task involves programming the Raspberry Pi to read encoder signals and calculate movement parameters such as speed and distance.

Task 3: Motion Estimation Based on Odometry

This task requires students to estimate the robot's speed and distance covered using the encoder data. This involves programming to handle asynchronous data collection and real-time computation.

Lab 6: Robot Vision with OpenCV

Lab 6 focuses on integrating computer vision capabilities into a robotics platform using OpenCV and a Raspberry Pi camera module. This session is designed to familiarize students with the basics of image processing in a practical robotics context.

Aims and Objectives:

Key Files and Their Functions

  1. test_camera.py

    This script initializes the Raspberry Pi camera and captures video frames continuously. It uses OpenCV to display these frames in real time, allowing students to observe the camera's output directly on their screens.

    Code Overview:

    # Python
    import picamera
    import picamera.array
    import time
    import cv2
    
    camera = picamera.PiCamera()
    camera.rotation = 180
    camera.resolution = (640, 480)
    rawCapture = picamera.array.PiRGBArray(camera, size=camera.resolution)
    
    for frame in camera.capture_continuous(rawCapture, format="bgr", use_video_port=True):
       image = frame.array
       cv2.imshow("Frame", image)
       rawCapture.truncate(0)
       if cv2.waitKey(1) & 0xFF == ord('q'):
          break

    This script captures frames and displays them using cv2.imshow(). The loop continues until 'q' is pressed, demonstrating basic video capture and display functionality.

  2. mask.py

    Expands upon test_camera.py by applying a color mask to isolate specific colors in the video feed. This is useful for tasks like tracking colored objects or navigating using visual markers.

    Code Overview:

    # Python
    # Similar setup to test_camera.py
    # Additional OpenCV color transformation and masking
    hsv = cv2.cvtColor(image, cv2.COLOR_BGR2HSV)
    blueMin = (100, 150, 0)
    blueMax = (140, 255, 255)
    mask = cv2.inRange(hsv, blueMin, blueMax)
    cv2.imshow("Mask", mask)

    This script converts the camera feed to HSV color space and applies a mask to detect blue objects, demonstrating how to isolate parts of the image based on color.

  3. blob.py

    Focuses on identifying and marking blobs (large connected components) in the masked image. This can be used for detecting and analyzing specific shapes or objects in the visual field.

    Code Overview:

    # Python
    # Using the mask created in mask.py
    detector = cv2.SimpleBlobDetector_create()
    keypoints = detector.detect(mask)
    kp_image = cv2.drawKeypoints(mask, keypoints, None)
    cv2.imshow("Keypoints", kp_image)

    This script identifies blobs in the masked output and displays these detections, teaching students how to recognize and quantify features in images.

  4. aruco_test.py

    Introduces the detection of ArUco markers, which are square markers that can be easily recognized and used for various purposes, such as positional tracking and 3D positioning.

    Code Overview:

    # Python
    import cv2
    from cv2 import aruco
    
    # Setup camera
    # Initialize ArUco detection
    aruco_dict = aruco.Dictionary_get(aruco.DICT_6X6_250)
    parameters = aruco.DetectorParameters_create()
    corners, ids, rejected = aruco.detectMarkers(image, aruco_dict, parameters=parameters)
    image_with_markers = aruco.drawDetectedMarkers(image, corners, ids)
    cv2.imshow("ArUco Markers", image_with_markers)

    This script processes the video to detect and display ArUco markers, providing a practical application of marker-based navigation or interaction in robotics.

Lab 7: Robot Control with ROS

Overview: Lab 7 introduces students to the Robot Operating System (ROS), a powerful and widely-used open-source robotics middleware. This lab focuses on teaching students how to develop ROS-based applications using Python, specifically covering the creation and management of networked publishers and subscribers.

Aims and Objectives:

Contents and Tasks:

Task 1: Getting Started

Task 2: Running the Example System

Turtlesim: Utilize ROS's turtlesim package to understand topics, nodes, publishers, and subscribers. This involves running simulation nodes and nodes that capture key presses to control a simulated turtle.

Task 3: Examining the System

Task 4: Creating a Package

Task 5: Examining the Package

Task 6: Writing Some Code

Task 7: The Sender and Receiver

Task 8: Name Clashes

Lab 8: Robot Movement Control

Lab Session 8 in the MSc Practical Robotics and Year 4 Robotics module centers on developing advanced movement control capabilities for a robot. This lab leverages all the skills and tools acquired in previous labs to create a comprehensive movement control program.

Aims and Objectives:

Task Breakdown:

The Python scripts in Lab 8 for controlling the robot's movement make use of the TurtleBot class, a custom Python class designed to abstract and manage the robot's hardware interfaces like motors and sensors. The Turtlebot class must be used by other Python programs in the Raspberry Pi while the generalControl.ino runs on the Arduino. This Arduino code interfaces with all ARB sensors and actuators, act based on received serial data and send sensor data to serial registers to be read by the Pi.

Below, I'll outline code snippets from some of these tasks and explain how they utilize the TurtleBot class to execute specific movements.

Task 1: Create a Movement Control Program

Task 2: Set Up and Test Repeated Robot Motion

Task 3: Implement Obstacle Detection

Task 4: Error Data Collection & Analysis

Lab 9: Robot Navigation/Assessment Guidance

Lab Session 9 is the culmination of the robotics module, focusing on integrating various robotic components to achieve complex navigational tasks. This lab involves programming a robot to traverse an obstacle course autonomously, using an array of sensors and actuators developed in previous labs.

Key Details of Lab 9:

Aims and Objectives:

Pre-Lab Preparation:

Key Tasks and Python Scripts Overview:

Task 1: Localization

Task 2: Mapping

Task 3: Planning

Python Scripts Breakdown:

The solution for the task proposed in this lab can be found under the UCAS_showcase directory, explained below. Here are some snippets of some tests that can be found in the Lab 9 directory:

  1. obstacle_test.py

This script includes functions to test the robot's obstacle detection and avoidance capabilities. The robot uses its sensors to detect obstacles in its path and execute maneuvers to navigate around them without human intervention.

Code Snippet from obstacle_test.py:

# Python
from TurtleBot import TurtleBot
import math

def main():
   tb = TurtleBot(estop=False)
   tb.motors.move_continuous(20)
   tb.motors.rotate_continuous(math.pi)
   tb.motors.move_continuous(20)

if __name__ == '__main__':
   try:
      main()
   except KeyboardInterrupt:
      print('Interrupted!')

The script initializes a TurtleBot instance and commands it to move and rotate continuously, testing the integration of movement commands and sensor feedback in real-time.

  1. speed_conversion_new_test.py

This script is designed to test different speed settings and directions, potentially to calibrate or verify the speed control systems within the robot.

Code Snippet from speed_conversion_new_test.py:

# Python
from TurtleBot import TurtleBot
import time

def main():
   tb = TurtleBot()
   directions = ["forward", "backward", "left", "right"]
   
   for direction in directions:
      tb.motors.change_direction(direction)
      for speed_level in range(1, 10):
            tb.motors.reset_encoder("A")
            tb.motors.reset_encoder("B")

The script tests various movement directions and speed levels, resetting encoder readings between tests to measure the precise effect of each command on the robot's motion.


"Turtlebot" and "General Control" Classes

The Turtlebot class and the generalControl.ino sketch form a system for controlling the RPRK robotics platform, using the Raspberry Pi and Arduino Nano, respectively. High-level decision-making and processing are handled by the Raspberry Pi, while real-time hardware interactions are managed by the Arduino, combining the strengths of both platforms for effective robot control. The last version of these classes can be found in the UCAS_showcase/ directory.

The generalControl.ino reads all sensor data and forwards it through specified serial registers, while at the same time reading the data recieved through separate control registers and operating the actuators based on it. It thus, acts as a general control interface for the Arduino. The Turtlebot class uses serial communication to create a high-level abstraction of the RPRK robot's operation. It can be imported into any Python project in order to send commands to the ARB by the use of simple functions. These functions send the appropiate signal through the right serial channel in order for generalControl.ino to receive this signal and operate the robot's actuators and sensors in accordance with the command. Here's a detailed look at how these two components work together to manage robot operations:

Turtlebot.py (Raspberry Pi)

Turtlebot.py is a Python class designed to provide high-level abstraction and to interface through serial with the RPRK robot's hardware components, mostly controlled via an Arduino Nano running generalControl.ino. This class encapsulates methods for motor control, sensor data acquisition, and camera operations, allowing for command and control over the robot. It defines a comprehensive and modular class structure to manage various components of the RPRK robotic platform, and relies on several classes nested within it to handle specific subsystems of the robot.

Here's a detailed breakdown of the structure and functionalities within TurtleBot.py. Each of these subsystems interacts with the Arduino via a serial communication link, sending commands to control the hardware and receiving sensor data back from the Arduino:

Initialization and Configuration

To initialize the TurtleBot, you start by creating an instance of the class. During initialization, various components like motors, camera, infrared sensor, ultrasound sensor, and joystick are also initialized. Here is an example:

turtlebot = TurtleBot(estop=True)

This command initializes the TurtleBot with emergency stop (estop) functionality enabled, which can be used to halt the robot if it encounters a critical situation.

Helper Methods

Includes methods for reading data from registers in various formats (16-bit integers, fractional numbers), which are crucial for interpreting sensor data and controlling actuators based on feedback from the Arduino.

Motors Subclass

Controls the robot's motion including forward/backward movement and turning. It sends commands to the Arduino to adjust motor speeds and directions using PWM signals.

Methods

Camera Subclass

Manages video capture for vision tasks using the PiCamera library, processes images for navigation cues, and object or obstacle recognition using OpenCV.

Methods

Ultrasonic Subclass

Handles ultrasonic distance measurements, essential for obstacle avoidance strategies.

Methods

Joystick Subclass

If a joystick is used for manual control, this class interprets the joystick inputs.

Methods

InfraredSensor Subclass

Manages the infrared distance sensor data collection.

Methods

Example of Using TurtleBot

Here’s a simple example demonstrating how to use the TurtleBot to move forward, rotate, and then stop:

# Python
# Initialize the TurtleBot
turtlebot = TurtleBot(estop=True)

# Move forward by 100 centimeters
turtlebot.motors.move_step(100)

# Get infrared sensor reading
turtlebot.infrared.get_infrared_distance()

# Get left ultrasonic sensor reading
turtlebot.ultrasound.get_ultrasound_distance("left")

# Rotate by 90 degrees (π/2 radians)
turtlebot.motors.rotate_step(math.pi / 2)

# Stop the robot
turtlebot.motors.change_direction("stop")

This example illustrates basic movement commands that utilize the motor's subclass functions. The move_step and rotate_step functions use encoder feedback to adjust the robot’s movement accurately.

generalControl.ino (Arduino) Interface

The generalControl.ino sketch runs on the Arduino and acts as the low-level controller managing direct hardware interactions. This sketch is responsible for:

This sketch uses registers to manage data communication with the Raspberry Pi, which includes sending sensor readings back to the Pi and receiving motor control commands and other directives from the Pi.

The generalControl.ino file is structured to control various aspects of a robotics platform, specifically designed for the RPRK (Raspberry Pi Robotics Kit). It integrates multiple components such as infrared sensors, a joystick, motors, and ultrasonic sensors into a cohesive system, allowing for modular interaction and control of a robot. Here's a detailed breakdown of the code:

Includes and Global Object Declarations

The script begins by including header files for various modules:

It also includes ARB.h for the Arduino Robotics Board specific functions and Wire.h for I2C communication, essential for interfacing with certain sensors.

Objects for each of the components are instantiated globally:

Setup Function

The setup() function initializes the system:

Loop Function

The loop() function is where the continuous operation of the robot occurs:

Ultrasonics.cpp Module

The Ultrasonics.cpp file in the UCAS_showcase directory is one of the modules instantiated and used by generalControl.ino, as part of the system designed to handle ultrasonic sensors on the RPRK robot. The file includes both the definitions of how these sensors are initialized and read, as well as how their data is processed and stored. Here’s a detailed breakdown of the code:

Includes and Constructor

Public Methods

Private Members

Data Handling

Ultrasonic sensor data is being interfaced through the use of registers to send data (putRegister()) with the Raspberry Pi via a serial communication protocol, for decision-making processes and further data handling.

Motors.cpp Module

The Motors.cpp file is a comprehensive implementation for controlling and managing motors on the RPRK robotics platform, specifically for an Arduino-based setup. It includes functionalities for direct motor control, feedback handling via encoders, and communication with external controllers through registers. Here’s a detailed explanation of the key components of the code:

Public Methods

Includes and Constructor

Initializations

// C++
void Motors::initialize(){
   m_setPinModes();
   m_initializeComponents(); // Initializes values
   m_attachInterrupts(); // Attaches interrupts
   m_initializeSerialRegisters(); // Initialize serial registers
}

Motor Operation

// C++
void Motors::runMotors(){
   // Wheels
   m_readWheelDirections();
   m_readPWMSignals();

   // General movement
   m_readSpeedValue();
   m_readDirectionInput();

   // Encoders
   m_setAbsoluteEncoderSteps();
   m_calculateCurrentStepsA();
   m_calculateCurrentStepsB();
}

Private Methods

Run During Initialisation (initialize())

Motor Control Functions

Encoder and Distance Handling

Utility Functions

Interrupt Service Routines (ISRs)

Interaction Between Turtlebot.py and generalControl.ino

The interaction between Turtlebot.py and generalControl.ino is primarily through serial communication, facilitated by the Raspberry Pi’s UART interface and the Arduino’s serial ports. Here's how the process typically works:

  1. Command and Control:

  1. Data Feedback:

  1. Synchronization:

Example Communication

For example, if the Raspberry Pi wants the robot to move forward:

  1. The Pi’s TurtleBot class sends a speed and direction command through the serial line.

  2. The Arduino’s generalControl.ino receives this command, interprets it, and adjusts the motor controllers accordingly.

  3. Simultaneously, the Arduino might send back the status of encoders or other sensors, which the TurtleBot class uses to adjust its commands or process navigation algorithms.

This system architecture allows for sophisticated control schemes where high-level decision-making and processing are handled by the Raspberry Pi, while real-time hardware interactions are managed by the Arduino, combining the strengths of both platforms for effective robot control.

Examples and tests in UCAS_showcase

The UCAS_showcase directory contains two subdirectories that are tailored for various aspects of robotic control and testing:

GeneralControl Directory

This directory includes a collection of C++ files that are components of the robot's control system:

These files suggest a structured approach to managing different hardware components of the robot, with a primary control script (generalControl.ino) that ties all individual sensor and actuator controls together.

InitialTesting Directory

This directory contains various Python scripts focused on testing and demonstrating different functionalities: