Difference between revisions of "S19: Lightfury"

From Embedded Systems Learning Academy
Jump to: navigation, search
(Software Design)
(Software Design)
Line 498: Line 498:
  
 
=== Software Design ===
 
=== Software Design ===
'''Bearing distance calculation'''
+
'''Bearing distance calculation''':
 
Bearing distance is the shortest distance from point A to point B on the great-cicle of the Earth. We have used Haversine Distance formula for the same
 
Bearing distance is the shortest distance from point A to point B on the great-cicle of the Earth. We have used Haversine Distance formula for the same
  
'''Bearing Angle Calculation'''
+
'''Bearing Angle Calculation''':
 
Bearing angle is the angle representing the desired navigation of the object with respect to the north in clockwise direction. The bearing angle is used to calculate the relative angle between two points on the map. In our case we used this to calculate the turning angle which tells the car how much to turn by and which direction.
 
Bearing angle is the angle representing the desired navigation of the object with respect to the north in clockwise direction. The bearing angle is used to calculate the relative angle between two points on the map. In our case we used this to calculate the turning angle which tells the car how much to turn by and which direction.
  
'''Route Planning'''
+
'''Route Planning''':
 
We have designed a simple algorithm takes in source and destination as a input parameter. Also we have maintained a pool of checkpoints which avoids the car to approach inaccessible locations. The algorithm calculates midpoint of the source and destination and calculates the nearest checkpoint to it. Later this checkpoint will be used as a source to calculate midpoint and searched for the nearest checkpoint.
 
We have designed a simple algorithm takes in source and destination as a input parameter. Also we have maintained a pool of checkpoints which avoids the car to approach inaccessible locations. The algorithm calculates midpoint of the source and destination and calculates the nearest checkpoint to it. Later this checkpoint will be used as a source to calculate midpoint and searched for the nearest checkpoint.
 +
 +
 +
 +
<center>
 +
<table>
 +
<tr>
 +
<td>
 +
<li style="display: inline-block;"> [[File:GPS /Block.jpg|600px|thumb|Sensor Hardware Interface]] </li>
 +
</td>
 +
</tr>
 +
</table>
 +
</center>
  
 
=== Technical Challenges ===
 
=== Technical Challenges ===

Revision as of 10:50, 23 May 2019

LightFury

Ultrasonic and Geo Sensor Based Self-Navigating Autonomous Car using CAN communication bus.

Abstract

LightFury is an autonomous electric car project that aims to bring different embedded system paradigms together and consolidate them with industry level sophistication and robustness. This project will feature an RC car which will employ different sensors and motors to navigate the track without human assistance. Every sensor and motor combined with a dedicated functionality is managed and processed by a controller. Such different controllers will communicate with the master node using the CAN bus protocol. Real time interaction with the car for communicating destination and getting car updates is possible with bridge controller and mobile application. The autonomous car navigation is a result of all electronic module functioning harmoniously to reach the destination location.

The navigation is based on destination position and car position. The autonomous car navigates with the help of GPS and compass along the checkpoints. Also, upon detecting obstacle, the car effectively navigates away from obstacle coming into its path. The motor controller effectively controls speed at turning and on ramp. Using the communication bridge and on board LED indicators we can have interpretation of the controller decisions. Also, the CAN bus communication can be used to observe the messages and sensor output on GUI or graphs. Thus we can observe the navigation decisions taken by the autonomous car.

Introduction

The project is divided into 7 modules:

  • Master Controller
  • Motor Controller
  • Ultrasonic Sensor Controller
  • GPS Controller
  • Android application and Bluetooth Connectivity
  • Hardware (PCB designing and Electronic layout)
  • Testing and Verification

The system has five SJOne Boards that run FreeRTOS and communicate with CAN bus. The car uses low power source for Boards and Sensory Units and high power source for Motor Driving Unit. The LEDs on each board are used to indicate status of controllers. The system is mounted and arranged on Traxis chassis. The final autonomous car is functional and compact unit.

Team Members & Responsibilities

<Team Picture>

Project Link: Gitlab Link


Schedule

Week# Start Date Task Status Completion Date
1 02/12/2019
  • Form Teams and decide group name. Also look up past projects and learn about the autonomous car design.
Completed 02/12/2019
2 02/19/2019
  • Setup Gitlab
  • Order CAN Transceivers. Study CAN communication.
  • Commit and raise merge request by each member to get hold over Gitlab basics
Completed 02/19/2019
3 02/26/2019
  • Setup Gitlab master branch for Project Light Fury. Create and merge branches for development tracking.
Completed 02/26/2019
4 03/05/2019
  • Read previous projects, gather information and discuss among the group members.
  • Distribute modules to each team member.
  • Divide the applications in different module for independent development.
  • Identify the baseline application.
Completed 03/09/2019
5 03/12/2019
  • Identify components required for the project
  • Allocated budget for the project
  • Order Components
Completed 03/19/2019
5 03/19/2019
  • Sensor: Perused the datasheet to get started with development
  • GPS: Went through the datasheet and circuitry details for GPS module(no.)
  • Compass & LCD: Read the respective datasheets and manuals
  • Motor: Getting hold of the specification and the user manuals
  • Android: Design the basic template of the Application
  • BLE: Thorough understanding of the module
Completed 03/26/2019
6 03/26/2019
  • Sensor: Successful interfaced ultrasonic with LPC to get raw data
  • GPS & Compass: Acquire data from GPS and Compass
  • Motor: Basic motor controlled vehicle orientation
  • Android: Interfacing with other modules
  • Unit-testing for each module
Completed 04/02/2019
7 04/02/2019
  • ----SPRING BREAK-----
Completed 04/09/2019
8 04/09/2019
  • Sensor: Parsed the raw data to achieve useful data
  • GPS & Compass: Parsing of raw data to get meaningful values
  • Motor: Take motor feedback through encoder and speed control on ramp
  • Android: Basic Android app
  • BLE: Bridge to receive Driver Heartbeat
Completed 04/16/2019
9 04/16/2019
  • Sensor: Design mounts and stabilize sensor input
  • GPS & Compass: Acquire GPS coordinate after GPS lock, Compass calliberation
  • Motor: Speed control and angle control precision testing
  • Android: Develop User Interface for data display
  • BLE: Interfacing bridge to Android app
  • PCB designing
Completed 04/23/2019
10 04/23/2019
  • Sensor: Analysis for jitters in sensor value
  • Obstacle avoidance logic on Master Controller
  • GPS & Compass: Range and bearing calculation
  • Motor: Implemented LCD to display motor parameters
  • Android: Adding UI for destination coordinates
  • BLE: Send checkpoints to GeoSensors
  • Master: Testing Sensor Obstacle Distance Limits
  • PCB Designing
Completed 04/30/2019
10 04/23/2019
  • Add Geo Navigation logic on Master Controller
  • Integration testing with obstacle avoidance
  • Order designed PCB
Completed 04/30/2019
11 04/30/2019
  • Outdoor testing and GPS navigation
Completed 05/07/2019
12 05/07/2019
  • Outdoor testing and Checkpoints tracking
Completed 05/14/2019
12 05/22/2019
  • ----DEMO DAY----
Completed 05/22/2019

Parts List & Cost

CMPE 243 SP19 LF Traxxis.png
Item# Part Desciption Vendor Qty Cost
1 RC Car Traxxas 1 From Prof. KaiKai Liu
2 CAN Transceivers MCP2551-I/P Microchip 15 Free Samples
3 Semtec GPS Microchip 1 Free Samples
4 Tilt Compensated Magnetic Compass Amazon 1 $29
5 LIPO Batteries + Charger 1 with car package
6 7" LCD 1
7 RPM 6520 Traxxas Amazon 1 $11.67
8 UltraSonic Sensor Maxbotix 4 $150
9 PCB PCBWay 1 $40.00 (estimated)
10 SJOne board 5 From Preet

Printed Circuit Board

Initial prototyping was done on wire wrapping board for a common CAN bus and power input to all the controllers. Over time on finalizing the layout and components, we designed a PCB to have a compact and stable connections for our electronic and mechanical components. Planned a single PCB to place and route CAN transceivers and eliminate dangling wires. The PCB was designed with Eagle CAD software tool. Components were placed on the design after careful consideration for compactness and routing constraints. The design was modified multiple time to cater for new requirement. Finally, the designed PCB was placed on the chassis for stable and compact car design.

PCB Schematic
PCB Layout



CAN Communication

Controlled Area Network or CAN is broadcast bus used in modern autonomous car systems for reliably communicating between devices. Here we use CAN bus to communicate between different controllers and debug with CAN messages. An errorneous node goes in bus off mode and other node keep communicating over CAN bus. This is why CAN is preferred over other communication protocols. Using PCAN dongle we can debug CAN communication on the bus in real time. These messages have helped in developing the navigation algorithm after observing the system in real time and monitoring CAN communication channel.

The CAN Bus physical design and communication is described in this section. The CAN controller present over SJOne board communicates to external transceiver over Rx and Tx. CAN transceiver transmit the message to CAN bus using differential signals. 0 is the dominant bit. This means that message with lower CAN message ID wins the bus arbitration and transmits its message on the bus. The other transceiver stops transmitting and waits for the next clock cycle to begin arbitration. Hence CAN message ID also acts as priority indicator. This arrangement is terminated with 2 terminal resistors of 120 Ohm. This removes signal reflection from the node end for combating echo from the signal. Due to differential means of transmitting the signal, the CAN bus is immune to noise loss and interference. All transceivers receive the CAN message. Only the intended terminal decodes the message. In case the message is not received by the terminal it goes into MIA state and consequent action can be decided by the user. This makes CAN convenient to be used in any applications.

The CAN follows certain data formatting method known as DBC. With the help of CAN transceivers, each sensor module sends data in DBC format to the controller. The data from ultrasonic sensor helps in obstacle detection. The GPS and Compass Module helps with navigation. The LCD gives live information of component status and values. Finally there is motors and control unit for navigating the car as per the commands from controller. All this controllers share information over CAN bus.

The CAN DBC file is unique format for information storage into structure and recording sender and receiver of the CAN network. It include the different message IDs along with message format and scale offset operations if any. Also there can be debugging node which keeps note of all the node data and can be used to observe the CAN communication. The DBC file comes handy while observing CAN operations in action with the help of Peak CAN. This became really helpful while observing sensor values in graph to detect false triggering.

PeakCAN dongle
Can DB9 connections
CAN Hardware

DBC File

Git Link to DBC file



Sensor ECU

Parallax Ultrasonic Sensor

The sensor ECU is consist of SJOne board interfaced with four Parallax ping ultrasonic sensors. The primary objective of sensor ECU is to detect the obstacles and provide the corresponding information to the master controller in order to avoid those obstacles. According to beam angles, each sensor is mounted in such a way that the car can avoid the obstacles present in front and rear of the car. Based on the acquired information from sensors, distance is calculated and forwarded to the master controller over CAN bus. Based on the previous project reports, Parallax ping sensors were decided for this project as they provided reliable outputs with better range.

Parallax ping

The Parallax ping sensor works on 5V supply voltage. It provides precise distance measurement ranging from about 2 cm to 3 meters. Beyond the mentioned range, the measurement provided by the sensor is not accurate. The sensor operates at 40 kHz. Blinking of LED provided on the sensor depends on triggering frequency. It has only one pin called "Signal" pin for triggering and listening to the echo pulse, which reduces hardware complexity. The distance from the obstacle is calculated by measuring the width of echo pulse and multiplying it with a constant (speed of sound in air). Also, there are some scenarios under which these sensors won't give proper readings such as:

  • Object is too small to reflect enough sound back to the sensor
  • Obstacle with the reflective surface will reflect sound at a shallow angle ( < 45 degrees), which won't be reflected back towards the sensor
  • The sound pulse gets reflected off the floor when the sensor is mounted low on the device


  • Distance greater than 3 m
  • Shallow angle ( < 45 degrees) reflection
  • Unable to detect small object
  • Hardware Design

    Four ultrasonic sensors are used to detect obstacle on left, front, right and rear of the car. The sensor has 124 inches (3.1m) detection range for an obstacle in line of sight. All ultrasonic sensors are mounted upright with an upward tilt to avoid ground reflection. The sensors have a minimum overlap of detection area and have a blind spot too close to the car. All the sensors are interfaced with SJOne board on port 2. Four GPIO pins are used for each sensor and external interrupts are enabled for those pins. The measured distance is transmitted over CAN bus using CAN transceiver (MCP 2551).

    Hardware Interface

    1. Pin 2.1 of SJOne board is configured as GPIO and is connected to the signal pin (SIG) of the left sensor. External interrupt for rising and falling edge is enabled to calculate the distance from an obstacle if any.
    2. Pin 2.2 of SJOne board is configured as GPIO and is connected to the signal pin (SIG) of the front sensor. External interrupt for rising and falling edge is enabled to calculate the distance from an obstacle if any.
    3. Pin 2.3 of SJOne board is configured as GPIO and is connected to the signal pin (SIG) of the right sensor. External interrupt for rising and falling edge is enabled to calculate the distance from an obstacle if any.
    4. Pin 2.4 of SJOne board is configured as GPIO and is connected to the signal pin (SIG) of the rear sensor. External interrupt for rising and falling edge is enabled to calculate the distance from an obstacle if any.
    5. Pin 0.0 of SJOne board is configured as RD1 and is connected to RXD pin (Pin 4) of MCP 2551 (can transceiver).
    6. Pin 0.1 of SJOne board is configured as TD1 and is connected to TXD pin (Pin 1) of MCP 2551 (can transceiver).


  • Sensor Hardware Interface
  • Software Design

    Sensor_ECU_SW_flowchart

    Sensor triggering is implemented in the 100Hz periodic task. Sensors are triggered in sets instead of all the sensors triggering at the same time. This technique helped in minimizing signal interference between two adjoining sensors. The front and back sensors are triggered first and then the left and right sensors. Each sensor is fed with a 5us high pulse from the host controller and it emits a short ultrasonic burst and then starts listening for the echo. After sending out the pulse, the SIG pin becomes high and it goes low when the obstacle is detected. To sense this pulse, external interrupts are enabled. The maximum duration of this pulse is 18.5ms which denotes that there is no obstacle in front of the sensor. Given this time period, left and right sensors are triggered 20ms after front and back sensors are triggered. Each sensor is triggered at 20Hz, i.e., after 50ms.

    After collecting the data from sensors, distance is calculated and it is transmitted over CAN bus. CAN transmission also takes place 100Hz task only so that updated values are sent at the faster speed. A heartbeat message is sent to the master controller indicating that the sensor controller is up and running. This message is sent using 10Hz periodic task.

    Implementation

    1. Initialize the CAN bus either on can1 or can2 with baud rate of 100 kbps and RX/TX queues of size 100
    2. Configure the host controller pins 2.1, 2.2, 2.3 and 2.4 as GPIO pins (These pins are connected to SIG pin of left, front, right and rear sensor respectively)
    3. Enable the external interrupts for corresponding pins to detect rising and falling edge of the input pulse
    4. Set the micro-controller pin connected to SIG pin as an output
    5. Triggering the sensors:
      1. Send low signal from the controller to SIG pin (for a clean high pulse)
      2. Insert delay of 2us
      3. Send high signal from the controller to SIG pin
      4. Insert delay of 5us
      5. Send low signal from the controller to SIG pin
    6. Set the corresponding pin on the controller as an input which is connected to SIG pin
    7. Fetch the system uptime when rising edge interrupt occurs. The noted time can be considered as the "start_time" of the echo pulse.
    8. Fetch the system uptime when falling edge interrupt occurs. The noted time can be considered as the "stop_time" of the echo pulse.
    9. Calculate the distance from the obstacle. (Distance = ((start_time - stop_time)/147) in inches or Distance = ((start_time - stop_time)/57.14) in cm).
    10. Send the calculated distance to the master controller over the CAN bus.

    Steps 4 to 10 are executed within the 100Hz periodic task.

    Technical Challenges

    Unreliable sonor sensors values

    Problem Summary: Observed lots of false detection for sensor over CAN bus resulting in unwanted motor turning.

    Problem Resolution: Reduced noise with the help of mounts to reduce vibration from car.

    Reduced range when mounted on car

    Problem Summary: Max detection range reduced when mounted on car with mounts.

    Problem Resolution: Increased ampere to entire circuit to support complete functionality of sensors.

    False triggering due to proximity

    Problem Summary: All the sensors transmitted pulse at the same time which caused interference among adjoining sensors.

    Problem Resolution: Revised sensor placement and triggered non-overlapping sensors at the same time to have minimum overlapping detection range and reduced interference among sensors.

    Calculation Error

    Problem Summary: Calculated distance in ISR which provided random results.

    Problem Resolution: ISR should be kept simple and it should take less time for execution. So for distance calculation other function was created which was called in the 100Hz task.


    Motor ECU

    Hardware Design

    The traxxas chassis came with ECU and servo controller. It has DC motor with servo control for turning. Working on 3.4 V/ 3000mAH power specifications it has axle to rotate all the four wheels. The feedback for PWM controlled speed attained is fed back through magnetic encoder. The front wheels have servo connection for turning. The chassis is placed on suspension unit for shock absorbing. An acrylic sheet is mounted over certain height on which the PCB and controller is placed. The motor controller sends signals for PWM and servo motor angles for driving the car.

    Software Design

    The motor gets signal from motor controller. The motor controller sends PWM signals for speed control of DC motor. Also it implements PID for uniform performance on ramp. For direction control, the servo has 2 levels of turning: soft and moderate. Depending on Driver Controller signal, the Motor Controller sends control signals to the motor. In case of communication loss from Master Controller, the Motor Controller displays CAN MIA condition on LED.

    Technical Challenges

    Finding PID constants

    Problem Summary: For uniform speed over ramp, we implemented PID. However, calculating the constants for PID proved to be challenging due to oscillations of set speed.

    Problem Resolution: Set discrete speed levels to prevent oscillations. Determined PID constants through trials and errors.

    Determining RPM accurately

    Problem Summary: No support available for motor encoder reed sensor.

    Problem Resolution: After checking values on DSO, we noticed irregular output. We resolved it by using pull up resistor of 1k ohms.

    Motor stop functioning before demo

    Problem Summary: The motor stopped functioning even with correct power and signal input.

    Problem Resolution: Had previously dismantled the chassis for encoder study. Re assembled the chassis to function correctly at demo.


    Geographical Controller

    NAZA GPS and Compass module

    The GPS module provides the location of the car on the earth in terms of latitude and longitude in degrees. This helps us know the current position of the car to navigate to the destination. We use this information to calculate range and bearing of the car to the destination and navigate according to this information. The compass gives the heading of the car with respect to North direction. In case the car is facing north, we will get 0 degree in compass. However, that is not always true and repeatable, hence the compass module needs caliberation. The gps and compass module together called as geo sensors form important part of Geographical Controller. The geo sensors module used in the car is from NAZA. The positioning of the module on the car is such that it is away from all the electromagnetic interference. The NAZA module communicates to geographical controller over UART to send data. This data is decoded by the Geographical Controller and send to Master Controller for further action to the Motor Controller. The part of the LCD display mounted on the car. The Geographical Controller interprets geo data for the Master Controller.

    Hardware Design

    The NAZA module consisting of both gps locator and compass is mounted on a stbaud rateand to avoid electromagnetic interference. The small notch on the device indicates the front direction of the compass. The module is interfaced to the SJOne board through UART at a baud rate of 115200 and called periodically in 10Hz frequency. The module is set to transmit mode hence receiver UART signal connection was used to just configure the GPS baud rate (Initially comes with 9600 ). It sends longitude and latitude (message id: 0x10) in one cycle and compass value (message id: 0x20) in the next. It also sends the version number (message id : 0x30), but it is not being used in the project.

    The GPS module, works in all weather conditions, within an unobstructed line of sight communication using 4 or more GPS satellites. As more number of satellite in line of sight to a GPS receiver, higher is the accuracy in determining the position of the module. When a receiver receives a signal from one of the satellite, it calculates its distance from the satellite considering a 3-D sphere with the satellite located at the center of the sphere. Once the receiver receives the signal from at least three satellites out of 32, the receiver then points its location using trilateration process. The trilateration is the process of determining module position based on intersecting spheres of satellite distance to module. The GPS module calculates its distance from the satellite considering a 3-D sphere with the satellite located at the center of the sphere. Once the receiver does the same with 3 other GPS satellites, the receiver then proceeds to find the intersection point of the 3 spheres to calculate it’s location.A GPS requires at least 3 satellites to calculate 2-D position(latitude and longitude on a map) at mean sea level. However, it requires at least 4 satellites to find receivers 3-D position(latitude, longitude, and altitude)

    Software Design

    Bearing distance calculation: Bearing distance is the shortest distance from point A to point B on the great-cicle of the Earth. We have used Haversine Distance formula for the same

    Bearing Angle Calculation: Bearing angle is the angle representing the desired navigation of the object with respect to the north in clockwise direction. The bearing angle is used to calculate the relative angle between two points on the map. In our case we used this to calculate the turning angle which tells the car how much to turn by and which direction.

    Route Planning: We have designed a simple algorithm takes in source and destination as a input parameter. Also we have maintained a pool of checkpoints which avoids the car to approach inaccessible locations. The algorithm calculates midpoint of the source and destination and calculates the nearest checkpoint to it. Later this checkpoint will be used as a source to calculate midpoint and searched for the nearest checkpoint.


  • File:GPS /Block.jpg
    Sensor Hardware Interface
  • Technical Challenges

    Unreliable GPS lock

    Problem Summary: Was losing GPS lock necessary to get reliable GPS data.

    Problem Resolution: Worked on the received data from the GPS module. Ensured GPS lock only upon receiving reliable and consistent geo data.

    Jumpy Compass Values

    Problem Summary: The compass would not return same value at same position on switching power off and on again.

    Problem Resolution: Initially, we thought it was just due to electromagnetic interference. However that was not just the case and the problem also was with compass calibration. Hence, implemented Kalman filter to reduce the sudden change in compass sensor values.

    NOTE: 1) Always for testing and data calibration, do it in an open air. 2) Before testing the car for navigation, check multiple times if there is any offset that the compass shows. If it does and the offset is constant, just compensate the offset in the received data. If the offset is not constant then there might be different issue. 3) Also try including filters to avoid compass angle fluctuations.


    Communication Bridge Controller & LCD

    Hardware Design

    The bridge controller is an interface of communication between car and the android Application controlling the car. Whatever commands App needs to send to the car, they are sent using Bridge Controller. All the data to be updated on the android application such as current location, car speed etc., is first sent to Bridge controller and then bridge controller sends the whole data to Android Application. Effectively, this controller communicates with each and every controller on the car and hence it is one of the crucial controllers. This controller also keeps the track of Master Controller's Heart Beat and Resets the car if master controller is not responding with heart beat.

    Bridge controller uses XBee Pro ZigBee module to communicate with the android application. ZigBee provides long range of communication i.e. approximately up to 100 meters when in line of sight or practically around 80 meters. However, there is no method to send data directly to ZigBee module from android application. Thus, to work around, a Bluetooth module is connected with Zigbee module. In this method, app can send data to Bluetooth module placed near to it. The BT module is connected to 1 ZigBee module directly with Tx-Rx wires. Hence The data received by BT is automatically transmitted to ZigBee module 1. This XBee receives the data from BT and sends it ahead to another XBee Pro; placed on the Bridge Controller on the car. The whole process occurs in reverse when any data is to be updated on the application from car. Thus, the hardware design of Bridge controller consists of 3 parts:-

    • Bluetooth HC05 - XBee Pro Connection
    • SJOne- XBee Pro Connection
    • Integration for the communication
  • Bluetooth - XBee Connection
  • Bluetooth - XBee Connection

  • Bridge Hardware Interface
  • Software Design

    The bridge controller being the controller to communicate with all the controller on the car has to adhere to the data formats send by the respective controllers. The controller should always fetch the data in different formats, parse it to convert to a single format and then send to mobile application. The process becomes reverse i.e. accept the data from application in one format and parse it to convert in different formats to send to every other controller.

    Technical Challenges

    Delayed or no response to mobile switch on off data

    Problem Summary: The on and off from the mobile app did not reliably switched on the Master Board. Often had to send start/stop signal multiple times to be registered by the Master bridge controller.

    Problem Resolution: During code review we came to know to decode all CAN messages inside 1 while loop and assign the data into respective structure. Prior to that the code was designed to decode CAN message for each structure in different while loops. This also resolved the dim led glow of Master controller heartbeat.

    Co ordination with Geo Controller for destination details

    Problem Summary: The destination geo location data (longitude and latitude) is available to bridge controller from the mobile application before the geo controller gets geo fix. This caused synchronization problem as the destination coordinates was only sent once and not received by the geo controller.

    Problem Resolution: Synchronized the data sending of destination coordinates by sending destination data only after geo fix was attained. the process on each controller after that were independent and did not require synchronization.


    Master Module

    The Master Controller is important part of the system. It takes data from Geo Controller board and Ultrasonic Controller board and decides the movement of the car through Motor Controller board. Also it tracks heart beat of all the controllers. Its main objective is to navigate to destination with obstacle avoidance. It receives navigation start signal from bridge controller. It stops navigation when Geo controller sends destination is reached. The master controller makes use of onboard LEDs as indicators of different status.

    Hardware Design

    The master controller is connected to all the controllers through CAN bus. The master receives and sends CAN message at 100 Hz frequency. It uses on board LEDs to display functioning controller which gives heartbeat. If any board goes off the CAN bus, from the LED off status we can come to know which board has reached MIA condition. To display sent motor command it sets appropriate numeric value on LED segment. For different states it indicates respective number on the 7 segment LED display. For navigating based on sensor value, logic is written with higher priority to sensor and stopping the car then to react to response from Geo Controller. Ultimately, the master has movement control of the car operations.

    Software Design

    The master controller gets start-stop command from bridge controller. This signal is sent from the mobile application by the user. From each ultrasonic sensors, it gets distance to obstacle and compares it to threshold value. Then it checks for direction and magnitude from geo sensor input to send motor controller commands for driving and steer control. Also it displays heartbeat for remaining controllers through on board LED.

    Sr no Left sensor value Middle sensor value Right sensor value Motor reaction Motor Command Drive Motor Command Steer
    0 0 0 0 movFrwd drive_front steer_front
    1 0 0 1 movSoftLeft drive_moderate steer_soft_left
    2 0 1 1 movModLeft drive_slow steer_moderate_left
    3 0 1 0 movModLeft drive_slw steer_moderate_left
    4 1 1 0 movModRight drive_slow steer_moderate_right
    5 1 0 0 movSoftRight drive_moderate steer_soft_right
    6 1 0 1 movFrwd drive_forward steer_front
    7 1 1 1 movReverse drive_reverse steer_moderate_left

    Technical Challenges

    Levels of turning

    Problem Summary: For turning on detecting obstacle, the large servo turning value would result in oversensitive behaviour.

    Problem Resolution: Set 2 discrete servo levels for turning based on how many ultrasonic sensors are triggered. A moderate turning angle command is sent if two sensors (front or any one of the side sensors) and a soft turn command is sent if only one of the side sensor detects obstacle closer than threshold.

    Determining threshold

    Problem Summary: The car kept crashing even after detecting obstacle.

    Problem Resolution: Determined threshold values through trials and errors. For high speed, large clearance is required for stopping distance. Ideally keep higher threshold value for front sensor than side sensors.

    Unresponsive to GEO sensor data

    Problem Summary: The motor command responded only to ultrasonic commands and disregarded the geo information even after including it the geo data in motor command decision making.

    Problem Resolution: This was a programming bug. Code restructuring and verifying the conditions helped solve this problem. The nested if structure had most frequently used command at the top of nested if, to reduce time lag. This proved unreliable as the frequently used command had ultrasonics default condition which overshadowed the geo data analysis part. Putting this condition to the end of the nested structure helped solve this default behaviour taking precedence everytime. Geo data had same conditions for stop and no data received from geo sensors. Hence the car stopped when no geo data was received. Remedying this with separate constants for each helped solve this problem.

    Evaluating both Geo sensors and Ultrasonic

    Problem Summary: The conditions for steering was taken with both ultrasonic and geo sensors data. This created delay and uncertainty in decision making even with checking ultrasonic first.

    Problem Resolution: Restructuring the code to check all possible outcomes of Ultrasonic and then checking Geo sensors outcome. This made sure ultrasonic obstacle detection always got higher priority and faster response then geo navigation outcome.


    Mobile Application

    <Picture and link to Gitlab>

    Hardware Design

    Software Design

    <List the code modules that are being called periodically.>

    Technical Challenges

    <Bullet or Headings of a module>

    Wifi Link Reliability

    <Problem Summary> <Problem Resolution>



    Conclusion

    Successfully designed, implemented and tested autonomous car navigation as part of course requirement. Additionally, we worked as a team and completed the assigned tasks successfully.

    We achieved following learning goals:

    • Usage of CAN bus

    Working extensively with CAN bus for communication has given us better understanding of this communication protocol. With CAN, it became really easy to get system status in real time instead of using print statements over UART. Further, understanding the DBC file format made us more aware about the data being transmitted.

    • GIT version control

    With GITLab it became really easy for the team members to work on their portion of code and then push it to their respective branch for sharing with others. The merge resolve gave valuable peer feedback. The simplicity of use of the tool was added bonus to learn and do necessary version control.

    • Unit Testing

    Unit testing helped us to remove programming bugs at development stage itself. Anytime with new logic insertion, the unit test would give warning if the modified algorithm is compatible with the overall logic or not. It proved to be challenging task with the developing logic be it use of static elements or restructuring the code for ease of unit testing.

    • Team work and Dedication

    Team members were always open minded about approaching difficulties. Everyone worked diligently on their module often staying overnight to finish task at hand. The team structure would evolve with the requirement of that week. No one limited themselves to one particular task and always went out of their way to lend helping hand.

    Project Video

    Project Source Code

    Advise for Future Students

    Do lots of field testing! Initially for obstacle avoidance then with geographical sensors. Finally with both integrated on the designed PCB. As this is mostly last minute, one can miss the minor/major bugs at this crucial stage. So do lots of field testing and analyse the behavior of the autonomous car.

    Use reliable sensors and not only cheap ones. Sensors provide the controller with reliable and crucial data for navigating autonomously. Hence selected sensor should be repeatable and reliable.

    Using CAN bus for debugging the issues in the car. CAN has graphical tools which can make debugging easier. In our case, we noticed right away that sensor values were jumping randomly and triggering falsely. We caught this immediately over the Bus Master representation of CAN data values.

    Order extra components! This is important as during testing your component may get damaged. Replacing them at that point is time consuming and frustrating. So always order more components than requirement. You can always return the unused components later.

    Follow the grading rubrics. The rubrics is designed such that it tests stages of development for the autonomous car. Completing the rubrics goals is completing the basic system functionality and testing them with ISA or Professor. They provide valuable feedback on the current and next course of action.

    Acknowledgement

    We would like to acknowledge the following people for their help in completing this project:

    • Prof. Preetpal Kang for teaching CAN and Git and guiding throughout the project
    • Prof. Kai Kai Liu for the Car chassis and geographical sensor
    • Pratap for advice on obstacle avoidance
    • Maxbotix for a generous student discount on their product.
    • Microchip for the free CAN ICs.

    References Used