S22: Firebolt
Contents
- 1 Abstract
- 2 Objectives & Introduction
- 3 Schedule
- 4 Parts List & Cost
- 5 Printed Circuit Board
- 6 CAN Communication
- 7 Sensor and Bluetooth ECU
- 8 Motor ECU
- 9 Geographical And Bridge Controller
- 10 Driver Node
- 11 Mobile Application
- 12 Conclusion
Abstract
Firebolt is battery powered autonomous RC car. The car uses four microcontrollers for communication between the nodes- driver node, motor node, bridge & sensor node, and geological node over the CAN bus. It is interfaced to the mobile application which sends GPS coordinates for the destination location to the driver node and reaches the destination by avoiding any obstacles that comes in the path. For obstacle detection and avoidance it uses Ultrasonic Sensor and makes the decision of steering and maintaining speed after performing calculations based on the bridge and sensor node's data.
Objectives & Introduction
Objectives
The objective of this project is to get hands on experience of application of embedded systems in autonomous vehicles, have understanding of CAN bus communication, CAN database files, TDD and other related tools such as PCAN dongle and Busmaster.
Software side
- The car communicates with an Android application
- Receive coordinates from gps to drive itself to the destination while avoiding obstacles
- Display useful information on the LCD
- Take care of elevation and make correct speed decisions
- DBC file for all the nodes
Hardware side
- Design PCB for four controllers and other necessary components
- Choose good options for mounting the ultrasonic sensors on the car
- Make a good GUI Android application for interfacing with the microcontroller
Introduction
Four Nodes of the RC Car are:
- Driver Node
- GEO Node
- Sensors and Bridge Node
- Motor Node
- Mobile Application
Team Members & Responsibilities
Priyanka Rai LinkedIn'
- Geo Controller
- GPS and Compass Interfacing
- Motor Controller
- Integration Testing
- Wiki Page Update
Ritu Patil LinkedIn'
- Motor Controller
- RPM Sensor
- Integration Testing
- Wiki Page Update
Ritika Beniwal LinkedIn'
- Driver Node
- LCD interfacing
- Motor Controller
- Integration Testing
- Wiki Page Update
Utsav Savaliya LinkedIn'
- Sensor Controller
- Integration Testing
- Wiki Page Update
Dhanush Babu LinkedIn'
- Bluetooth module interfacing
- Motor Controller
- Android App
- Integration Testing
Schedule
Week# | Start Date | Target Date | Task | Completion Date | Status |
---|---|---|---|---|---|
Week 1 |
|
|
|
|
|
Week 2 |
|
|
|
|
|
Week 3 |
|
|
|
|
|
Week 4 |
|
|
|
|
|
Week 5 |
|
|
|
|
|
Week 6 |
|
|
|
|
|
Week 7 |
|
|
|
|
|
Week 8 |
|
|
|
|
|
Week 9 |
|
|
|
|
|
Week 10 |
|
|
|
|
|
Week 11 |
|
|
|
|
|
Week 12 |
|
|
|
|
|
Parts List & Cost
Item# | Part Desciption | Vendor | Qty | Price($) |
---|---|---|---|---|
1 | RC Car | Traxxas [1] | 1 | 280 |
2 | CAN Transceivers MCP2551-I/P | Comimark [2] | 5 | 8.99 |
3 | Ultrasonic Sensors | Max Botix[3] | 4 | 24.95 |
4 | GPS Breakout Board | Adafruit[4] | 1 | 29.95 |
5 | GPS Antenna | Adafruit[5] | 1 | 19.95 |
6 | RPSMA female to mhf4 | Superbat[6] | 1 | 7.99 |
7 | HC05 bluetooth RF Transceiver | HiLetgo[7] | 1 | 15.99 |
8 | Triple-axis Accelerometer | Adafruit[8] | 1 | 14.95 |
9 | Traxxas RPM Sensor | Traxxas[9] | 1 | 13.76 |
10 | Traxxas Battery and Charger | Traxxas[10] | 1 | 62.95 |
11 | Voltage Regulator | Valefod[11] | 6 | 10.99 |
12 | Headlights | Hobbypark[12] | 1 | 7.96 |
Printed Circuit Board
Initially we started our testing with mounting all our hardware on the breadboard (yes, it was messy and unstable!).
PCB Schematic
PCB Board
Challenges
- Since there are four controllers and a significant number of components (gps, sensors, can transceivers, volt regulator etc.) it was difficult for us to keep our hardware stable because every time we go for field testing some will get disconnected and we were kind of stuck up in the hardware setup.
- We decided to get the PCB printed but there were some issues and resolving them and getting a new PCB would take time.
Solution
- Finally we decided to use the prototype board for mounting all the components and stabilizing our hardware.
CAN Communication
We used controller area network to communicate data between four nodes. All nodes are connected to each other through a physically conventional two wire bus CANH and CANL. The wires are a twisted pair with 120 Ω termination resistors at each end of the bus. 1s and 0s are transmitted as CAN High(0V difference) and Can Low(2v difference). A CAN frame has the following contents:
- Data Length Code (4bits)
- Remote Transmission Request.
- ID extend bit.
- Message ID (11 bit or 29 bit)
- Data bytes( depends on DLC)
- CRC
Arbitration: No two nodes will transmit at the same time because of arbitration. A lower Message-ID has a Higher priority on the CAN bus since 0 is the dominant bit.
Bit Stuffing: CAN bus stuffs extra bits when a long chain of multiple 1's or 0's occur to improve CAN integrity.
DBC File
The DBC file is a simple text file that consists of information for decoding raw CAN bus data to physical values or in human readable form.
Sr. No | Message ID | Message function | Receivers |
---|---|---|---|
Driver command | |||
1 | 300 | Speed and steering direction for the motor | Motor |
2 | 100 | Driver Heartbeat | Motor, Sensor, Geo |
Sensor And Bridge Controller | |||
3 | 200 | Sensor sonars from front, back, left ,right sensor | Driver |
Motor Controller | |||
4 | 600 | motor speed, motor direction | Driver |
Geo Controller | |||
8 | 400 | Bearing, Heading and Distance | Driver |
Debug messages | |||
6 | 700 | Driver Debug | BRIDGE_SENSOR,MOTOR,GEO |
7 | 750 | Geo Debug | BRIDGE_SENSOR,MOTOR,DRIVER |
VERSION "" NS_ : BA_ BA_DEF_ BA_DEF_DEF_ BA_DEF_DEF_REL_ BA_DEF_REL_ BA_DEF_SGTYPE_ BA_REL_ BA_SGTYPE_ BO_TX_BU_ BU_BO_REL_ BU_EV_REL_ BU_SG_REL_ CAT_ CAT_DEF_ CM_ ENVVAR_DATA_ EV_DATA_ FILTER NS_DESC_ SGTYPE_ SGTYPE_VAL_ SG_MUL_VAL_ SIGTYPE_VALTYPE_ SIG_GROUP_ SIG_TYPE_REF_ SIG_VALTYPE_ VAL_ VAL_TABLE_ BS_: BU_: DRIVER MOTOR BRIDGE_SENSOR GEO DEBUG BO_ 100 DRIVER_HEARTBEAT: 1 DRIVER SG_ DRIVER_HEARTBEAT_cmd : 0|8@1+ (1,0) [0|0] "" BRIDGE_SENSOR,MOTOR,GEO BO_ 101 DRIVE_STATUS: 1 BRIDGE_SENSOR SG_ DRIVE_START_STOP : 0|8@1+ (1,0) [0|0] "" DRIVER BO_ 200 SENSOR_SONARS: 5 BRIDGE_SENSOR SG_ SENSOR_SONARS_left : 0|10@1+ (1,0) [0|0] "cm" DRIVER SG_ SENSOR_SONARS_right : 10|10@1+ (1,0) [0|0] "cm" DRIVER SG_ SENSOR_SONARS_middle : 20|10@1+ (1,0) [0|0] "cm" DRIVER SG_ SENSOR_SONARS_rear : 30|10@1+ (1,0) [0|0] "cm" DRIVER BO_ 250 DESTINATION_LOCATION: 8 BRIDGE_SENSOR SG_ DEST_LATITUDE : 0|28@1+ (0.000001,-90.000000) [-90|90] "degrees" GEO SG_ DEST_LONGITUDE : 28|28@1+ (0.000001,-180.000000) [-180|180] "degrees" GEO BO_ 300 DRIVER_TO_MOTOR: 2 DRIVER SG_ DRIVER_TO_MOTOR_speed : 0|8@1+ (0.1,-10) [-10|10] "kmph" MOTOR, BRIDGE_SENSOR SG_ DRIVER_TO_MOTOR_direction : 8|8@1+ (1,-45) [-45|45] "degrees" MOTOR, BRIDGE_SENSOR BO_ 400 GEO_CONTROLLER_COMPASS: 8 GEO SG_ HEADING : 0|12@1+ (0.1,0) [0|359.9] "degrees" DRIVER, BRIDGE_SENSOR SG_ BEARING : 12|12@1+ (0.1,0) [0|359.9] "degrees" DRIVER,BRIDGE_SENSOR SG_ DISTANCE_TO_DESTINATION: 24|32@1+ (0.01,0) [0|359.9] "meters" DRIVER,BRIDGE_SENSOR BO_ 600 MOTOR_SPEED: 2 MOTOR SG_ MOTOR_SPEED_info : 0|8@1+ (0.1,-10) [-10|10] "kmph" DRIVER, BRIDGE_SENSOR BO_ 700 DRIVER_DEBUG: 2 DEBUG SG_ car_driving_status: 0|8@1+ (1,0) [0|0] "" DEBUG SG_ car_steering_status: 8|8@1+ (1,0) [0|0] "" DEBUG BO_ 750 GEO_CONTROLLER_DEBUG_MESG: 10 DEBUG SG_ CURR_LATITUDE : 0|28@1+ (0.000001,-90.000000) [-90|90] "degrees" DEBUG SG_ CURR_LONGITUDE : 28|28@1+ (0.000001,-180.000000) [-180|180] "degrees" DEBUG SG_ RAW_HEADING : 56|12@1+ (0.1,0) [0|359.9] "degrees" DEBUG CM_ BU_ DRIVER "The driver controller driving the car"; CM_ BU_ MOTOR "The motor controller of the car"; CM_ BU_ SENSOR "The sensor controller of the car"; CM_ BO_ 100 "Sync message used to synchronize the controllers"; CM_ BU_ GEO "To provide raw GPS and compass heading"; CM_ SG_ 100 DRIVER_HEARTBEAT_cmd "Heartbeat command from the driver"; VAL_ 700 car_steering_status 2 "RIGHT" 1 "LEFT" 0 "STRAIGHT"; VAL_ 700 car_driving_status 2 "BACKWARD" 1 "FORWARD" 0 "STOPPED";
Sensor and Bluetooth ECU
The obstacle detection sensors used here are Ultrasonic sensors. The HRLV-MaxSonar-EZ1 sensors from MaxBotix are used here. In these sensors there is membrane which needs to be triggered in order to generate and send ultrasonic objects every few seconds. When ultrasonic waves collide and come back and strikes with this membrane a pulse is generated which is used for sensing.
Hardware Design
Pin connections between board and sensor:
Sl No. | SJ2 board Pin No. | Ultrasonic sensor Pin No. | Function |
---|---|---|---|
1. | ADC Pin 1.30 | AN(Front left sensor) | Input to ADC channel 4 |
2. | ADC Pin 1.31 | AN(Front right sensor) | Input to ADC channel 5 |
3. | ADC Pin 1.26 | AN(Front sensor) | Input to ADC channel 3 |
4. | ADC Pin 1.25 | AN(Rear sensor) | Input to ADC channel 3 |
5. | GPIO Pin 0.6 | Rx(Front left sensor) | Triggering pulse for left sensor |
6. | GPIO Pin 0.8 | Rx(Front right sensor) | Triggering pulse for right sensor |
7. | GPIO Pin 0.9 | Rx(Front sensor) | Triggering pulse for front sensor |
8. | GPIO Pin 0.7 | Rx(Rear sensor) | Triggering pulse for rear sensor |
Software Design
The sensor node has to receive values from all the sensors and send the distance values on the CAN bus for the driver to run the obstacle avoidance logic.
Receive sensor values:
Four sensors are used here. Three in the front and one at the rear side. We need four ADC channels to address the receiving from all sensors. In order to use four pins on the SJ2 board we need to set the pins to analog mode. In the adc.h file and adc.c file there are only three channels initialized, so one needs to add ADC channel 3 in these files. On how to use these sensors, the datasheet of helped a lot. It addresses every aspect of how to use this particular sensor and the solution to most of the problem that can arise. All the sensor raw values are digitally converted in the range of 0 to 1024( 10 bit ADC). These value is in inches as mentioned in the datasheet. So, one needs to convert it into centimeter by applying some formula. The formula can be different based on the configuration used to setup the ADC channel even if same sensor is used.
Technical Challenges
The main challenge while using ultrasonic sensor with this particular project is of crosstalk. While detecting objects in the front all the front sensors waves are interfering with each other giving false values in the left or right sensor while the object is in the front only. The datasheet addresses this issues and what to do when multiple sensors are used in a system. It says that trigger each sensor are different time period in order to avoid crosstalk. So we triggered the front and rear at one particular time and left and right at one particular time. One sequence is triggered at particular 10Hz and other sequence is triggered at another 10Hz. There is a division of callbacks counts in 100Hz and a lock mechanism is used in order to used different 20Hz period out of 100Hz.
For frequency noise measurements like when the values suddenly change or vary between certain range sometimes, a filter is implemented. The most common filter for this type of use is median filter where a series of values are stored in a array and median is taken of all the values stored in that array.
Motor ECU
The Motor ECU acts as an encoder for the DC motor (used for propulsion) and Servo motor (used for turning the axle and changing direction of the car). The car is a two wheel drive with DC motor connected to the rear wheels and the servo motor is connected to the front wheels. The DC motor is controlled by Electronic Speed Control. The ECU supplies PWM signal to the ESC and the ESC powers the DC motor. The Servo motor is powered by the car battery as well and gets its PWM signal from the ECU. The RPM sensor sends its output to motor ECU by which the actual speed of the wheels is calculated.
Hardware Design
ESC & DC MotorThe DC motor is controlled by ESC using PWM signals provided by the motor controller for forward and reverse movements. We used the 9v NiMH battery to power up the ESC. The DC motor is powered by the ESC which has a dc-to-dc converter which converts 9v to 6v. The output from the ESC is used to power the Servo motor. ESC has an ease set button which is used for calibration and setting different modes for the car. The car can be operated in the following 3 modes:
As we desire to run the car at full throttle, Sport mode is being used. The frequency of the PWM signal fed to the servo motor is 100Hz. Based on the duty cycle set by the user, the car will go forward, reverse, or neutral.
Servo MotorWe are using Traxxas 2075 for this project which came with the car and it is responsible for steering the car. It takes the 6V power directly from ESC. The servo motor is controlled directly from the SJ2 micro-controller board. The PWM signal is supplied at a frequency of 100 Hz. Based on the duty cycle of the signal sent to the servo, the direction of servo motor can be changed: PWM 10 to 14.9 for turning left.
Software DesignAt startup the motor is initialized by giving a neutral PWM signal for 3s and the interrupt for the rpm sensor input is setup as well. The motor receives angle for steering and speed in a single CAN message from the driver ECU. After receiving the command the speed value is converted into corresponding value of PWM by increasing or decreasing neutral PWM value in steps of 0.01. The physical value of the motor speed is compared to the speed received from the driver and it is reduced or increased to match with the desired speed. For reverse a PWM of 14.5 is given to smoothly reverse the car. The direction of the car is set according to the value of ENUM received from the driver ECU. For navigation the car takes soft turns and when and obstacle is detected it takes hard turns to avoid collisions.
Technical Challenges
Geographical And Bridge ControllerHardware DesignThe Geographical controller does the processing for compass data and GPS data. After processing the data for heading ,bearing and distance to destination , the controller sends these data over can bus to the Driver node. The GPS module is interfaced with SJ2 board using UART. SJ2 board gets the data (NMEA string) for GPS coordinates processing. The controller sends the command to GPS module to filter the string and only send GPGGA string. The Compass module is interfaced over I2C to find the heading for car navigation. The CAN transceiver uses port 0 (can1) of the SJ2 board.
Software DesignThe GEO controller consisted of 4 main parts which are:
OverviewThe geographical node uses the following code modules:
These modules, calculate compass heading degree, bearing, parse GPS coordinates, calculate the checkpoints the RC car has to go through when navigating to a destination, send distance to destination to driver node, and handle messages received on the CAN bus.
GPSInitializationIn the initialization process of the GPS, the line buffer module is configured to parse the GPS messages, the GPIOs P0.15(Tx) and P0.16(Rx) are configured, UART interrupt queues enabled, and the UART is configured at a baudrate of 9600(GPS standard). ConfigurationIn the gps__run_once_10Hz() the GPS is initially configured once to disable all NMEA messages except GNGGA which is message chosen to parse the coordinates and GPS lock. Parsing NMEA GNGGA messagesThe GPS module constantly transmits NMEA GNGGA messages over UART to the SJ2 MCU. These messages which come in the form of a string are stored character by character in the line buffer until a new line character which indicates the end of string. The stored string is then extracted from the line buffer. The extracted line is then tokenized to parse the latitude, latitude direction, longitude, longitude direction, and fix quality. South and West directions are also properly handled to make the latitude and longitude negative values. GPS lockAlthough the GPS module has fix indication , but GPGGA string has field for FIX status also. Getting the Fix/Lock status using the string is much easier than using GPIO pins to get the Lock status using FIX led of the GPS module. The Lock status/flag was used as a condition to calculate the bearing and checkpoints only when the GPS had a lock meaning that the current coordinates were valid. CompassInitializationThe compass initialization configures the LSM303DLHC magnetometer and accelerometer registers over I2C bus to default settings using default gain and single mode. Heading degree computationThe compass heading degree is computed by using the tilt compensation algorithm and the pitch and roll values of LSM303DLHC accelerometer. The tilt compensation algorithm ensures that the values of the compass heading are precise. The formulae used to calibrate the compass are mentioned below: Pitch and Roll: pitch = asin(-acc_x / sqrt(acc_y * acc_y + acc_z * acc_z + acc_x * acc_x))
mag_x = mag_x * cos(pitch) + mag_z * sin(pitch) mag_y = mag_y * cos(roll) + mag_x * sin(roll) * sin(pitch) - mag_z * sin(roll) * cos(pitch) mag_z = -mag_x * cos(roll) * sin(pitch) + mag_y * sin(roll) + mag_z * cos(roll) * cos(pitch)
Heading angle heading = atan2(mag_y, mag_x) * r2d r2d is radian to degree conversion function This heading is calculated in radians since atan2 returns a value between -π and +π. Therefore, before converting the heading into degrees the value needs to be normalized to put it in the range from 0 to 360 degrees. Geo_logic_calculations.c and waypoints.c moduleBearing Angle computationThe bearing which is the angle towards our desired destination is computed using the formulas below referenced at this link. X = cos θb * sin ∆L Y = cos θa * sin θb – sin θa * cos θb * cos ∆L β = atan2(X,Y)
The bearing is also calculated in radians since atan2 returns a value between -π and +π. Therefore, before converting the heading into degrees the value needs to be normalized to put it in the range from 0 to 360 degrees. The calculated bearing is then sent to the driver node which use the compass heading degree and the bearing to align the car toward the target destination. Checkpoints AlgorithmThe checkpoint algorithm depicted below uses a simple algorithm in which chooses the next point to navigate to if the checkpoint is the closest to the car while at the same time the closest to the destination. For the testing of our car navigation system, we choose the top floor of the north garage at San Jose State University as it provides a great open space and best signal for the GPS. In the figure shown below, five checkpoints were chosen in which the car can navigate to depending on where the destination is set to. Having fewer points rather then having too many reduces the amount of checkpoints the car has to move to and allows to reach the destination quicker while at the same time avoid areas such as the ramp in which the car should not go to.
a = sin²(ΔlatDifference/2) + cos(lat1) * cos(lt2) * sin²(ΔlonDifference/2) c = 2 * atan2(sqrt(a), sqrt(1−a)) d = R * c
Technical ChallengesDriver NodeDriver Node is the master controller. It receives input from sensor and bridge node, processes it to make right decision for controlling the speed and steering direction of the car and then commands the motor node to drive accordingly. This node is also interfaced to the LCD, which acts as dashboard of the car and displays information such as car speed and distance to destination on the screen. HardwareLCD is interfaced with the SJ2 board and it communicates over UART. P4.28 and P4.29 which is UART3 on board is used. Headlights and Tailights are also connected to the driver node using four GPIOs. Software Architecture Driver Logic
Obstacle Avoidance Logicif (obstacle_on_all_front_sides()) { stop_the_car(); reverse_car_and_steer(); } else if (obstacle_on_left() && obstacle_in_right() && (!obstacle_on_front())) { drive_forward(); } else if (obstacle_on_left() && (!obstacle_in_right())) { obstacle_on_right = false; get_steering_range(obstacle_on_right); // right steer } else if (obstacle_in_right() && (!obstacle_on_left())) { obstacle_on_right = true; get_steering_range(obstacle_on_right); // left steer } else if (obstacle_on_front() && (!obstacle_on_left() && !obstacle_in_right())) { stop_the_car(); reverse_car_and_steer(); obstacle_on_right = (internal_sensor_data.SENSOR_SONARS_right < internal_sensor_data.SENSOR_SONARS_left) ? true : false; get_steering_range(obstacle_on_right); } else if (obstacle_on_rear() && (!obstacle_on_all_front_sides())) { obstacle_on_right = (internal_sensor_data.SENSOR_SONARS_right < internal_sensor_data.SENSOR_SONARS_left) ? true : false; get_steering_range(obstacle_on_right); debug_values.car_driving_status = FORWARD; debug_values.car_steering_status = STRAIGHT; } else { stop_the_car(); debug_values.car_driving_status = STOPPED; debug_values.car_steering_status = STRAIGHT; }
if (obstactle_on_right == true) { //steer left motor_signal.DRIVER_TO_MOTOR_direction = (motor_signal.DRIVER_TO_MOTOR_direction <= 40) ? motor_signal.DRIVER_TO_MOTOR_direction + offset_to_angle : max_angle_threshold; motor_signal.DRIVER_TO_MOTOR_speed = slow_speed; update_lights(10, headlight_left); } else { //steer right motor_signal.DRIVER_TO_MOTOR_direction = (motor_signal.DRIVER_TO_MOTOR_direction >= -40) ? motor_signal.DRIVER_TO_MOTOR_direction - offset_to_angle : -max_angle_threshold; motor_signal.DRIVER_TO_MOTOR_speed = slow_speed; update_lights(10, headlight_right); } Reverse and Steer if (!obstacle_on_rear()) { motor_signal.DRIVER_TO_MOTOR_direction = 0; motor_signal.DRIVER_TO_MOTOR_speed = reverse_speed; update_lights(10, taillight_left); update_lights(10, taillight_right); } else { stop_the_car(); } Driver receives raw heading and bearing from the Geo node and in order to calculate the turning direction, it first computes the difference between heading and bearing. Then based on which quadrant the difference lies and where the destination lies, take navigation decisions to steer left, right or straight. if (heading_difference >= 350 && heading_difference <= 10) { gps_navigation_direction = straight; heading_difference = fabs(heading_difference); debug_values.car_driving_status = FORWARD; debug_values.car_steering_status = STRAIGHT; } else if (heading_difference > 180) { gps_navigation_direction = left; heading_difference = 360 - heading_difference; debug_values.car_driving_status = FORWARD; debug_values.car_steering_status = LEFT; } else if (heading_difference < 0 && heading_difference > -180) { gps_navigation_direction = left; heading_difference = fabs(heading_difference); debug_values.car_driving_status = FORWARD; debug_values.car_steering_status = LEFT; } else if (heading_difference < -180) { gps_navigation_direction = right; heading_difference = fabs(heading_difference + 360); debug_values.car_driving_status = FORWARD; debug_values.car_steering_status = RIGHT; } else if (heading_difference > 0 && heading_difference <= 180) { gps_navigation_direction = right; debug_values.car_driving_status = FORWARD; debug_values.car_steering_status = RIGHT; } Technical Challenges
Mobile ApplicationThrough the app we first scan for available devices and connect to the Bluetooth present on the RC car. After the connection is successful the destination is pinned on the map and by clicking on the "Send Destination to Car" button the car is notified of the destination. After this we can control the start and stop of the car with the two buttons present on the application. User Interface
Software DesignThe app was developed using MIT App inventor
BluetoothTechnical Challenges
ConclusionProject VideoProject Source Codehttps://gitlab.com/ritupatil1/firebolt/-/tree/master Advise for Future Students
AcknowledgementReferenceshttp://socialledge.com/sjsu/index.php/Industrial_Application_using_CAN_Bus
|