Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: FRDM-TFC mbed CBuffer XBEE mbed_angular_speed motor2 MMA8451Q
Fork of KL25Z_Camera_Test by
main.cpp
- Committer:
- lh14g13
- Date:
- 2016-12-07
- Revision:
- 19:65f0b6febc23
- Parent:
- 18:0095a3a8f8e4
- Child:
- 20:ed954836d028
- Child:
- 23:b234e8fb51b3
File content as of revision 19:65f0b6febc23:
//Autonomous Car GDP controller
//Written by various group members
//Commented & cleaned up by Max/Adam
//To-do
// -Change xbee transmission to non-blocking
// -Improve start/stop detection and resultant action (setting PID values?)
#include <stdarg.h>
#include <stdio.h>
#include "mbed.h"
#include "TFC.h"
#include "XBEE.h"
#include "angular_speed.h"
#include "main.h"
#include "motor.h"
// Serial
#if USE_COMMS
Serial pc(PTD3,PTD2);
XBEE xb(&pc);
#endif
// PID Timer
Timer t;
//Speed Sensors interupts and timers
InterruptIn leftHallSensor(D0);
InterruptIn rightHallSensor(D2);
Timer t1;
Timer t2;
//testing timer
Timer test;
int main() {
//Set up TFC driver stuff
TFC_Init();
ALIGN_SERVO;
#if USE_COMMS
//Setup baud rate for serial link, do not change!
pc.baud(BAUD_RATE);
#endif
//Initialise/reset PID variables
initVariables();
initSpeedSensors();
while(1) {
#if USE_COMMS
handleComms();
#endif
//If we have an image ready
if(TFC_LineScanImageReady>0) {
/* Find the bounds of the track and calculate how close we are to
* the centre */
servo_pid.measured_value = findCentreValue(CLOSE_CAMERA, left, right);
// Slow down, adjust PID values and enable differential before corners.
handleCornering();
// Run the PID controllers and adjust steering/motor accordingly
PIDController();
#if USE_COMMS
// Send the line scan image over serial
sendImage();
// Send the wheel speeds over serial
sendSpeeds();
#endif
// Check if car is at the stop line
//handleStartStop();
//Reset image ready flag
TFC_LineScanImageReady=0;
}
}
}
void initVariables() {
// Initialise three PID controllers for the servo and each wheel.
initPID(&servo_pid, 2.2f, 0.6f, 0.f);
initPID(&left_motor_pid, 0.01f, 0.f, 0.f);
initPID(&right_motor_pid, 0.01f, 0.f, 0.f);
right_motor_pid.desired_value=0;
left_motor_pid.desired_value=0;
// intialise the maximum speed interms of the angular speed.
valBufferIndex = 0;
speed = 50;
//Start stop
startstop = 0;
seen = false;
// Turning
turning = 0;
keepTurning = 0;
slow = false;
}
void initPID(pid_instance* pid, float Kp, float Ki, float Kd) {
pid->Kp = Kp;
pid->Ki = Ki;
pid->Kd = Kd;
pid->dt = 0;
pid->p_error = 0;
pid->pid_error = 0;
pid->integral = 0;
pid->measured_value = 0;
pid->desired_value = 0;
pid->derivative = 0;
}
inline float findCentreValue(volatile uint16_t * cam_data, uint8_t &l, uint8_t &r) {
diff = 0;
prev = -1;
for(i = 63; i > 0; i--) {
curr_left = (int8_t)(cam_data[i] >> 4) & 0xFF;
diff = prev - curr_left;
if(abs(diff) >= CAM_DIFF && curr_left <= CAM_THRESHOLD && prev != -1) {
l = i;
break;
}
prev = curr_left;
}
prev = -1;
for(i = 64; i < 128; i++) {
curr_right = (int8_t)(cam_data[i] >> 4) & 0xFF;
int diff = prev - curr_right;
if(abs(diff) >= CAM_DIFF && curr_right <= CAM_THRESHOLD && prev != -1) {
r = i;
break;
}
prev = curr_right;
}
//Calculate how left/right we are
return (64 - ((l+r)/2))/64.f;
}
inline void handleCornering() {
float lookaheadMeasuredValue = findCentreValue(LOOKAHEAD_CAMERA, farLeft, farRight);
measuredValBuffer[frame_counter % 64] = servo_pid.measured_value;
int count = 0;
for(i = 0; i < 10; i++) {
float val = abs(measuredValBuffer[(frame_counter - i) % 64]);
if(val > 0.09) {
count++;
}
}
if(!turning && abs(lookaheadMeasuredValue) > 0.11f){
TFC_SetMotorPWM(0.4,0.4);
}
if(turning) {
//default
//TFC_SetMotorPWM(0.4,0.4);
//dutyCycleCorner(speed,servo_pid.output);
//may want to have just to set cornering speed at different if going to be slowing down for cornering.
//dutyCycleCorner(float cornerspeed, servo_pid.output);
//dutyCycleCorner(speed, servo_pid.output);
//sensorCorner(left_motor_pid.desired_value, right_motor_pid.desired_value , servo_pid.output, 50);
}
if(abs(servo_pid.measured_value) > 0.11f){
if(!turning) {
turning = 1;
} else {
turning++;
}
} else {
if(turning) {
if(keepTurning == 0 || count > 6) {
keepTurning++;
} else {
//sendString("stop turning turned=%d",turning);
keepTurning = 0;
turning = 0;
TFC_SetMotorPWM(speed,speed);
}
}
}
}
inline float getLineEntropy() {
float entropy = 0;
float last = (int8_t)(CLOSE_CAMERA[0] >> 4) & 0xFF;
for(int i = 1; i < 128; i++) {
entropy += abs(last - ((int8_t)(CLOSE_CAMERA[i] >> 4) & 0xFF));
}
return entropy;
}
void handlePID(pid_instance *pid) {
pid->dt = t.read();
pid->pid_error = pid->desired_value - pid->measured_value;
pid->integral = pid->integral + pid->pid_error * pid->dt;
pid->derivative = (pid->pid_error - pid->p_error) / pid->dt;
pid->output = pid->Kp * pid->pid_error + pid->Ki * pid->integral + pid->Kd * pid->derivative;
pid->p_error = pid->pid_error;
if(pid->integral > 1.0f) {
pid->integral = 1.0f;
}
if(pid->integral < -1.0f) {
pid->integral = -1.0f;
}
}
inline void PIDController() {
// update motor measurements
// Read the angular velocity of both wheels
wL=Get_Speed(Time_L);
wR=Get_Speed(Time_R);
left_motor_pid.measured_value = wL;
right_motor_pid.measured_value = wR;
//PID Stuff!
t.start();
handlePID(&servo_pid);
handlePID(&left_motor_pid);
handlePID(&right_motor_pid);
if((-1.0 <= servo_pid.output) && (servo_pid.output <= 1.0))
{
TFC_SetServo(0, servo_pid.output);
}
else //Unhappy PID state
{
//sendString("out = %f p_err = %f", servo_pid.output, servo_pid.p_error);
ALIGN_SERVO;
if(servo_pid.output >= 1.0f) {
TFC_SetServo(0, 0.9f);
servo_pid.output = 1.0f;
} else {
TFC_SetServo(0, -0.9f);
servo_pid.output = -1.0f;
}
}
// need to get thepid to set the duty cycle
// need to have the desired value set0
//MOTORS
if((0<=left_motor_pid.output)&&(0<=right_motor_pid.output))
{
TFC_SetMotorPWM(left_motor_pid.output,right_motor_pid.output);
}
else
{
if(0 > right_motor_pid.output)
{
TFC_SetMotorPWM(left_motor_pid.output,0);
}
if(0 > left_motor_pid.output)
{
TFC_SetMotorPWM(0,right_motor_pid.output);
}
}
t.stop();
t.reset();
t.start();
}
inline void handleStartStop() {
//Hacky way to detect the start/stop signal
if(right - left < 60) {
sendString("START STOP!! &d",startstop);//do you mean %d?
lapTime();
//testSpeed(speed) HOLY SHIT ITS DAT BOI!!!!!!!!
if(seen) {
seen = false;
} else {
startstop++;
seen = true;
}
//If we've done 5 laps, stop the car
if(startstop >= 1) {
TFC_SetMotorPWM(0.f,0.f);
TFC_HBRIDGE_DISABLE;
startstop = 0;
}
}
}
inline void initSpeedSensors() {
t1.start();
t2.start();
//Left and Right are defined looking at the rear of the car, in the direction the camera points at.
leftHallSensor.rise(&GetTime_L);
rightHallSensor.rise(&GetTime_R);
}
void GetTime_L(){
Time_L=t1.read_us();
t1.reset();
}
void GetTime_R(){
Time_R=t2.read_us();
t2.reset();
}
#if USE_COMMS
void sendBattery() {
if(frame_counter % 256 == 0) {
float level = TFC_ReadBatteryVoltage() * 6.25;
pc.putc('J');
thing.a = level;
pc.putc(thing.bytes[0]);
pc.putc(thing.bytes[1]);
pc.putc(thing.bytes[2]);
pc.putc(thing.bytes[3]);
}
}
void sendString(const char *format, ...) {
va_list arg;
pc.putc('E');
va_start (arg, format);
pc.vprintf(format,arg);
va_end (arg);
pc.putc(0);
}
inline void sendImage() {
//Only send 1/3 of camera frames to GUI program
if((frame_counter % 3) == 0) {
pc.putc('H');
if(sendCam == 0) {
for(i = 0; i < 128; i++) {
pc.putc((int8_t)(CLOSE_CAMERA[i] >> 4) & 0xFF);
}
} else {
for(i = 0; i < 128; i++) {
pc.putc((int8_t)(LOOKAHEAD_CAMERA[i] >> 4) & 0xFF);
}
}
sendBattery();
}
frame_counter++;
}
inline void sendSpeeds() {
/*float en = getLineEntropy();
if(onTrack) {
if(en <= 14000) {
onTrack = false;
sendString("offfffffffffffff");
TFC_SetMotorPWM(0.0,0.0);
TFC_HBRIDGE_DISABLE;
}
} else {
if(en > 14000) {
onTrack = true;
sendString("ON TRACK");
}
}*/
pc.putc('B');
thing.a = wL * WHEEL_RADIUS;
pc.putc(thing.bytes[0]);
pc.putc(thing.bytes[1]);
pc.putc(thing.bytes[2]);
pc.putc(thing.bytes[3]);
thing.a = wR * WHEEL_RADIUS;
pc.putc(thing.bytes[0]);
pc.putc(thing.bytes[1]);
pc.putc(thing.bytes[2]);
pc.putc(thing.bytes[3]);
}
inline void handleComms() {
if(curr_cmd != 0) {
switch(curr_cmd) {
case 'A':
if(xb.cBuffer->available() >= 3) {
char p = xb.cBuffer->read();
char i = xb.cBuffer->read();
char d = xb.cBuffer->read();
servo_pid.Kp = p/25.0f;
servo_pid.Ki = i/25.0f;
servo_pid.Kd = d/25.0f;
sendString("pid= Kp: %f, Ki: %f, Kd: %f, p: %u, i: %u, d: %u", servo_pid.Kp, servo_pid.Ki, servo_pid.Kd, p, i, d);
curr_cmd = 0;
}
break;
case 'F':
if(xb.cBuffer->available() >= 1) {
char a = xb.cBuffer->read();
//speed = a/255;
speed = (a/0.025f)/50.f;
//TFC_SetMotorPWM(speed,speed);
sendString("s = %u %f",a, speed);
curr_cmd = 0;
}
break;
default:
// Unrecognised command
curr_cmd = 0;
break;
}
}
if(xb.cBuffer->available() > 0 && curr_cmd == 0) {
//Start car
char cmd = xb.cBuffer->read();
if(cmd == 'D') {
ALIGN_SERVO;
TFC_HBRIDGE_ENABLE;
right_motor_pid.desired_value=speed;
left_motor_pid.desired_value=speed;
servo_pid.integral = 0;
test.start();
lapNo =0;
} else if (cmd == 'C') {
TFC_SetMotorPWM(0.0,0.0);
right_motor_pid.desired_value=0;
left_motor_pid.desired_value=0;
TFC_HBRIDGE_DISABLE;
endTest();
} else if(cmd == 'A') {
curr_cmd = 'A';
} else if(cmd == 'F') {
curr_cmd = 'F';
} else if(cmd == 'K') {
sendCam = ~sendCam;
}
}
}
float testSpeed(float speed)
{
// search: Speed Increase
// every time the car sees the stop start the speed of the car will increase
// this can occur on stop start trigger.
// may need to send the speed back to the telemetry.
if (speed>0.4)
{
speed+=0.05;
}
else
{
speed+=0.1;
}
sendString("s = %f", speed);
return speed;
}
int lapTime()
{
// function which sends the lap time back to the telemetry.
float newTime= test.read();
lapNo += 1;
float lapTime= newTime-oldTime;
float avgTime= newTime/lapNo;
sendString("For lap number: %d Lap Time: %f Avergae time: %f \n\r", lapNo,lapTime,avgTime);
// OH WHAT UP IT'S DAT BOI!!!!
return 0;
}
void endTest()
{// This runs when the car has stopped, this should give the final elapsed time and othere things. this also stops the timer
float time= test.read();
sendString("Laps done: %d Time elapsed: %f Average time: %f \n\r",lapNo, time,float (time/lapNo));
test.stop();
}
#endif
