​Bluetooth Controlled- Obstacle Avoidance Robot Car Using PIC32 Microcontroller

“Robot-Car: Design Fused with Obstacle Avoidance Technology”

Recently, there is an intensive research undertaken in the field of intelligence robotics and autonomous mobile robot applications. Through the this project we wanted to explore this field by building a robot car that can potentially avoid the obstacles. This is a user controlled robot car that has been integrated with ultrasonic sensors to get the information from the surrounding area and thereby avoid any kind of obstacle collisions.This is a robot car that can be remotely controlled using a Bluetooth terminal mobile/PC application and has the capability to avoid the collision with the obstacles. Essentially when the user gives a command that can potentially lead to an obstacle collision the bot overrides his command and stops avoiding any major damage. The robot car in the project can be made to move in six directions (Forward, Backward, Front right, Front left, Back right and Back left). The system includes a PIC32 microcontroller that forms the heart of the system .The Dc motors, Bluetooth module are interfaced to the microcontroller and the data received by the Bluetooth terminal application by the user is processed by the microcontroller to perform the necessary operations.

Step 1: ​High-Level Design

Main Goals Of the Project:

1) Basic movements (forward, backward, and steering mount) and speed control

2) The body should be easy to build

3)Make it as compact as possible

4) Proximity sensing for obstacle avoidance

5) Wirelessly controlled

The robot car design structure primarily consists of PIC32MX250F128B microcontroller, one dc motor, one servomotor and four ultrasonic sensors, a dual motor driver and a Bluetooth module. The car is capable of moving in six directions (forward, Backward, forward right, forward left, backward right, backward left). Additionally the car also incorporates an obstacle avoidance feature using the proximity sensors (ultrasonic). The car is controlled wirelessly using the Bluetooth module which is mounted on the car. A mobile/Pc Bluetooth terminal application is used to send the control commands to the robot car. The hardware aspect of the car is explained in detail in the following sections.

Step 2: Figure 1: Block Diagram

Step 3: ​Hardware

The primary hardware components used in this project have been listed below:

1. Pic32mx250f128b Microcontroller

2. Hc-05 Bluetooth Module

3. Dc Motor

4. SG-90 Micro-Servo Motor

5. HC Sr-04 Ultrasonic Sensors

6. Motor Driver- L293dne

7. 4n35 Optoisolator

8. Resistors (300 O To 1k?)

9. Robot Car Chassis

10. Battery Pack (Mn604) (9v)

Step 4: PIC32MX250F128B MICROCONTROLLER

Figure 2: PIC32 Layout PIC32MX250F128B MICROCONTROLLER

align=”center”> The PIC32MX MCU series offers a rich peripheral set at a low cost for a wide range of embedded designs that require complex code and higher feature integration. The series delivers up to 50 MHz/83 DMIPS performance and provides up to 512/64 KB Flash/ RAM options. The family encompasses a wide variety of rich features including SPI/I2s, capacitive touch sensing, an enhanced Parallel Master Port (PMP), Controller Area Network (CAN), a 10-bit, 1 Msps, 48-channel Analog to-Digital Converter (ADC) and a full-speed USB 2.0 device/host/OTG module. Additionally it also consists of includes four general purpose Direct Memory Access (DMA) controllers and two dedicated DMA controllers on each CAN and USB module. The car uses a large board that encompasses the pic controller with a port expander, Digital to Analog Converter, TFT header socket, programming header plug and power supply that has been used for lab exercises as a part of this course. The project had a requisite for a large number of pins as it had to custom four ultrasonic sensors and for this reason the TFT display unit has been removed. The PIC32 microcontroller was powered by the 9V battery pack. The layout of the large board referenced from the ECE 4760 course website is shown below

Step 5: Figure 2: PIC32 Layout

Step 6: HC-05 BLUETOOTH MODULE

The Bluetooth module HC-05 is a MASTER/SLAVE module that is very easy to operate and can be used in a master or slave configuration making it a great solution for wireless communication. The Bluetooth module is interfaced to the microcontroller using serial communication (UART). The receive terminal of the Bluetooth module is connected to the transmit channel of the microcontroller and transmit channel of the microcontroller is connected to the receive end of the microcontroller. The default factory setting is SLAVE that can be modified by the AT commands. When set in the master mode the module can initiate a connection with other devices and in this way when mounted on the car the module can pair with another client for instance a smartphone. Through the use of a Bluetooth terminal on the mobile phone or the computer the user can send the data over to the target system. For this project one character of data is transmitted through the Bluetooth connection for enabling the direction control of the robot car. The primary standards that we have followed is determined by the Bluetooth Special Interest Group (SIG). The standards for Bluetooth that we have followed is set by IEEE 802.15.1. This standard essentially sets the PC addresses available for our use as well as limits our applications to the 2.4-2.485 GHz ISM band.

Step 7: ​Figure 3: HC-05 Bluetooth Module HC-05 BLUETOOTH MODULE

Step 8: DC MOTOR

The robot car constructed in this project utilizes a geared DC motor which essentially is an extension of DC motor that has a gear assembly attached to it. The DC motor works over a fair range of voltage (6V-12V) and as the input voltage increases the speed (RPM) of the motor also increases. One significant disadvantage of these class of motors is that they generate significant voltage spikes that can potentially damage the microcontroller. Two optoisolaters have been used in the circuit to provide an electrical isolation between the Dc motor and the PIC32 microcontroller. The main functionality of DC motor in this project is enable the bidirectional control of the robot car.

Step 9: Figure 4: Dc Motor

Step 10: ​MOTOR DRIVER- L293DNE

A motor driver is an integrated circuit chip that acts an interface between the microcontroller and the motors. They act as current amplifiers since they take a low-current control signal and provide a higher-current signal which is utilized to drive the motors. The most commonly used motor driver IC’s are from the L293 series such as the L293D. This IC with 16 pins consist of two H-bridges and are designed to control 2 DC motors simultaneously. The motor controller (H bridge) is typically used as a simple driver for the DC motor to turn ON and OFF in one direction and can also be used to drive the motor in both directions. Appropriate input high and input low voltage levels to enable each channel of the device. This project utilizes bidirectional control mechanism of the motor driver.

Step 11: Figure 5: Motor Driver

Step 12: 4N35 OPTOISOLATOR


The basic design of an optoisolater (4N35) consists of an LED that produces infra-red light and a semiconductor photo-sensitive device that is used to detect the emitted infra-red beam. They essentially aid in electrically isolating the microcontroller from the DC motor thereby protecting it from high voltage spikes. Basically when the input voltage of the LED is forward biased, the LED emits light and this transmitted light turns ON the photo diode which produces nearly the same voltage as the input. The two input terminals of the H-Bridge have been connected through two optoisolaters to the I/O ports of the PIC32 microcontroller.

Step 13: Figure 6: 4N35 Optoisolater

Step 14: ​SG-90 MICRO-SERVO MOTOR

Fundamentally, servomotors are electrical devices that can rotate objects at specific angles with great precision. The main components of the servomotor consists of a motor, potentiometer and a controlling circuit. The motor runs on a closed loop feedback system where by the difference in the values given to the error amplifier (one from the potentiometer which is the measured angle and the other is the true value of the angle to be reached which is given by the microcontroller) is minimized. The control signal to the servomotor is given in the form of Pulse Width Modulation by the microcontroller. The servomotor can 90 degrees in either directions from the neutral positon. Pulses of 1.5msec and 2msec will turn the motor 90 degrees and 180 degrees respectively. These pulses are given with an interval of 20msec

Step 15: SERVO MOTOR

Step 16: ​HC SR-04 ULTRASONIC SENSORS

This project utilizes four ultrasonic sensors and these are integrated into the system to enable obstacle avoidance feature in the car. Two sensors were placed on the either side of the car and one was placed on the front side and the other is placed on the backside of the car. The HC-SR04 ultrasonic module provides 2cm – 400cm non-contact measurement function with a ranging accuracy of about 3mm. The Module includes ultrasonic transmitter, receiver and a control circuit. The sensor is activated by sending a 10 μs pulse from the microcontroller. The ultrasonic sensor gives back an echo response when it detects an obstacle within the specified distance by the user.

Step 17: Figure 8: HC-SR04 Ultrasonic Sensor

Step 18: ​Voltage Divider

We have built four voltage divider circuits for the four ultrasonic sensors to reduce the 5 voltage echo pulses to 3.3V, as these echo pulses are captured by the MCU pins which are set as Input Captures (I/O pins set as Input Captures). We have designed the voltage divider with 330Ω and 1KΩ resistors as shown in the figure-9.

Step 19: ​ROBOT CAR CHASSIS

A robot chassis kit has been purchased online which is linked in the Appendix section. The chassis has been modified according to our requirement to robustly house all the hardware components. The sensors have been hot glued to the sides of the car and the hardware circuitry were soldered on the protoboards and then were mounted on to the chassis using metal clamps and screws. The microcontroller which is mounted on a large board was drilled on to the base of the car chassis. The car is three wheeled with two in the back and one in the front that essentially controls the direction in which the car moves.

Step 20: CAR CHASSIS

Step 21: SOFTWARE DESIGN

The software components of the project can be divided into the following categories:

1. Bluetooth and Serial Communication

2. Ultrasonic Sensors Setup3. Sevomotor

4. Serial Peripheral Interface

5. Signaling Algorithm

Step 22: ​Signaling Algorithm

Signaling Algorithm

The major software component of the robot car is the signaling algorithm. It has been implemented using a protothread that was ran 100 times a second to obtain good control and stability over the vehicle. A detailed description of the algorithm is mentioned below.

Step 23: Figure 11 : Signaling Algorithm Functional Diagram

Step 24:

Signaling Algorithm:

1. STOP: This state is the default state of the car, that is all states go to the STOP state before entering some other state. The STOP state is in-charge of checking of all the ultrasonic readings and to stop the car when one of the defined criteria is met. Such criteria have been set through different ‘if’ conditions based on ultrasonic sensor readings depending on the position of the car and the obstacles. Range for the ultrasonic sensors has been set as less than 200 by experimenting with the sensors in presence of an obstacle to avoid collision. If the car is in STOP state and one of the criteria is still being met and user tries to give a command that would lead to collision with an obstacle, the car remains in the STOP state to avoid collision.

2. FORWARD: This is the state that the car enters when user gives the command ‘f’ through the Bluetooth serial terminal. The car turns the wheels in the forward motion and the duty cycle of the servo is maintained at 4200 to provide front direction. As mentioned above, the STOP state is entered in between states when the system changes state. This is done to eliminate unwanted behaviors that may be caused by random/erroneous readings. The FORWARD state will continue to execute until the car is within the limits of the allowed criteria. Once the reading of the sensor goes outside the allowed value due to the detection of an obstacle by the north sensor, car immediately enters the STOP state to avoid collision.

3. BACKWARD: This state relies on the south sensor and the car enters this state when the user gives the command ‘b’ through the Bluetooth serial terminal. The car turns the wheels in the backward motion and the duty cycle of the servo is maintained at 4200 to provide back direction. The BACKWARD state will continue to execute until the car is outside the limits of the defined criteria and enters the STOP state as soon as an obstacle is close enough to the south sensor.

4. FORWARD LEFT: This is the state that the car enters when user gives the command ‘i’ through the Bluetooth serial terminal. The car turns the wheels in the forward motion and the duty cycle of the servo is maintained at 3000 to provide the left direction. The servo motor goes in left direction for 1.5seconds and changes the duty cycle back to 4200 and goes in forward direction. The time for which the duty cycle is maintained at 3000(left direction) was corroborated experimentally. This state relies on the west sensor and when the value detected by the sensor goes below 200 which is the threshold for the criteria, the car enters the STOP state.

5. FORWARD RIGHT: The car enters this state when user gives the command ‘o’ through the Bluetooth serial terminal. The car turns the wheels in the forward motion and the duty cycle of the servo is maintained at 5500 to provide the right direction. The function of FORWARD RIGHT is very similar to that of FORWARD LEFT as mentioned above except for the change in direction. This sensor relies on the east sensor and forward sensor, and when the value detected by any of the sensor goes below 200 which is the defined criteria for all sensors, the car enters the STOP state.

6. BACKWARD LEFT: The car enters this state when user gives the command ‘k’ through the Bluetooth serial terminal. The car turns the wheels in the backward direction and the duty cycle of the servo is maintained at 3000 for the left direction. Implementing the backward functions were very similar to that of forward functions as described above. The car steers to the left while moving backward for 1.5seconds and then continues in the backward direction until some obstacle is detected. In that case, the car enters the STOP state.

7. BACKWARD RIGHT: The car enters this state when the user gives the command ‘l’ through the Bluetooth serial terminal. The operation is similar to that of BACKWARD LEFT except for the direction. FLAG4 keeps track of the time since it entered this state and after 1.5seconds time duration, changes the duty cycle to 4200 and the car steers in the backward direction till any obstacle is detected.

8. CIRCULAR LEFT: The car enters this state when the user gives the command ‘q’ through the Bluetooth serial terminal. This state is used for making left U turns across a corner of the road. The servo rotates in the left direction as the duty cycle is set to 3000 and the DC Motor remains in the STOP state allowing the car to make a circular left.

9. CIRCULAR RIGHT: The car enters this state when the user gives the command ‘w’ through the Bluetooth serial terminal. This is similar to CIRCULAR LEFT as described above except for the change in direction. Using the above 9 commands, it is possible to maneuver the car in all the directions possible making the model more like an actual car.

Step 25: Bluetooth and Serial Communication Setup

The Bluetooth module is interfaced with microcontroller to wirelessly transmit the commands from the user to the robot car. In this project one character commands are sent from the Bluetooth terminal application on the PC/Mobile to the HC-05 Bluetooth module mounted on the car using the serial communication interface. The command PT_SETUP() has been used to setup the serial communication and the required baud rate for the functioning of the Bluetooth.In the protothread that has been initialized to setup the Bluetooth module the characters are received and transmitted to the remote user using the following commands:

character = UARTGetDataByte(UART2); //Store Bluetooth command in a variable

UARTSendDataByte(UART2, character); //Echo back the same command to serial terminal

The bits RB0 and RB1 on the microcontroller which essentially control the direction of rotation of the DC motor are controlled based on the character sent by the user. The duty cycle of the servomotor that controls the direction of motion of the car is also set based on the character input by the user in this protothread.

Example:

<p>if(character == 'i') //Turn left and Forward </p><p>{ flag1=0; </p><p>time1 = PT_GET_TIME(); </p><p>duty_cycle = 3000; </p><p>mPORTAClearBits(BIT_0);</p><p> mPORTASetBits(BIT_3);</p>

Step 26: ​HC-SR04 Ultrasonic Sensor Setup

The first part of ultrasonic sensor involves generation of a trigger signal from the microcontroller to initialize it. We have given the trigger signal through PWM wave that has very low frequency (10HZ) and a pulse width of 10 µs. An OpenCapture has been used for each of the four sensors to output a PWM trigger signal from the I/O ports of the microcontroller.

Example:

OpenOC5(OC_ON | OC_TIMER3_SRC | OC_PWM_FAULT_PIN_DISABLE, 10, 10);

PPSOutput(3, RPA4, OC5);

The second part of the setup involves capturing the echo signal generated by the sensor when an obstacle is encountered. For this we have utilized four input captures for four sensors respectively and declared different sub priorities to achieve coordinated functionality.

Example:

<p>OpenCapture3(IC_EVERY_FALL_EDGE | IC_INT_1CAPTURE |IC_TIMER3_SRC | IC_ON );

</p><p>ConfigIntCapture3(IC_INT_ON | IC_INT_PRIOR_2 | IC_INT_SUB_PRIOR_3);

</p><p>INTClearFlag(INT_IC3);PPSInput(2, IC3, RPB11);mPORTBSetPinsDigitalIn(BIT_11); 

</p><p>port as input (BIT_11)</p>

Step 27:

Servo Motor Setup

A basic servo motor normally has three terminals: Ground, Vcc and PWM input signal. As described in the hardware section of the project the based on the duty cycle change given by the user the direction of the servomotor changes. In this project we have once again used an OpenCapture to generate the pulse width modulation pulse with a frequency of 50HZ.

Example

OpenTimer2(T2_ON | T2_SOURCE_INT | T2_PS_1_16, 50000); // 

40000000/(50000*16)=50Hz Frequency OpenOC3(OC_ON | OC_TIMER2_SRC | OC_PWM_FAULT_PIN_DISABLE, duty_cycle, duty_cycle); 

PPSOutput(4, RPB9, OC3);

The values of the duty cycles used for the six directions have been described in detail inside the Signaling Algorithm section.

Serial Peripheral Interface Setup

For this project we had to include a Serial Peripheral Interface Setup for setting the I/O pins of the microcontroller to opencapture pins and input capture pins. This is necessary for the interfacing of the sensors and the servomotor to the PIC32 microcontroller

.PPSOutput(2, RPB5, SDO2);

mPORTBSetPinsDigitalOut(BIT_4);

mPORTBSetBits(BIT_4);

divide Fpb by 2, configure the I/O ports.

16 bit transfer CKP=1 CKE=1;

Enable SPI at 20MHz clock;SpiChnOpen(spiChn, SPI_OPEN_ON | SPI_OPEN_MODE16 | SPI_OPEN_MSTEN | ; SPI_OPEN_CKE_REV, spiClkDiv);

Step 28: ​Results

A. Accuracy

The final configuration of the car is capable of accurately moving in any one of the six directions (forward, backward, forward-right, forward-left, backward-right, backward-left) with 100% accuracy by extensive training of the car through optimization of the duty cycle. Essentially we have given a time offset of 1.5 seconds to align the servo motor in the neutral direction after turning into a particular direction. This way the turnings made by the car are precise relative to the direction it is intended to go .The performance of the car to obstacle avoidance is good with an accuracy of 80%. The car stops when the sensor (that is if the car is going in the backward direction the forward sensor doesn’t work) detects an obstacle with a range of 3.448cm despite the user giving the driving commands. However the system fails to perform in a few corner cases. When the car is supposed to make a turn alongside a boundary it detects the boundary as an obstacle and the stops. There were also instances when the hardware circuitry of the car caused a hindrance to the sensor causing false detection. This was rectified by rewiring and remounting of the hardware compactly on the chassis of the car.

Step 29:

B. Outputs of the Bluetooth:

1st is the waveform for character sent from the serial terminal to the bot 2nd is the echo from the bot to the serial terminal and this essentially the character that the user has sent.We have used this as a form of debugging to confirm whether the character has been received by the microcontroller or not. Additionally we have also utilised the bluetooth terminal as a TFT display to debug the working of the sensors by displaying a character when an obstacle is encountered.

Figure 12 : Bluetooth Diagram is shown above

1st is the waveform for character sent from the serial terminal to the bot

2nd is the echo from the bot to the serial terminal and this essentially the character that the user has sent.We have used this as a form of debugging to confirm whether the character has been received by the microcontroller or not. Additionally we have also utilised the bluetooth terminal as a TFT display to debug the working of the sensors by displaying a character when an obstacle is encountered.

Step 30: Figure 13 : Bluetooth Serial Terminal

The figure illustrates characters “f” and “b” being sent to the bluetooth module on the car for direction control

Step 31: C. Ultrasonic Sensors Output Waveforms:

Figure 14 : Ultrasonic Output Waveform When the obstacle is near the echo pulse becomes high for a duration that can be converted into distance using the formula mentioned below:

Distance (cm) = Time (Micro Seconds)/58

Step 32: ​Figure 15 : Ultrasonic Output Waveform

When the obstacle is far the echo pulse duration increases and once the proximity of the obstacle increases beyond the range of the sensor (~200cm) the sensor does not give back any echo pulse to the microcontroller.

Step 33: Figure 16 : Ultrasonic Trigger and Echo Waveforms (as Given by the Module’s Datesheet)

Step 34: Conclusions

Through the design project we were able to explore the domain of wireless communication modules like the Bluetooth, sensors etc. and their integration with the pic32 microcontroller. There exists an incredible amount of scope to expand upon this project. Some of future improvements we would like to make include designing of an autonomous parking mode and an intelligent path planning algorithm for the robot. Our design with the sensors can be improved through the utilization of their values to intelligently train the robot to perform specified tasks. Initially we also proposed to have an alternate energy source for the car. We planned to have a saline water based power source where the car runs on the voltage obtained through the electrolysis of salt water. Due to time constraints and infeasibility of the technique at this stage we had to stick to the 9v battery to power the car.

Step 35: SCHEMATIC

Step 37: Code

It is highly commented so get your idea

***************************Junaid Khan PROJECT*************************
* Title: Bluetooth Collision Avoidance Car * Authors: Junaid Khan * Target PIC: PIC32MX250F128B * Not to be distributed! */ /////////////////////////////////////////////////////////////////// // Clocks and Protothreads Configure! #include "config_1_2_2.h" // threading library #include "pt_cornell_1_2_2.h" //PORT A Internal Pull ups/Pull downs #define EnablePullDownA(bits) CNPUACLR=bits; CNPDASET=bits; #define DisablePullDownA(bits) CNPDACLR=bits; #define EnablePullUpA(bits) CNPDACLR=bits; CNPUASET=bits; #define DisablePullUpA(bits) CNPUACLR=bits; char buffer[60]; // string buffer // === thread structures ============================================ // thread control structs // note that UART input and output are threads static struct pt pt_serial; // The following threads are necessary for UART control //SPI DAC SETUP volatile SpiChannel spiChn = SPI_CHANNEL2; volatile int spiClkDiv = 2; // 20 MHz DAC clock // Variables static char character; static int duty_cycle = 4200; //Initial value for the servo motor in forward direction static int time1 = 0, time2 = 0, time3=0, time4=0; //To store timer counts static int flag1 = 0, flag2=0, flag3=0, flag4=0; //Keep track of execution loops volatile int south = 0, west = 0, north = 0, east = 0; //To capture Infrared sensor values /****** Input Capture Event Interrupt *******/ void __ISR(_INPUT_CAPTURE_1_VECTOR, ipl2) IC1Handler(void) { south = mIC1ReadCapture(); //Read Capture event for Back Sensor if((south < 200) && (mPORTAReadBits(BIT_0)==1)) { mPORTASetBits(BIT_0); mPORTASetBits(BIT_3); duty_cycle = 4200; } mIC1ClearIntFlag(); //clear Interrupt Flag } void __ISR(_INPUT_CAPTURE_4_VECTOR, ipl2) IC4Handler(void) { west = mIC4ReadCapture(); //Read Capture event for left sensor if (west <200 && (mPORTAReadBits(BIT_0)==0) && duty_cycle == 3000) //Obstacle Detection for front left { mPORTASetBits(BIT_0); mPORTASetBits(BIT_3); duty_cycle = 4200; } if (west <200 && (mPORTAReadBits(BIT_0)==1) && duty_cycle == 5500) //Obstacle detection for back right { mPORTASetBits(BIT_0); mPORTASetBits(BIT_3); duty_cycle = 4200; } mIC4ClearIntFlag(); //clear Interrupt flag } void __ISR(_INPUT_CAPTURE_5_VECTOR, ipl2) IC5Handler(void) { north = mIC5ReadCapture(); //Read Capture event for front sensor if (north <200 && (mPORTAReadBits(BIT_0)==0)) { mPORTAClearBits(BIT_0); mPORTAClearBits(BIT_3); duty_cycle = 4200; } mIC5ClearIntFlag(); //clear Interrupt flag } void __ISR(_INPUT_CAPTURE_3_VECTOR, ipl2) IC3Handler(void) { east = mIC3ReadCapture(); //Read Capture event for right sensor if (east <200 && (mPORTAReadBits(BIT_0)==0) && duty_cycle == 5500) //Obstacle detection for front right { mPORTASetBits(BIT_0); mPORTASetBits(BIT_3); duty_cycle = 4200; } if (east <200 && (mPORTAReadBits(BIT_0)==1)&& duty_cycle == 3000) //Obstacle detection for back left { mPORTASetBits(BIT_0); mPORTASetBits(BIT_3); duty_cycle = 4200; } mIC3ClearIntFlag(); //Clear Interrupt flag }//=== Serial terminal thread ========================================= //Thread for interfacing with the Bluetooth to take user input static PT_THREAD (protothread_serial(struct pt *pt)) { PT_BEGIN(pt); mPORTASetPinsDigitalOut(BIT_0 | BIT_3); //Set port as output mPORTAClearBits(BIT_0 | BIT_3); while(1) { PT_YIELD_TIME_msec(100); character = UARTGetDataByte(UART2); //Store Bluetooth command in a variable UARTSendDataByte(UART2, character); //Echo back the same command to serial terminalif(character == 'b') //Backward direction { mPORTASetBits(BIT_0); mPORTAClearBits(BIT_3); duty_cycle = 4000; } if(character == 'f') //Forward direction {mPORTASetBits(BIT_3); mPORTAClearBits(BIT_0); duty_cycle = 4200; } if(character == 's') //Stop { mPORTASetBits(BIT_0); mPORTASetBits(BIT_3); duty_cycle = 4200; } if(character == 'i') //Turn left and Forward { flag1=0; time1 = PT_GET_TIME(); duty_cycle = 3000; mPORTAClearBits(BIT_0); mPORTASetBits(BIT_3); } if((PT_GET_TIME()-time1)>1500 && flag1==0) { UARTSendDataByte(UART2, character); duty_cycle=4200; flag1=1; } if(character == 'o') //Turn right and forward { time2 = PT_GET_TIME(); flag2=0; mPORTAClearBits(BIT_0); mPORTASetBits(BIT_3); duty_cycle = 5500; } if(PT_GET_TIME()-time2>=1500 && flag2==0) { duty_cycle=4200; flag2=1; } if(character == 'k') //Turn left and backward { time3 = PT_GET_TIME(); flag3=0; mPORTASetBits(BIT_0); mPORTAClearBits(BIT_3); duty_cycle = 3000;} if(PT_GET_TIME()-time3>=1500 && flag3==0) { duty_cycle=4200; flag3=1; } if(character == 'l') //Turn right and backward { time4 = PT_GET_TIME(); flag4=0;mPORTASetBits(BIT_0); mPORTAClearBits(BIT_3); duty_cycle = 5500; } if(PT_GET_TIME()-time4>=1500 && flag4==0){ duty_cycle=4200;flag4=1; } if(character == 'q') // circular left { mPORTAClearBits(BIT_0); mPORTASetBits(BIT_3); duty_cycle = 3000; } if(character == 'w') // circular right { mPORTAClearBits(BIT_0); mPORTASetBits(BIT_3); duty_cycle = 5500; } SetDCOC3PWM(duty_cycle); } // End While(1) PT_END(pt); // End Thread } // === Main ====================================================== void main(void) { // === config threads ========== ANSELA = 0; ANSELB = 0; PT_setup(); //=== Timer Setups ========================================= // Set up Timer 2 to control Servo Motor Direction OpenTimer2(T2_ON | T2_SOURCE_INT | T2_PS_1_16, 50000); // 40000000/(50000*16)=50Hz Frequency // set up timer 3 for echo captures of all sensors through IC1,IC3,IC4,IC5 OpenTimer3(T3_ON | T3_SOURCE_INT | T3_PS_1_256, 20000); //Controls PWM Signals// back sensor Echo capture OpenCapture1(IC_EVERY_FALL_EDGE | IC_INT_1CAPTURE |IC_TIMER3_SRC | IC_ON ); // turn on the interrupt so that every capture can be recorded ConfigIntCapture1(IC_INT_ON | IC_INT_PRIOR_2 | IC_INT_SUB_PRIOR_3); INTClearFlag(INT_IC1); // connect RPB13 to IC1 capture unit PPSInput(3, IC1, RPB13);mPORTBSetPinsDigitalIn(BIT_13); // Set port as input (BIT_13)// set up compare1 for back sensor OpenOC1(OC_ON | OC_TIMER3_SRC | OC_PWM_FAULT_PIN_DISABLE, 10, 10); // // OC1 is PPS group 1, map to RPB3 PPSOutput(1, RPB3, OC1); // west sensor Echo capture OpenCapture4(IC_EVERY_FALL_EDGE | IC_INT_1CAPTURE |IC_TIMER3_SRC | IC_ON ); // turn on the interrupt so that every capture can be recorded ConfigIntCapture4(IC_INT_ON | IC_INT_PRIOR_2 | IC_INT_SUB_PRIOR_2); INTClearFlag(INT_IC4); // connect RPB7 to IC4 capture unit PPSInput(1, IC4, RPB7); mPORTBSetPinsDigitalIn(BIT_7); // Set port as input (BIT_7)// set up compare2 for west sensor OpenOC2(OC_ON | OC_TIMER3_SRC | OC_PWM_FAULT_PIN_DISABLE, 10, 10); // //OC2 is PPS group 2, map to RPB8 PPSOutput(2, RPB8, OC2);// front sensor Echo capture OpenCapture5(IC_EVERY_FALL_EDGE | IC_INT_1CAPTURE |IC_TIMER3_SRC | IC_ON ); // turn on the interrupt so that every capture can be recorded ConfigIntCapture5(IC_INT_ON | IC_INT_PRIOR_2 | IC_INT_SUB_PRIOR_1); INTClearFlag(INT_IC5); // connect RPB2 to IC5 capture unit PPSInput(3, IC5, RPB2); mPORTBSetPinsDigitalIn(BIT_2); // Set port as input (BIT_2)// set up compare4 for front sensor OpenOC4(OC_ON | OC_TIMER3_SRC | OC_PWM_FAULT_PIN_DISABLE, 10, 10); // //OC4 is PPS group 3, map to RPBA2 PPSOutput(3, RPA2, OC4);// east sensor Echo capture OpenCapture3(IC_EVERY_FALL_EDGE | IC_INT_1CAPTURE |IC_TIMER3_SRC | IC_ON ); // turn on the interrupt so that every capture can be recorded ConfigIntCapture3(IC_INT_ON | IC_INT_PRIOR_2 | IC_INT_SUB_PRIOR_3); INTClearFlag(INT_IC3); // connect RPB11 to IC3 capture unit PPSInput(2, IC3, RPB11); mPORTBSetPinsDigitalIn(BIT_11); // Set port as input (BIT_11)// set up compare5 for east sensor OpenOC5(OC_ON | OC_TIMER3_SRC | OC_PWM_FAULT_PIN_DISABLE, 10, 10); // //OC5 is PPS group 3, map to RPA4 PPSOutput(3, RPA4, OC5); //=== Setup of servo motor ========================================= // set up compare3 for PWM mode OpenOC3(OC_ON | OC_TIMER2_SRC | OC_PWM_FAULT_PIN_DISABLE, duty_cycle, duty_cycle); // // OC3 is PPS group 4, map to RPB9 PPSOutput(4, RPB9, OC3);//=== Setup of SPI ========================================= // SDO2 is in PPS output group 2 connected to RPB5 PPSOutput(2, RPB5, SDO2); // control CS for DAC mPORTBSetPinsDigitalOut(BIT_4); mPORTBSetBits(BIT_4); // divide Fpb by 2, configure the I/O ports. // 16 bit transfer CKP=1 CKE=1 // Enable SPI at 20MHz clock SpiChnOpen(spiChn, SPI_OPEN_ON | SPI_OPEN_MODE16 | SPI_OPEN_MSTEN | SPI_OPEN_CKE_REV, spiClkDiv); // === setup system wide interrupts ======== INTEnableSystemMultiVectoredInt(); //INIT the threads PT_INIT(&pt_serial); // Schedule the threads using round-robin scheduling while (1){ PT_SCHEDULE(protothread_serial(&pt_serial)); } } // main// === end ======================================================

Step 38: References

Datasheets

HC-05 Bluetooth Module: Datasheet

Ultrasonic Sensor: Datasheet

ServomotorDatasheet

Motor DriverDatasheet

4N35 OptoisolaterDatasheet

Pic32: Datasheet

Attachments

Source: ​Bluetooth Controlled- Obstacle Avoidance Robot Car Using PIC32 Microcontroller

About The Author

Muhammad Bilal

I am a highly skilled and motivated individual with a Master's degree in Computer Science. I have extensive experience in technical writing and a deep understanding of SEO practices.