F17: Viserion

From Embedded Systems Learning Academy
Revision as of 08:40, 19 December 2017 by Proj user7 (talk | contribs) (Testing)

Jump to: navigation, search

Contents

Viserion Team RC Car

Abstract

Aim of this project is to build a self-navigating car. The car is divided into five modules. Each module consists of SJ One board as the main controller. The different modules in the car are master, sensors, geo, motor and bluetooth module. The car uses CAN communication protocol for communication between the modules.

The five modules of the car are :
Sensor Controller: This module detects obstacles in the driving path with the help of ultrasonic sensors.
Motor Controller: This controller drives the DC motor and Servo in the car.
Geographical Controller: This module assists the car in navigating to a destination with the help of location details provided by GPS and the orientation(bearing and heading angle) provided by the compass.
Bluetooth Controller: The controller uses Bluetooth to communicate with an Android application. Destination coordinates are provided by this module. The bluetooth module also displays important data like sensor readings, GPS coordinates and speed.
Master Controller: This module will collect data from all modules and direct the motor towards the destination.

Objectives & Introduction

Objectives

The objectives are as follows:

1.To detect and avoid obstacles encountered in the path.
2.To move at an appropriate speed depending upon the path requirement.
3.To use Bluetooth module to start/stop the car and display important data on the LCD.
4.To integrate gps and compass to make sure that the car navigates from source to destination.
5.To efficiently establish communication between all the modules using CAN protocol.
6.To reach a destination given by the Bluetooth module autonomously for a valid path.

System Block Diagram

Viserion Block Diagram

Team Members & Responsibilities

Master Controller

  • Aakash Menon
  • Omkar Kale

Geographical Controller

  • Ajinkya Mandhre
  • Aniket Dali
  • Jean Madassery

Sensor Controller

MOTOR & I/O CONTROLLER

BLUETOOTH CONTROLLER & ANDROID APP

Schedule

Show a simple table or figures that show your scheduled as planned before you started working on the project. Then in another table column, write down the actual schedule so that readers can see the planned vs. actual goals. The point of the schedule is for readers to assess how to pace themselves if they are doing a similar project.

Legend: Motor & I/O Controller , Master Controller , Communication Bridge Controller, Geographical Controller, Sensor Controller , Team Goal , Team PCB, , Team Android

Week# Start Date End Date Task Actual Completion Date / Notes Status
1 10/09/2017 10/15/2017
  • Research previous projects wiki page, gather useful information.
  • Discuss about roles and study data sheet of the required parts and list down minimum two parts for each required function.
  • Setup Git and slack accounts and verify that access is provided to all the team mates.
Done
2 10/16/2017 10/22/2017
  • Design Hardware layout for the project, schematic shall identify all the modules, ports and the pins interfaced.
  • Design sensor and motor board's schematic in eagle PCB.
  • Design data flow diagram for all the software exchanges between the modules and the master.
  • Complete DBC file based upon the design data flow diagram and share the file via GIT repo.
  • Study about GPS and Compass calibration .
  • Interface motor and drive using Preet's PWM driver API. Find different levels of speed and direction.
  • Interface one sonic sensor to the sensor controller. Receive data and calculate distance. Write send, receive and MIA functions to be able to perform basic CAN communication.
  • Study Android application software and approaches from previous projects and document the required features being provided by the application.
  • Order finalized Components.
Done on time except
  • PCB design was changed to only one PCB that will gather all controllers and have Can Bus on it.
3 10/23/2017 29/10/2017
  • Start interfacing received components to respective Nodes and do a superficial testing of components.
  • Design GPS/Compass, Bluetooth and master board's schematic in eagle PCB.
  • Identify and document best approach to calibrate Compass.
  • Experiment on duty cycle suitable for direction and speed of the motors
  • Communicate with Master and set speed and directions.
  • Interface RPM sensor and calculate speed in KPH
  • Interface all three front sonic sensor to the sensor controller. Apply filtering to get reliable data and send data to Master Controller.
  • Document Android approaches and decide on how to design the app and fix the protocol to exchange data with Bluetooth module.
Done on time except
  • Basic PCB design is done
  • Filtering was not applied at this time
4 10/30/2017 11/05/2017
  • Interface RPM sensor and measure Speed.Maintain the speed based on feedback for uphill and downhill
  • Improve the trajectory of the car using algorithm based on speed and directions
  • Stress test front sensors in different environment conditions indoor, outdoor and compare data. Also change different angles for sensors and find best angles for most reliable data and maximum coverage.
  • Start development of software modules for GPS and Compass modules and document the efforts and ways to test the algorithm.
  • Test can bus communication by mounting master, sensor and motor modules and transmitting master related commands.
  • Mount the parts on off shelf PCB for Demo 1 and verify the wiring connections and verify that CAR is ready for the demo,
Done on time
5 11/06/2017 11/12/2017
  • Finish Bearing Angle Calculation.
  • Control the Car's speed on detection of obstacle.
  • Interface back sensor, receive, filter and send data. All sensors should be working properly by now and master should be getting stable values even while car is on the move.
  • Finish development of algorithm for Compass & GPS calibration and verify that the direction obtained from the modules with that of any off shelf smartphone's Compass.
  • Car should now move without hitting "any" obstacle when powered on. Car should be able to take a reverse if required.

  • Back sensor was not yet interfaced. Filtering applied for front sensors.
6 11/13/2017 11/19/2017
  • Interface the LCD with micro controller and do basic display of text
  • Prepare design and possibly try to finish 3D printing or figure out some other hardware solution for sensor mount for final car design.
  • Share Gerber files with the PCB fabrication house and order 2 PCB.
  • Design basic Android application UI, which can verify that the communication with BT module was successful or not
  • Fetch current longitude and latitude values from GPS modules via BT app and send all the checkpoints to the destination via BT app and BT module to master and verify the link between GPS/Compass, master and BT module and Application is working as expected.
  • PCB design not finished yet.
  • Back sensor interfaced.
7 11/20/2017 11/25/2017
  • Display speedometer, longitude and direction values
  • Mount sensors on new/final hardware solution, position them properly and test again received data while car is in move.
  • If the link between Geo, BT, master and Motor module is working, perform outdoor system testing.
  • PCB design finished and main PCB board ordered
  • Still waiting for sensor mounts 3D printing to be finished.
8 11/26/2017 12/01/2017
  • Connect battery output to ADC channel and read back the battery parameters.
  • Interface Head lights and turn them ON based on light sensor value.
  • Implement automatic bluetooth connection between APP and bluetooth module
  • Sensor breakout PCB design and ordered
9 12/03/2017 12/08/2017
  • Display the battery parameters on LCD.
  • Perform round 1 of system testing.
  • Start documenting project report by collaborating artifacts produced during project development.
  • Fix the bugs in system testing.
10 12/10/2017 12/12/2017
  • Perform round 2 of system testing.
  • Start documenting project report by collaborating artifacts produced during project development.
  • Fix the bugs in system testing.
11 12/13/2017 12/16/2017
  • Perform round 3 of system testing.
  • Work on unfinished project report documentation.
  • Fix the bugs in system testing.
12 12/17/2017 12/19/2017
  • Perform round 4 of system testing.
  • Fix the bugs in system testing.
  • Record a video to demonstrate project working and features.
  • Complete Documentation of wiki page.
13 12/20/2017
  • Ready for Demo.

Parts List & Cost

Item# Part Desciption Vendor Qty Cost
1 RC Car - Traxxas 1/10 Slash 2WD Amazon 1 $189.95
2 Battery - Traxxas 7600mAh 7.4V 2-Cell 25C LiPo Battery Amazon 2 $143.26
3 Charger - Traxxas 2970 EZ-Peak Plus 4-Amp NiMH/LiPo Fast Charger Amazon 1 $49.95
4 GPS - Readytosky Ublox NEO-M8N GPS Module Amazon 1 $29.98
5 Bluetooth Module HC-05 Amazon 1 $8.99
6 IMU SparkFun 9DoF Razor IMU M0 SparkFun 1 $49.95
7 LV Maxsonar EZ0 Ultrasonic sensors Robotshop 6 $158.7
8 RPM Sensor - Traxxas 6520 RPM Sensor Amazon 1 $10.25
9 Jumper Wires Amazon 1 $10
10 Acrylic Board MIFFLIN Acrylic Plexiglass 12 x 12 Amazon 1 $11
11 CAN tranceivers Microchip Samples 30 Free
12 SJOne Boards Provided by Preet 5 $400.0

Process Control

Progress Tracking

- For efficient progress tracking purposes, we exclusively created Milestones in GIT project repository and assigned tasks to the respective module owners.
- Milestones divided into smaller tasks and assigned to the module members.
- The task assignee had to regularly update the tasks with the impediments and useful information.
- Once the task was completed, it was dragged forward from "doing" stage to "closed" stage on the task board. In this way we were able to keep regular track on the completed and pending tasks.

Viserion task board

Unit Testing

Code review

- During the planning phase of the project we had listed a set of coding guidelines to be followed uniformly within the team. This included naming conventions, code commenting formats, committing formats etc. For example: The whole team followed the below rule while committing the code:

 Git commit – m “Modulename_Personsinitial: short description of what was added”
 Ex: if ABC wants to make a commit to GEO module ABC would:
 Git commit –m “GC_ABC: Added new file for XYZ”

- After the code has been pushed by a module member onto GIT, all the respective module members would meet up in the presence of 1 or 2 external module member and brainstorm on the written code to find code bugs, cosmetic errors, logical errors etc. The team member would then fix the bugs and push the final code.

PCB Design

Sensors Controller

Based on research done on previous projects we decided to use Maxbotix EZ0 Ultrasonic sensors due to its reliability and cost. Four sensors total are used in this project. Three front sensors and one back sensor. They are all of the same type and manufacturer. Since they are triggered at different time, every 50ms, there was no need to use different sensor with different ranging frequency.

Hardware Design

There are two PCBs on car that are involved in wiring sensors, providing them with power and collecting data from them. “Main PCB” which is directly connected to Sensor Controller and “Sensors breakout PCB” which is mounted at the front of the car as close to sensors as possible to reduce wire length that goes through air. Two PCBs are connected with 12-pin ribbon cable. The sensors are powered with 3.3V and since we had only 5V power from power bank, we had to use 3.3V voltage regulator mounted on “Sensors breakout PCB”. Providing stable input voltage for sensors was also required because of unstable reading we were getting from sensors, caused by electrical interference. Our front sensors were interfaced by ADC, so stable input voltage was a must. Back sensor was interfaced by PWM since SJOne board has only three ADC pins.

Two PCBs connection

3D Printing Design

As a really important part of hardware design, 3D printing part was fun to make. After testing sensors on different heights from the ground and different angles we noticed that best results are when sensors are mounted as closer to the ground as possible, so we came out with our own design for sensors mount. Most important thing to consider when making design was to be able to adjust tilt of the sensors since we were receiving lot of reflection from the ground with temporarly mounts we used until we got the final printed version. So in order to satisfy that requirement mount is constructed from two parts, the stand and part that holds the sensor what gave us freedom to test sensors positioning during testing phase.


3D Design for Sensor stand
3D Design for Sensor mount
Final product
Sensor Mount in action

Hardware Interface

Sensors are interfaced with combination of GPIO, ADC and PWM pins. GPIO pins are used to trigger all sensors. Three ADC pins collect output from front sensors and PWM pin collect output from back sensor. Below you can see pin layout and schematics.


Sensors Pin Layout
Pin Name Function
P2.6 Trigger for left sensor
P2.7 Trigger for right sensor
P2.8 Trigger for middle sensor
P2.9 Trigger for back sensor
P0.26 ADC input from left sensor
P1_30 ADC input from right sensor
P1_31 ADC input from middle sensor
P2_0 PWM input from back sensor
Sensors Connection Schematics

Software Design

Show your software design. For example, if you are designing an MP3 Player, show the tasks that you are using, and what they are doing at a high level. Do not show the details of the code. For example, do not show exact code, but you may show pseudocode and fragments of code. Keep in mind that you are showing DESIGN of your software, not the inner workings of it.

Implementation

This section includes implementation, but again, not the details, just the high level. For example, you can list the steps it takes to communicate over a sensor, or the steps needed to write a page of memory onto SPI Flash. You can include sub-sections for each of your component implementation.

Motor and I/O Controller

The motor controller is responsible for the steering and controlling the speed of the car. Both direction and speed of the car is controlled using the duty cycle of PWM signal. The RC car comes with a DC motor for driving the car and a servo motor for steering the vehicle. The speed of the car can also be controlled using the Electronic Speed Controller(ESC), which drives the motor based on the PWM signal. Additionally, a RPM sensor was mounted inside the DC motor bracket, to control the speed of the car based on this feedback.These modules where interfaced such that it can work solely on the command from the Master Controller. These modules are explained in further detail in the hardware interface section below.


Design and Implementation

For controlling both the DC motor and Servo motor using the SJ-one board, we require to transmit the required duty cycle. Initially the Radio Control remote provided by Traxxas was used to determine the duty cycle for speed and direction by probing it to using a Oscilloscope. Hence, based on our requirements for steering five different PWM duty cycles were captured for center, slight left, left , right and slight right positions. Before implementing speed control based on feedback, ideal speed for testing was chosen and corresponding PWM cycle was captured.

After mounting the RPM sensor, the rotations per second(rps) could be calculated as it generated a signal for every rotation of the motor shaft. Using this signal as interrupt, the rps was calculated in the 1Hz periodic function. Based on the rps value calculated every second the PWM signal sent to drive the DC motor was calculated dynamically to achieve the required rps specified by the Master controller.

Block diagram

Hardware Design

The hardware design includes the servo motor, DC motor, ESC and the SJ-one board. Both the ESC and Servo motor are connected to PWM pins on the SJ-one board for sending PWM signals to steer and drive the vehicle. The ESC is used to control the DC motor of the car.The power source for both ESC and DC motor is a LiPo battery. The servo motor, RPM sensor and other LEDs are powered using 5v from a power bank.

Hardware Interface

In this section, you can describe how your hardware communicates, such as which BUSes used. You can discuss your driver implementation here, such that the Software Design section is isolated to talk about high-level workings rather than the inner working of your project.

DC Motor

The DC motor is used to drive the vehicle using PWM signal transmitted to ESC. The DC motor in the car is provided by Traxxas and is a 12-turn brush-less motor. It can be considered as the most important part of the vehicle as it drives the vehicle ahead. The motor can be driven either in the forward direction or reverse by setting appropriate duty cycle to the ESC. In order to achieve rveerse direction, the motor has to cycle through states of neutral at least once before going into reverse.

DC Motor Pin Connection
Wires on (ESC) Description Wire Color Code
(+)ve Positive Terminal RED
(-)ve Negetive terminal BLACK

ESC

The Electronic Speed Controller is also powered on by the LiPo battery and is used to control the DC motor based on the PWM signals sent to the ESC. In the figure below it can be seen that the ESC has three color coded wires which serve as pins for PWM signal(WHITE Color), VCC(RED Color) and GND(BLACK Color).

The ESC comes with the feature of calibrating the DC motor using the EZ set button that is present. It comes with three modes namely Training mode, racing mode and Sport mode and also with low voltage detection. For our project we initially used the training mode and then shifted to the Sport mode because we needed full capability of the motor for uphills and rough terrains.

ESC Pin Connection
S.No Wires on (ESC) Description Wire Color Code
1. (+)ve Connects to DC Motor (+)ve RED
2. (-)ve Connects to DC Motor (-)ve BLACK
3. (+)ve Connects to (+)ve of Battery RED
4. (-)ve Connects to (-)ve of Battery BLACK
5. P2.1 (PWM2) PWM Signal From SJOne WHITE
6. NC NC RED
7. (-)ve Negetive terminal BLACK

Servo

The servo motor is used to steer the vehicle based on commands received from the master controller. The servo motor is powered on using 5V power supply via PCB from the power-bank. The servo motor also has three pins which serve as pins for PWM signal(WHITE Color), VCC(RED Color) and GND(BLACK Color). The PWM pin configured to supply steering signal on the SJ-one board is connected to the PWM pin on the servo. We have used PWM signals at 120Hz, the values were sent for the five different positions as per the Master controller commands.

Servo Motor Pin Connection
Pin No. (SJOne Board) Function Wire Color Code
P2.3 (PWM4) PWM Signal WHITE
VCC 5 Volts RED
GND 0 volts BLACK

RPM Sensor

Software Design

Show your software design. For example, if you are designing an MP3 Player, show the tasks that you are using, and what they are doing at a high level. Do not show the details of the code. For example, do not show exact code, but you may show pseudocode and fragments of code. Keep in mind that you are showing DESIGN of your software, not the inner workings of it.

Steering Control

Steering control flowchart

Speed Control

Drive Control

Consistent speed based on feedback

The design section can go over your hardware and software design. Organize this section using sub-sections that go over your design and implementation.


Implementation

This section includes implementation, but again, not the details, just the high level. For example, you can list the steps it takes to communicate over a sensor, or the steps needed to write a page of memory onto SPI Flash. You can include sub-sections for each of your component implementation.

Master Controller

The master controller is the brain of the car. It communicates over CAN bus with other modules to receive data. It accepts the values of different sensors mounted in front and rear, and takes decision based on this data. It uses heartbeat mechanisms to keep a check on other modules in the system. The entire module has two main algorithms : one for Obstacle Avoidance and another for Navigation.

Hardware Design

This module was interfaced with Microchip CAN transceiver MCP2551 to communicate with other nodes in the bus. No external peripherals were connected to the master controller.
The figure below shows the hardware design of the master.
CmpE243 F17 MasterHardwareDesign.jpg

Software Design

Main flow of Master controller

CMPE243 F17 Master Mainflow.jpg

Obstacle Avoidance

CMPE243 F17 Viserion ObstacleAvoidanceAlgorithm.jpg

Directions And Steering Signals

CMPE243 F17 Viserion GPSAlgorithm.jpg

Testing Challenges

Testing

Technical Challenges

Implementation

The master has to coordinate with other nodes and take decisions. To achieve this, we have used a state machine. The master takes specific decisions depending upon the state in which the car is. We have used five states : initial state, send start, get distance and heading angle, get sensor values and stop car state.

Initial State: The car will not move till all the initialization is done. The car will wait till it receives a start signal from bluetooth module.
Send Start State: In this state, the master will send a start signal to all the modules and wait till this message is transmitted over the CAN bus.
Get Distance and Heading Angle State: The master receives the heading,bearing angles and the direction from the geo module and then switches to other state.
Get Sensor Values State: The master will check for sensor values. Once it receives the values, master has to make a decision either to avoid obstacle or to go in the direction of the checkpoint.The master will go from 'get sensor values state' and 'get distance and heading angle state' till it reaches the destination or in other words, it reaches the stop state.
Stop Car State: The car goes to this state when it receives stop signal from bluetooth module or when it receives Destination reached message from the Geo module. In this state, the master will send a stop car signal to all the other modules.Once the stop signal is sent, the car will go back to initial state where it will wait for start message from the bluetooth module.
CmpE243 F17 MasterStateMachine.jpg

Bluetooth Controller And Android Application

Design And Implementation

The user selects a destination on the android application which then communicates with the Bluetooth module HC-05 through which car gets to know the route to destination. The user can directly interact with the car using the android application so this is one of the most important modules. The detailed software and hardware design is mentioned in below sub sections.

Hardware Design

This includes
• SJ-One Board
• Bluetooth Module HC-05
• Android Smartphone
• CAN transceiver

Bluetooth Module

Bluetooth Module -HC 05

Specifications
• Bluetooth protocol: Bluetooth Specification v2.0+EDR
• Frequency: 2.4GHz ISM band
• Speed: Asynchronous: 2.1Mbps(Max) / 160 kbps, Synchronous: 1Mbps/1Mbps
• Profiles: Bluetooth serial port
• Power supply: +3.3VDC 50mA
• Working temperature: -20 ~ +75Centigrade
• Dimension: 26.9mm x 13mm x 2.2 mm
• Modulation: GFSK(Gaussian Frequency Shift Keying)
• Sensitivity: ≤-84dBm at 0.1% BER
• Security: Authentication and encryption

Bluetooth And SJOne Board Connection Diagram

Bluetooth Communication

Hardware Interface

The Bluetooth module HC05 is connected to Bluetooth-ECU using UART3. The transmission rate is 9600bps. Bluetooth-ECU communicates with all other ECU's using CAN-Transceiver.The following pins where used for connections.

Bluetooth-ECU

Function On ECU Pin NO On ECU Function On HC05
RX P4_28 TX
TX P4_29 RX

Software Design

Flowchart for Data Processing and Transmitting in BT Module





















Bluetooth Module

Android App Flow for sending Co-ordinates to Car
















Android Application

Implementation

Testing

Technical Challenges

Geographical Controller

Design And Implementation

The Geographical controller acts as the navigation unit for the Viserion. It communicates with the attached GPS and compass unit over UART interfaces. It determines the location of the car in terms of Latitude and Longitude and figures out the car's direction with respect to Magnetic North axis. The Geo controller sends the Car's current location to BT application and then receives the source to destination check points, back from the BT application. Geo module periodically calculates the bearing angle with respect to the destination (subsequent checkpoints) and it sends the bearing angle and the compass angle to master module to steer the car towards the destination.

Hardware Design

The components included in Geo Module are as follows
• SJ-One Board
• GPS Module
• Compass Module
• CAN transceiver

The following block diagram captures how the GPS and Compass modules are interfaced with Geographical Controller.

Block Diagram for Geo Module

Software Design

Software flow diagram for Geo Module

Components

Accuracy of Compass and GPS module is of paramount importance, to successfully navigate the car towards the destination. The compass module is sensitive to the magnetic interference generated from the other components on the car and thus needs to be calibrated to compensate those interfaces. GPS module offers different configuration such as baud rate, selection of positioning systems etc, The module needs to be configured using u-center application from UBlocks.

Compass Module

The Sparkfun's SEN-14001 9DOF Razor's MPU-9250 module has ability to detect linear acceleration, angular rotation velocity and magnetic field vectors using on board 3 axis sensors such as accelerometer, gyroscope and magnetometer.

Compass Calibration

The Calibration of compass module is done with the help of Arduino IDE and the Magnetometer script written using open GL framework "processing".

The Guide https://learn.sparkfun.com/tutorials/9dof-razor-imu-m0-hookup-guide
from Sparkfun walks through the steps required to setup the environment to communicate with the compass module.

We followed the following procedure to calibrate the compass module.
Note the procedure mention is with respect to the east coast, it will differ sligtly for west coast

1. Download and flash the application written by "elizabethsrobert" to output the maximum and minimum values from all the three sensors.
The firmware can be obtained from the following link
https://github.com/sparkfun/9DOF_Razor_IMU
2.Calibrating accelerometer
To calibrate the accelerometer, tune the calibration application to output the maximum and minimum readings for all the three axes from accelerometer. To calibrate X axis,Hold the accelerometer flat to the surface and rotate it along Y-axis such to get the Xmax and Xmin value. Be careful to move the accelerometer slowly so that it is not affected by the acceleration of gravity. Repeat the sequence for all the axes.
3.Calibrating Gyroscope
Keep the module stable on the surface, select the gyroscope calibration, the module will average out noise on all the axes.
4.Calibrating Magnetometer [Hard Iron effects]
Align the X-axis of the magnetometer with North pole of the earth and rotate the module along E-W axis, tilt the compass in little further in both the axes until you the max/min values are increasing. Repeat the step for all the other axes.

Offsetting Hard Iron Effects

5.Magnetic declination
The true magnetic north pole is deviated by +13.22 degrees as of December 18,2017, consider the declination values to calibrate the compass. The following Picture shows the magnetic declination at sanjose. Magnetic Declination Calculator http://www.magnetic-declination.com

Magnetic Declination at San Jose

6. Feed all the calculated values back to the application written by "elizabethsrobert to output the calibrated pitch,roll,yaw values. The Yaw value points to the Y axis of Magneto meter which provides the Head angle of compass with respect to the magnetic north.

GPS Module

Ublox Ready to Sky
The GPS module is the core unit of the car that is responsible to accurately navigate the car to it's destination based on the Latitude and Longitude values it provide. Choosing the right, stable and a good GPS module is crucial for the car's ultimate working. If the GPS used is of cheap quality then there are lot's of trouble in it's calibration and navigation. Investing in a right GPS module is the most important thing for the team and car's functioning. After a lot of study and understanding the previous projects we decided to select the Ublox GPS chip[1]

There are some modules available that have incorporated the Ublox GPS chip and created a product that can be directly used by the user in their system with minimum technical challenges. We also decided to go with one such module. Readytosky Ublox NEO-M8N GPS Module w/ Built-in HMC5883L Compass Protective Case with GPS Antenna Mount[2]




Why we selected Ublox GPS module?

The very first reason is the quality and technical support provided by the Ublox. Also the Ublox module was available on Amazon at a fairly good price. Having a good review on internet across various websites, it was seen that this module found its application use in many projects including quad copters and drones. This significantly shows that how stable, good and reliable the module is.


Some of the technical features of the module are:

The NEO-M8 series utilizes concurrent reception of up to three GNSS systems (GPS/Galileo together with BeiDou or GLONASS), recognizes multiple constellations simultaneously and provides outstanding positioning accuracy in scenarios where urban canyon or weak signals are involved. For even better and faster positioning improvement, the NEO-M8 series supports augmentation of QZSS, GAGAN and IMES together with WAAS, EGNOS, MSAS. The NEO-M8 series also supports message integrity protection, geofencing, and spoofing detection with configurable interface settings to easily fit to customer applications. The NEO form factor allows easy migration from previous NEO generations. The NEO-M8M is optimized for cost sensitive applications, while NEO-M8N/M8Q provides best performance and easier RF integration. The NEO-M8N offers high performance also at low power consumption levels. The future-proof NEO-M8N includes an internal Flash that allows future firmware updates. This makes NEO-M8N perfectly suited to industrial and automotive applications.


Support for the GPS module:

Apart from this the Ublox provides user with a Software frame work called the U-center. u-center evaluation software provides system integrators and end users with a quick and simple way to interface with u-blox GNSS chipsets, modules and boards. It enables easy evaluation, performance testing, development and debugging of GNSS positioning chips and modules. u-center allows easy connection to u-blox products and provides a suite of features to view, log, and analyze performance.

Ucenter: Software Package for Configuration of GPS



GPS Calibration

The GPS module that is received from the vendor is not calibrated or configured. Directly using the module in the car would result in lot of technical challenges and problems. We first need to understand our application use case and then configure and calibrate the GPS as per our requirement.


Now what exactly are we looking in terms of configuration/calibration for the GPS module?

The GPS module by default has multiple GNSS (GPS, Galileo, GLONASS and BeiDou) constellations active. Also there are other Augmentation systems(SBAS, QZSS, IMES, D-GPS) that are active. There are different NMEA protocol (GPGGA, GLL, GSV, GST, RMC, etc) messages that are simultaneously received as well. The baud rate is at different speed (9600 default) for the UART communication.

To have the GPS module perfectly work for the autonomous car requirement we had to do many configurations including.

1-Setting the NMEA messages to GPGGA format

2-Increasing the baud rate to 115200

3-Activating the pedestrian mode

4-Refresh rate of the GPS to 10Hz

5-Using the GNSS constellation of choice. We used all the constellations so as to get a deferentially corrected position,there by increasing the accuracy


For detailed configuration settings refer the U-center guide [3]


GNSS configuration of GPS


Pedestrian mode configuration of GPS


NMEA configuration of GPS

Implementation

Algorithm

Sequence diagram for Geo Module

Testing

Performance Analysis of Compass

1. Compare the performance with the off-shelf compass module. Make the heading angle given by compass module by rotating the compass, turn off the compass module, Place an off-shelf compass module exactly at the same place (direction same as pointed by Y axis of Magnetometer) note down the reading, rotate the compass by 90 degrees and repeat the same procedure. If the difference in all the readings is in within single digit, the performance of the compass is satisfactory.

Technical Challenges

Testing & Technical Challenges

Describe the challenges of your project. What advise would you give yourself or someone else if your project can be started from scratch again? Make a smooth transition to testing section and described what it took to test your project.

Include sub-sections that list out a problem and solution, such as:

<Bug/issue name>

Discuss the issue and resolution.

Conclusion

Conclude your project here. You can recap your testing and problems. You should address the "so what" part here to indicate what you ultimately learnt from this project. How has this project increased your knowledge?

Project Video

Upload a video of your project and post the link here.

Project Source Code

References

Acknowledgement

Any acknowledgement that you may wish to provide can be included here.

References Used

List any references used in project.

Appendix

You can list the references you used.