Skip to content

Commit

Permalink
Merge pull request SEA-ME-Team07-Embedded-System#35 from SEA-ME-Team0…
Browse files Browse the repository at this point in the history
…7-Embedded-System/develop

merge develop to main
  • Loading branch information
junho2000 authored Nov 8, 2023
2 parents 30459b6 + 675d948 commit 89a2972
Show file tree
Hide file tree
Showing 110 changed files with 2,439 additions and 115,014 deletions.
File renamed without changes.
62 changes: 62 additions & 0 deletions arduino/front_arduino/front_arduino.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
#include <SPI.h> //Library for using SPI Communication
#include <mcp2515.h> //Library for using CAN Communication (https://github.com/autowp/arduino-mcp2515/)

struct can_frame canMsg; //canMsg struct data type for storing CAN message format.

MCP2515 mcp2515(10); //set the pin number where SPI CS is connected.

const int TRIG_PIN = 5;
const int ECHO_PIN = 6;

int ultrasonic() {
digitalWrite(TRIG_PIN, HIGH);
delayMicroseconds(10);
digitalWrite(TRIG_PIN, LOW);

long duration = pulseIn(ECHO_PIN, HIGH);

int distance_cm = duration * 0.0343 / 2;
Serial.print("Distance :");
Serial.println(distance_cm);



return distance_cm;
}

void setup()
{
canMsg.can_id = 0x063; //CAN id as 0x063
canMsg.can_dlc = 8; //CAN data length as 8
canMsg.data[0] = 0x00;
canMsg.data[1] = 0x00;
canMsg.data[2] = 0x00; //Rest all with 0
canMsg.data[3] = 0x00;
canMsg.data[4] = 0x00;
canMsg.data[5] = 0x00;
canMsg.data[6] = 0x00;
canMsg.data[7] = 0x00;

while (!Serial);
Serial.begin(9600);

pinMode(TRIG_PIN, OUTPUT); //Ultra sonic
pinMode(ECHO_PIN, INPUT); //Ultra sonic

mcp2515.reset();
mcp2515.setBitrate(CAN_125KBPS, MCP_8MHZ); //Sets CAN at speed 125KBPS
mcp2515.setNormalMode();

Serial.println("Example: Write to CAN");

delay(1000);
}
void loop() {

//ultra sonic
int d = ultrasonic();

canMsg.data[2] = d;
mcp2515.sendMessage(&canMsg); //Sends the CAN message
delay(500);
}
File renamed without changes.
144 changes: 144 additions & 0 deletions arduino/rear_arduino/rear_arduino.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,144 @@
#include <SPI.h> //Library for using SPI Communication
#include <mcp2515.h> //Library for using CAN Communication (https://github.com/autowp/arduino-mcp2515/)

struct can_frame canMsg; //canMsg struct data type for storing CAN message format.

MCP2515 mcp2515(10); //set the pin number where SPI CS is connected.

const int TRIG_PIN = 5;
const int ECHO_PIN = 6;

const byte PulsesPerRevolution = 20;
const unsigned long ZeroTimeout = 100000;
const byte numReadings = 2;

volatile unsigned long LastTimeWeMeasured;
volatile unsigned long PeriodBetweenPulses = ZeroTimeout + 1000;
volatile unsigned long PeriodAverage = ZeroTimeout + 1000;
unsigned long FrequencyRaw;
unsigned long FrequencyReal;
unsigned long RPM;
unsigned int PulseCounter = 1;
unsigned long PeriodSum;

unsigned long LastTimeCycleMeasure = LastTimeWeMeasured;
unsigned long CurrentMicros = micros();
unsigned int AmountOfReadings = 1;
unsigned int ZeroDebouncingExtra;
unsigned long readings[numReadings];
unsigned long readIndex;
unsigned long total;
unsigned long average;

int ultrasonic() {
digitalWrite(TRIG_PIN, HIGH);
delayMicroseconds(10);
digitalWrite(TRIG_PIN, LOW);

long duration = pulseIn(ECHO_PIN, HIGH);

int distance_cm = duration * 0.0343 / 2;
Serial.print("Distance :");
Serial.println(distance_cm);



return distance_cm;
}

void setup()
{
canMsg.can_id = 0x036; //CAN id as 0x036
canMsg.can_dlc = 8; //CAN data length as 8
canMsg.data[0] = 0x00;
canMsg.data[1] = 0x00;
canMsg.data[2] = 0x00; //Rest all with 0
canMsg.data[3] = 0x00;
canMsg.data[4] = 0x00;
canMsg.data[5] = 0x00;
canMsg.data[6] = 0x00;
canMsg.data[7] = 0x00;

while (!Serial);
Serial.begin(9600);

pinMode(TRIG_PIN, OUTPUT); //Ultra sonic
pinMode(ECHO_PIN, INPUT); //Ultra sonic

SPI.begin(); //Begins SPI communication
attachInterrupt(digitalPinToInterrupt(3), Pulse_Event, RISING);

mcp2515.reset();
mcp2515.setBitrate(CAN_125KBPS, MCP_8MHZ); //Sets CAN at speed 125KBPS
mcp2515.setNormalMode();

Serial.println("Example: Write to CAN");

delay(1000);
}
void loop() {

//speedometer
LastTimeCycleMeasure = LastTimeWeMeasured;
CurrentMicros = micros();
if (CurrentMicros < LastTimeCycleMeasure) {
LastTimeCycleMeasure = CurrentMicros;
}
FrequencyRaw = 10000000000 / PeriodAverage;
if (PeriodBetweenPulses > ZeroTimeout - ZeroDebouncingExtra || CurrentMicros - LastTimeCycleMeasure > ZeroTimeout - ZeroDebouncingExtra) {
FrequencyRaw = 0; // Set frequency as 0.
ZeroDebouncingExtra = 2000;
} else {
ZeroDebouncingExtra = 0;
}
FrequencyReal = FrequencyRaw / 10000;

RPM = FrequencyRaw / PulsesPerRevolution * 60;
RPM = RPM / 10000;
total = total - readings[readIndex];
readings[readIndex] = RPM;
total = total + readings[readIndex];
readIndex = readIndex + 1;

if (readIndex >= numReadings) {
readIndex = 0;
}
average = total / numReadings;

Serial.print("Period: ");
Serial.print(PeriodBetweenPulses);
Serial.print("\tReadings: ");
Serial.print(AmountOfReadings);
Serial.print("\tFrequency: ");
Serial.print(FrequencyReal);
Serial.print("\tRPM: ");
Serial.print(RPM);
Serial.print("\tTachometer: ");
Serial.println(average);

//ultra sonic
int d = ultrasonic();

int r = RPM;
canMsg.data[0] = r;
canMsg.data[1] = d;
mcp2515.sendMessage(&canMsg); //Sends the CAN message
delay(500);
}

void Pulse_Event() {
PeriodBetweenPulses = micros() - LastTimeWeMeasured;
LastTimeWeMeasured = micros();
if (PulseCounter >= AmountOfReadings) {
PeriodAverage = PeriodSum / AmountOfReadings;
PulseCounter = 1;
PeriodSum = PeriodBetweenPulses;

int RemapedAmountOfReadings = map(PeriodBetweenPulses, 40000, 5000, 1, 10);
RemapedAmountOfReadings = constrain(RemapedAmountOfReadings, 1, 10);
AmountOfReadings = RemapedAmountOfReadings;
} else {
PulseCounter++;
PeriodSum = PeriodSum + PeriodBetweenPulses;
}
}
Empty file.
Loading

0 comments on commit 89a2972

Please sign in to comment.