docs(Code Cleanup): Cleaned Code and added comments, Updated Readme

This commit is contained in:
Devoalda 2023-11-29 11:44:12 +08:00
parent c0d7091b12
commit cb4b123a9a
5 changed files with 157 additions and 202 deletions

103
README.md
View File

@ -1,4 +1,5 @@
# freeRTOS-car
> Team 39
This project is a car that uses the [Raspberry Pi Pico](https://www.raspberrypi.org/products/raspberry-pi-pico/)
and [FreeRTOS](https://www.freertos.org/) to move around a maze.
@ -27,20 +28,36 @@ cp freeRTOS-car.uf2 /media/$USER/RPI-RP2
```
# Components
## Motors
Motor module consist of 4 components:
1. [motor_init](frtos/motor/motor_init.h): Initialises the pins and struct stated in [motor_config](frtos/config/motor_config.h) and [car_config](frtos/config/car_config.h), and the free rtos tasks related. Call `motor_init` followed by `motor_tasks_init` to initilise the parameters and define the tasks.
2. [motor_speed](frtos/motor/motor_speed.h): Monitors the speed of the motors by interrupt. Each **falling edge** of the wheel encoder will trigger the interrupt and the time elapsed since last trigger will be recorded and thus calculate the speed and distance travelled since boot. Typically, each interrupt will record one slot length of the distance travelled, calculated and defined in [motor_config](frtos/config/motor_config.h). Includes functions to adjust the duty cycle of the motor for speed control.
3. [motor_pid](frtos/motor/motor_pid.h): PID function to match the one motor duty cycle to the other motor such that the car can move straight, with 50ms interval, by comparing the difference in distance travelled by each wheel.
4. [motor_direction](frtos/motor/motor_direction.h): Sets and changes the direction of the motor to control the car using bit masks. Includes functions that work with the magnetometer to turn the car to/by specific yaw.
1. [motor_init](frtos/motor/motor_init.h): Initialises the pins and struct stated
in [motor_config](frtos/config/motor_config.h) and [car_config](frtos/config/car_config.h), and the free rtos tasks
related. Call `motor_init` followed by `motor_tasks_init` to initilise the parameters and define the tasks.
2. [motor_speed](frtos/motor/motor_speed.h): Monitors the speed of the motors by interrupt. Each **falling edge** of the
wheel encoder will trigger the interrupt and the time elapsed since last trigger will be recorded and thus calculate
the speed and distance travelled since boot. Typically, each interrupt will record one slot length of the distance
travelled, calculated and defined in [motor_config](frtos/config/motor_config.h). Includes functions to adjust the
duty cycle of the motor for speed control.
3. [motor_pid](frtos/motor/motor_pid.h): PID function to match the one motor duty cycle to the other motor such that the
car can move straight, with 50ms interval, by comparing the difference in distance travelled by each wheel.
4. [motor_direction](frtos/motor/motor_direction.h): Sets and changes the direction of the motor to control the car
using bit masks. Includes functions that work with the magnetometer to turn the car to/by specific yaw.
## Ultrasonic Sensor
1. Ultrasonic sensor package is in `frtos/ultrasonic_sensor`, and its configuration is in `frtos/config/ultrasonic_sensor_config.h`. It contains the drivers and FreeRTOS tasks to output and read the ultrasonic sensor data.
2. [ultrasonic_init](frtos/ultrasonic_sensor/ultrasonic_init.h): Initialises the pins and struct stated in [ultrasonic_sensor_config](frtos/config/ultrasonic_sensor_config.h) and [car_config](frtos/config/car_config.h), and the free rtos tasks related. Call `ultrasonic_init` followed by `ultrasonic_tasks_init` to start.
1. Ultrasonic sensor package is in `frtos/ultrasonic_sensor`, and its configuration is
in `frtos/config/ultrasonic_sensor_config.h`. It contains the drivers and FreeRTOS tasks to output and read the
ultrasonic sensor data.
3. The function check_obstacle() updates one of the parameter in the car's obstruction struct (s_obs_struct) in [car_config](frtos/config/car_config.h) to tell the car's whether it detects an obstruction .
2. [ultrasonic_init](frtos/ultrasonic_sensor/ultrasonic_init.h): Initialises the pins and struct stated
in [ultrasonic_sensor_config](frtos/config/ultrasonic_sensor_config.h) and [car_config](frtos/config/car_config.h),
and the free rtos tasks related. Call `ultrasonic_init` followed by `ultrasonic_tasks_init` to start.
3. The function check_obstacle() updates one of the parameter in the car's obstruction struct (s_obs_struct)
in [car_config](frtos/config/car_config.h) to tell the car's whether it detects an obstruction .
## Line Sensor
@ -49,9 +66,10 @@ contains the drivers and FreeRTOS tasks to read the line sensor data and update
## Magnetometer
The magnetometer used is the [LSM303DLHC](https://www.st.com/resource/en/datasheet/lsm303dlhc.pdf) from STMicroelectronics.
The magnetometer used is the [LSM303DLHC](https://www.st.com/resource/en/datasheet/lsm303dlhc.pdf) from
STMicroelectronics.
Magnetometer package is in `frtos/magnetometer`, and its configuration is in `frtos/config/magnetometer_config.h`. It
Magnetometer package is in `frtos/magnetometer`, and its configuration is in `frtos/config/magnetometer_config.h`. It
contains the drivers and FreeRTOS tasks to read the magnetometer data.
All the magnetometer data (roll, pitch, yaw) calculated is stored in the `direction_t` struct, which is defined in
@ -59,8 +77,9 @@ All the magnetometer data (roll, pitch, yaw) calculated is stored in the `direct
### Filtering
The magnetometer initially used a complementary filter (with the accelerometer) to calculate the Yaw, and the temperature,
sensor was used to perform an offset correction. But raw data was accurate enough to use it directly.
The magnetometer initially used a complementary filter (with the accelerometer) to calculate the Yaw, and the
temperature,
sensor was used to perform an offset correction. But raw data was accurate enough to use it directly.
An initial calibration method for the magnetometer was implemented, with the use of 100 initial samples, and then
a bias calculation. This method was not used in the final version, because the raw data was accurate enough.
@ -68,38 +87,76 @@ a bias calculation. This method was not used in the final version, because the r
The final version of the magnetometer uses a **moving average filter** to smooth the data and a bias of 0 degrees.
## Barcode (Line) Sensor
The barcode sensor uses edge interrupts to trigger the barcode sensor when the sensor hits a black line, which then measures the width of the black line to white, and stores it in an array. The Code39 barcode library is used as a reference for the barcode decoding function.
The barcode sensor uses edge interrupts to trigger the barcode sensor when the sensor hits a black line, which then
measures the width of the black line to white, and stores it in an array. The Code39 barcode library is used as a
reference for the barcode decoding function.
## WiFi (Web Server) Module
The WiFi (Web Server) Module within this project integrates Server-Side Includes (SSI) and Common Gateway Interface (CGI) handlers from the lwIP library, facilitating a web interface to display information and receive controls from a webpage.
The WiFi (Web Server) Module within this project integrates Server-Side Includes (SSI) and Common Gateway Interface (
CGI) handlers from the lwIP library, facilitating a web interface to display information and receive controls from a
webpage.
### Components Overview
1. **[frontend.h](frtos/frontend/frontend.h):** This component initializes and manages the web server frontend. It establishes the initial connection to the WiFi network using environment variables such as WIFI_SSID and WIFI_PASSWORD.
1. **[frontend.h](frtos/frontend/frontend.h):** This component initializes and manages the web server frontend. It
establishes the initial connection to the WiFi network using environment variables such as WIFI_SSID and
WIFI_PASSWORD.
2. **[html_files](frtos/frontend/html_files):** This directory contains HTML files used for the web server display. These files are linked into lwIP to enable server-side processing and rendering.
2. **[html_files](frtos/frontend/html_files):** This directory contains HTML files used for the web server display.
These files are linked into lwIP to enable server-side processing and rendering.
3. **[ssi.h](frtos/frontend/ssi.h):** Handles Server-Side Includes (SSI), which dynamically inserts content into web pages, allowing the display of real-time or changing information.
3. **[ssi.h](frtos/frontend/ssi.h):** Handles Server-Side Includes (SSI), which dynamically inserts content into web
pages, allowing the display of real-time or changing information.
4. **[cgi.h](frtos/frontend/cgi.h):** Manages Common Gateway Interface (CGI) handlers, enabling the reception of controls and user interactions from the web interface.
4. **[cgi.h](frtos/frontend/cgi.h):** Manages Common Gateway Interface (CGI) handlers, enabling the reception of
controls and user interactions from the web interface.
5. **makefsdata Utility:** This tool generates `htmldata.c` by converting HTML files into hexadecimal representation to link them into lwIP. It involves converting filenames into hex, defining HTTP headers for file extensions, and converting HTML content into a hex array for efficient storage and retrieval.
5. **makefsdata Utility:** This tool generates `htmldata.c` by converting HTML files into hexadecimal representation to
link them into lwIP. It involves converting filenames into hex, defining HTTP headers for file extensions, and
converting HTML content into a hex array for efficient storage and retrieval.
- **Automatic Generation of htmldata.c:**
- `makefsdata.c` creates `makefsdata.exe` automatically upon build, as specified in `CMakeLists.txt`.
- `makefsdata.exe` in turn generates `htmldata.c`, which links the HTML pages to lwIP for server-side processing, enabling seamless integration of web content.
- `makefsdata.exe` in turn generates `htmldata.c`, which links the HTML pages to lwIP for server-side
processing, enabling seamless integration of web content.
### Functionality and Implementation Details
The WiFi (Web Server) Module offers the following functionalities:
- **Dynamic Content Display:** SSI allows the server to include dynamic content in web pages, facilitating real-time updates or information display.
- **Dynamic Content Display:** SSI allows the server to include dynamic content in web pages, facilitating real-time
updates or information display.
- **User Interaction Handling:** CGI enables the server to process user interactions received from the web interface, enabling control and interaction with the Pico-based car.
- **User Interaction Handling:** CGI enables the server to process user interactions received from the web interface,
enabling control and interaction with the Pico-based car.
- **WiFi Connectivity:** `frontend.h` establishes a connection to the designated WiFi network using the environment variables WIFI_SSID and WIFI_PASSWORD. This connection is essential for enabling communication between the Pico device and the network.
- **WiFi Connectivity:** `frontend.h` establishes a connection to the designated WiFi network using the environment
variables WIFI_SSID and WIFI_PASSWORD. This connection is essential for enabling communication between the Pico device
and the network.
The integration of SSI, CGI, and the makefsdata tool empowers the WiFi (Web Server) Module to provide a user-friendly
interface for monitoring and controlling the Pico-based car within the defined network environment.
The integration of SSI, CGI, and the makefsdata tool empowers the WiFi (Web Server) Module to provide a user-friendly interface for monitoring and controlling the Pico-based car within the defined network environment.
## Mapping
The mapping module is in `frtos/map`, and its configuration is in `frtos/config/car_config.h`. It contains the drivers
and FreeRTOS tasks to map the maze.
### Data Structures and Algorithms used
Mapping is done primarily using a 2D array of `map_cell_t` structs, which is defined in `frtos/config/car_config.h`.
Each cell in the array represents a cell in the maze, and contains information about the cell's walls, whether it has
been visited, and the distance from the start cell. The array is updated as the car moves through the maze. Flood filling
is used to find reachable cells from the current cell.
Once the maze has been mapped, the simulation will bring the car back to the start cell, and the shortest path to the
end cell will be calculated using Breadth First Search (BFS).
Finally, the car will follow the shortest path to the end cell.
### Ideal Scenario
The ideal scenario will happen when the car utilises its sensors and mapping algorithm to map the maze and find the
shortest path to the end cell. The car will then follow the shortest path to the end cell.

View File

@ -2,23 +2,6 @@
#include "magnetometer_init.h"
#include "magnetometer_direction.h"
#define DIRECTION_TASK_PRIORITY (tskIDLE_PRIORITY + 1UL)
void
launch()
{
TaskHandle_t h_monitor_direction_task = NULL;
xTaskCreate(monitor_direction_task,
"Monitor Direction Task",
configMINIMAL_STACK_SIZE,
NULL,
DIRECTION_TASK_PRIORITY,
&h_monitor_direction_task);
vTaskStartScheduler();
}
int
main(void)
{

View File

@ -1,147 +0,0 @@
//
// Created by junwei on 31/10/23.
//
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#ifndef TEST_PROJECT_MAP_H
#define TEST_PROJECT_MAP_H
// Define the grid structure
typedef struct
{
bool **data; // 2D array to represent the grid
int rows; // Number of rows in the grid
int cols; // Number of columns in the grid
} Grid;
// Global grid to track the car's path
Grid *car_path_grid;
// Function to create and initialize a grid
Grid *
create_grid(int rows, int cols)
{
Grid *grid = (Grid *)malloc(sizeof(Grid));
grid->rows = rows;
grid->cols = cols;
// Allocate memory for the 2D array
grid->data = (bool **)malloc(rows * sizeof(bool *));
for (int i = 0; i < rows; i++)
{
grid->data[i] = (bool *)malloc(cols * sizeof(bool));
for (int j = 0; j < cols; j++)
{
grid->data[i][j] = false; // Initialize to 'false' (unvisited)
}
}
return grid;
}
// Function to mark a cell as visited
void
mark_cell(Grid *grid, int row, int col)
{
if (row >= 0 && row < grid->rows && col >= 0 && col < grid->cols)
{
grid->data[row][col] = true;
}
}
// Function to check if a cell has been visited
bool
is_cell_visited(Grid *grid, int row, int col)
{
if (row >= 0 && row < grid->rows && col >= 0 && col < grid->cols)
{
return grid->data[row][col];
}
return false; // Consider out-of-bounds as unvisited
}
// Function to destroy the grid and free memory
void
destroy_grid(Grid *grid)
{
for (int i = 0; i < grid->rows; i++)
{
free(grid->data[i]);
}
free(grid->data);
free(grid);
}
// Function to update the map based on car's current orientation
// Function to update the map based on car's current orientation and position
void
update_map(int orientation, int cur_x, int cur_y)
{
// Define offsets for different orientations
int offset_x = 0;
int offset_y = 0;
switch (orientation)
{
case NORTH:
offset_y = 1;
break;
case EAST:
offset_x = 1;
break;
case SOUTH:
offset_y = -1;
break;
case WEST:
offset_x = -1;
break;
case NORTH_EAST:
offset_x = 1;
offset_y = 1;
break;
case SOUTH_EAST:
offset_x = 1;
offset_y = -1;
break;
case SOUTH_WEST:
offset_x = -1;
offset_y = -1;
break;
case NORTH_WEST:
offset_x = -1;
offset_y = 1;
break;
}
// Update the map based on the car's current position and orientation
mark_cell(car_path_grid, cur_x, cur_y);
mark_cell(car_path_grid, cur_x + offset_x, cur_y + offset_y);
}
// Function to print the map
void
print_map()
{
// Invert the map, 0,0 is at the Middle
// Print 1 for visited cells and 0 for unvisited cells
for (int i = car_path_grid->rows - 1; i >= 0; i--)
{
for (int j = 0; j < car_path_grid->cols; j++)
{
(car_path_grid->data[j][i]) ? printf("1 ") : printf("0 ");
// case false:
// printf("0 ");
// break;
// case true:
// printf("1 ");
// break;
// }
}
printf("\n");
}
}
#endif // TEST_PROJECT_MAP_H

View File

@ -1,4 +1,16 @@
/**
* @file map_test.c
* @brief This file contains the functions to test the mapping
* of the car
* @author Woon Jun Wei 2200624
*
* @details This file is a "Test Case" to simulate the algorithms used for
* mapping, and to test the mapping of the car. The Raspberry Pico
* will be flashed with the built binary of this file and need not
* be attached to the car.
*/
#include "mapping.h"
#include "car_config.h"
@ -6,7 +18,7 @@ int
main(void)
{
stdio_usb_init();
maze_t maze;
maze_t maze;
sleep_ms(3000);

View File

@ -1,11 +1,31 @@
/**
* @file mapping.h
* @brief Map the environment using the line sensor and the ultrasonic sensor
* @author Woon Jun Wei 2200624 (Team 39)
* @author Wang Rongqi Richie 2201942 (Team 39)
* @author Poon Xiang Yuan 2200559 (Team 39)
* @author Benjamin Loh Choon How 2201590 (Team 78)
* @author Low Hong Sheng Jovian 2203654 (Team 78)
* @brief Simulated Mapping of the Maze
*
* @details This file contains the functions to simulate the mapping of the
* maze. Maze is created with hardcoded walls, obstacles, and the goal.
*
* Maze is then mapped by simulating the car's movement and performing
* floodfill to mark the reachable cells.
*
* The car will backtrack to the start once the entire maze is
* explored.
*
* The shortest path from start to goal is then found using BFS.
*
* BFS is also used to demonstrate the car's movement from start to
* goal.
*
* A Queue Data Structure is used to perform BFS.
*
* Reference:
* https://stackoverflow.com/questions/37207022/flood-fill-algorithm-maze
*
* @author Woon Jun Wei
*/
#ifndef MAPPING_H
@ -33,13 +53,18 @@ generate_random(int min, int max)
return num;
}
// Define a queue structure for BFS
/**
* Queue Node Structure
*/
typedef struct
{
int x;
int y;
} QueueNode;
/**
* Queue Structure
*/
typedef struct
{
QueueNode *array;
@ -47,7 +72,11 @@ typedef struct
unsigned capacity;
} Queue;
// Function to create a new queue
/**
* Queue Creation
* @param capacity
* @return
*/
Queue *
createQueue(unsigned capacity)
{
@ -59,21 +88,34 @@ createQueue(unsigned capacity)
return queue;
}
// Function to check if the queue is empty
/**
* @brief Check if the queue is empty
* @param queue
* @return true if the queue is empty, false otherwise
*/
bool
isEmpty(Queue *queue)
{
return (queue->size == 0);
}
// Function to check if the queue is full
/**
* @brief Check if the queue is full
* @param queue
* @return true if the queue is full, false otherwise
*/
bool
isFull(Queue *queue)
{
return (queue->size == queue->capacity);
}
// Function to enqueue a cell in the queue
/**
* @brief Enqueue a cell to the queue
* @param queue
* @param x
* @param y
*/
void
enqueue(Queue *queue, int x, int y)
{
@ -85,7 +127,11 @@ enqueue(Queue *queue, int x, int y)
queue->size = queue->size + 1;
}
// Function to dequeue a cell from the queue
/**
* @brief Dequeue a cell from the queue
* @param queue
* @return
*/
QueueNode
dequeue(Queue *queue)
{
@ -95,7 +141,12 @@ dequeue(Queue *queue)
return cell;
}
// Function to perform BFS and find the shortest path
/**
* @brief BFS to find the shortest path from start to goal
* @param maze pointer to the maze
* @param startX starting position x-coordinate
* @param startY starting position y-coordinate
*/
void
bfs_shortest_path(maze_t *maze, int startX, int startY)
{
@ -128,9 +179,6 @@ bfs_shortest_path(maze_t *maze, int startX, int startY)
int x = current.x;
int y = current.y;
// Process the cell (you can customize this part based on your needs)
// Here, we mark the cell with a special character to indicate it's part
// of the shortest path
maze->mazecells[y][x].type = 'P'; // 'P' for path
// Explore adjacent cells
@ -372,8 +420,10 @@ maze_explored(const maze_t *maze)
return true;
}
// Update the find_shortest_path function with the newly created
// bfs_shortest_path function
/**
* @brief Function to find the shortest path from start to goal
* @param maze
*/
void
find_shortest_path(maze_t *maze)
{