EmilKramborg
Published © GPL3+

Automotive speedometer for a camper

Converts mechanical speedo- and tachometer signal to digital. Display speed, rpm, trip, odometer on a LCD + "analog" speed using a servo.

IntermediateShowcase (no instructions)1,602
Automotive speedometer for a camper

Things used in this project

Hardware components

Arduino UNO
Arduino UNO
×1
Alphanumeric LCD, 16 x 2
Alphanumeric LCD, 16 x 2
×1
SG90 Micro-servo motor
SG90 Micro-servo motor
×1
Photo resistor
Photo resistor
×1
Analog to digital speedometer converter
×1

Story

Read more

Code

speedometer_only_dieseldoris

Arduino
Converts a mechanical speedometer signal to digital and displays speedometer and odometer data on a LCD display.
/* 
  "Speedometer for Diesel-Doris"
  
  Converts an aftermarket mechanical speedometer signal to digital.
  The speedometer converter output is a frequency signal (1 pulse cycle/revolution).
  The mechanical speedometer output is ~1,307 m/revolution.
  
  Emil Backram
  20 Dec 2020 - Project start  (Uno Rev.3)
  26 Dec 2020 - Succsessful lab test of basic algorithm - serial printer
  27 Dec 2020 - Succsessful lab test of basic algorithm - LCD
  29 Dec 2020 - Semi-succsessful lab test of variable contrast and back-light: 
                * Fixed setpoint back-light levels - OK
                * Variable back-light level - unstable 
                * All contrast levels inbetween ON and OFF - flickery (Note: No RC-filter!)
  07 Jan 2021 - Succsessful lab test of 
                * new basic algorithm:
                  + Added timer interrupt
                  + Count number of pulses every 250ms
                  + Calc speed using the sum of the last 4 puls counts
                * variable contrast and back-light: 
                  + Smoth back-light level transition
                  + Fixed the contrast flickering bug (digitalWrite --> analogWrite)
                  + Added RC-filter to contrast output (HW)
                * new trip and odometer meter algoritm:
                  + Store odometer data in eeprom
                  + Calculate trip data using the diff of odometer data at startup and current odometer data
  08 Jan 2021 - Rearranged #define constants in 2 groups, 'configurable' and 'non-configurable' 
  12 Jan 2021 - Fixed EEPROM read bug when > 2 bytes - cast back to 'unsigned long' 
  13 Jan 2021 - Updated comments and clarifications
              - Splited read/write from/to memory subroutine into separate read respective write subroutines
  15 Jan 2021 - Changed display delay timer from calculating "next time" using millis() to using a bool variable set in timer1 interrupt
  17 Jan 2021 - Minor updates:
                * Notes
                * Names
                * LCD visual appearance
                * Removed unused defines
                * Made eeprom read/write odometer data subroutines more generic --> unsigned long read/write subroutines
                * Moved some processing from timer1 interrupt to main loop
  22 Jan 2021 - Minor updates:
                * Activate on chip pullup for SPEED_PIN to match the hardware design
                * Use pin 9 instead of 11 for the LCD, in order to free the last usable PWM capable pin 
                  + Pin 3 and 11 use timer2 for PWM control 
                  + Pin 9 and 10 won't be used for PWM since timer1 is used for timer interrupt
  25 Jan 2021 - Added servo control for "analog" speedometer
  26 Jan 2021 - Added RPM handling
                * Display RPM on the LCD
                * "Shiftlight", LCD light blinks two times when RPM is too high or low
  27 Jan 2021 - Minor optimizations to minimize execution time and program memory space
              - Fixed minor bug for "Shiftlight"
  02 Feb 2021 - Updated shiftlight enable functionality (only enabled when vehicle speed is within a certain interval)
  18 Apr 2021 - Updated speed pulse sensor data. Test result: Mechanical speedometer wire output is 0,765 m/revolution
  20 Apr 2021 - Removed engine speed, and its related functionalities (for now, due to mechanical difficulties)
              - Fixed brain somersault: 0,765 = revolutions/m --> ~1,307 m/revolution
              - Changed interrupt trigger from RISING (1 pulse/revolution) to CHANGE (2 pulses/revolution) to increase resolution
                * ~1,307 m/revolution --> ~0,654 m/pulse
  03 May 2021 - Fixed light intensity bug (missing analog write)
              - Added floating average for vehicle speed
  18 May 2021 - Fixed floating average for vehicle speed bug
*/

/* Libraries */
#include <EEPROM.h>
#include <LiquidCrystal.h>

/* Pin definitions */
LiquidCrystal lcd(4, 7, 8, 9, 12, 13);  //Pins chosen to avoid IRQ inputs and PWM outputs (Uno)
#define SPEED_PIN         2             //Dig pin 2 = IRQ 0 (Uno)
#define LCD_CONTRAST_PIN  5             //PWM pin 5 using Timer0 (Uno)
#define LCD_LIGHT_PIN     6             //PWM pin 6 using Timer0 (Uno)
#define SERVO_PIN         11            //PWM pin 11 using Timer2 (Uno)
#define LIGHT_SENS_PIN    A0            //Analog pin 0

/* Non-configurable system-specific constants */
#define UPDATE_FREQUENCY  4       //Hz
#define OCR1A_VAL         62499   //Corresponds to UPDATE_FREQUENCY
#define BYTE_SHIFT        8       //(bits)
#define ODO_ADDR          0       //Odometer data address in eeprom
#define LCD_ROWS          2       //Number of rows in the LCD display
#define LCD_COLUMNS       16      //Number of columns in the LCD display
#define LCD_UPPER         0       //(row)
#define LCD_LOWER         1       //(row)
#define LCD_INIT_COLUMN   0       //(column)
#define LCD_HALF_COLUMN   8       //(column)
#define OCR2A_MIN         7       //Corresponds to 180 degrees @ ~61Hz (Attention!!! This works for my servo, it might damage yours! I found the limits through carefull trial and error!)
#define OCR2A_MAX         34      //Corresponds to 0 degrees @ ~61Hz (Attention!!! This works for my servo, it might damage yours! I found the limits through carefull trial and error!)

/* Configurable vehicle-specific constants */
#define M_PER_PULSE           0.654f  //(m/pulse) Using CHANGE instead of RISING for the interrupt will double the pulses per revolution
#define SPEED_MIN             5       //(km/h)
#define KPH_PER_SERVO_STEP    5       //(km/h)/step
#define LIGHT_SENS_LIMIT      300     //0-1023
#define LCD_LIGHT_MAX         255     //LCD_LIGHT_MIN-255
#define LCD_LIGHT_MIN         10      //0-LCD_LIGHT_MAX
#define LCD_CONTRAST          25      //0-255
#define STARTUP_SCREEN_DELAY  2500    //(ms)

/* Macros */
#define MIN_CONSTRAINT(X, MIN) ((X > MIN) ? X : MIN)
#define MAX_CONSTRAINT(X, MAX) ((X < MAX) ? X : MAX)
#define VAL_CONSTRAINT(X, MIN, MAX) MAX_CONSTRAINT(MIN_CONSTRAINT(X, MIN), MAX)

#define DISTANCE_CALC(X) ((X * M_PER_PULSE) / 1000.f) //Input (float)pulses, returns (km)
#define SPEED_CALC(X)    (X * M_PER_PULSE * 3.6f)     //Input (float)pulses/s, returns (km/h)

#define KPH_TO_SPEEDO_SERVO(KPH) VAL_CONSTRAINT((OCR2A_MAX - (KPH / KPH_PER_SERVO_STEP)), OCR2A_MIN, OCR2A_MAX) //Input km/h, returns PWM setpoint (OCR2A_MIN - OCR2A_MAX)

/* Global variables */
bool volatile timer1_interrupt                              = false;
byte volatile orc2a_val                                     = OCR2A_MIN;
byte volatile irq_array_cntr                                = 0;
unsigned int volatile speed_irq_cntr                        = 0;
unsigned int volatile speed_pulses_array[UPDATE_FREQUENCY]  = {0};

/* Subroutines */
void display_vehicle_data(byte, unsigned long, unsigned long);
unsigned long eeprom_read_u_long(unsigned int);
void eeprom_write_u_long(unsigned int, unsigned long);

/* Setup */
void setup()
{
  /* Pins */
  pinMode(SPEED_PIN, INPUT_PULLUP);   //Activate pullup resistor for speed interrupt pin
  pinMode(LIGHT_SENS_PIN, INPUT); 
  pinMode(LCD_LIGHT_PIN, OUTPUT); 
  pinMode(LCD_CONTRAST_PIN, OUTPUT); 
  pinMode(SERVO_PIN, OUTPUT);         //Output correspond to orc2a_val (no analogWrite() in code)

  /* Interrupts */
  attachInterrupt(digitalPinToInterrupt(SPEED_PIN), speed_isr, CHANGE); //Using CHANGE instead of RISING for the interrupt will double the pulses per revolution
  
  cli();  //Clear global Interrupts
  
  /* Timer1 */
  TCCR1A  = 0;                          //Clear register, CTC mode
  TCCR1B  = 0;                          //Clear register
  TCNT1   = 0;                          //Clear register
  OCR1A   = OCR1A_VAL;                  //Corresponds to UPDATE_FREQUENCY
  TCCR1B |= (1 << WGM12);               //CTC mode
  TCCR1B |= (1 << CS11) | (1 << CS10);  //64 prescaler, corresponds to UPDATE_FREQUENCY
  TIMSK1 |= (1 << OCIE1A);              //Output Compare A Match Interrupt Enable

  /* Timer2 (analog speed) */
  TCCR2A  = 0;                                        //Clear register
  TCCR2B  = 0;                                        //Clear register
  TCNT2   = 0;                                        //Clear register
  OCR2A   = OCR2A_MIN;                                //Initial setpoint at startup (OCR2A_MIN --> 'max' km/h)
  TCCR2A |= (1 << COM2A1);                            //Compare Output Mode (non-inverting mode)
  TCCR2A |= (1 << WGM21) | (1 << WGM20);              //Fast PWM Mode
  TCCR2B |= (1 << CS22) | (1 << CS21) | (1 << CS20);  //1024 prescaler
  TIMSK2 |= (1 << TOIE2);                             //Overflow Interrupt Enable
  
  sei();  //Set global interrupts
  
  /* LCD */
  analogWrite(LCD_CONTRAST_PIN, LCD_CONTRAST); 
  lcd.begin(LCD_COLUMNS, LCD_ROWS);
  lcd.setCursor(LCD_INIT_COLUMN, LCD_UPPER);
  lcd.print("<<<< Diesel >>>>");
  lcd.setCursor(LCD_INIT_COLUMN, LCD_LOWER);
  lcd.print("<<<< Doris  >>>>");
  analogWrite(LCD_LIGHT_PIN, LCD_LIGHT_MAX);
  delay(STARTUP_SCREEN_DELAY);
  lcd.clear();
  
  /* Analog speed (OCR2A_MAX --> 0 km/h) */
  orc2a_val = OCR2A_MAX;  
}

/* Main */
void loop()
{ 
  static bool run_once = false;
  static unsigned long accumulated_speed_pulses = 0;
  static const unsigned long init_odometer = eeprom_read_u_long(ODO_ADDR);  //Fetch latest odometer data at startup

  /* Calculate total distance (km) */
  unsigned long current_odometer = (unsigned long)DISTANCE_CALC((float)accumulated_speed_pulses) + eeprom_read_u_long(ODO_ADDR);

  /* Calculate speed (km/h) and store odometer data */
  unsigned long speed_pulses_per_s = 0;
  for(byte array_cntr = 0; array_cntr < UPDATE_FREQUENCY; array_cntr++)
  {
    speed_pulses_per_s += speed_pulses_array[array_cntr];
  }
  
  float speed_kph = SPEED_CALC((float)speed_pulses_per_s);
  if(speed_kph < SPEED_MIN)
  {
    speed_kph = 0.f;
    accumulated_speed_pulses = 0;
    if(run_once)  //Store odometer data in eeprom (only once when vehicle no longer is in motion)
    {
      eeprom_write_u_long(ODO_ADDR, current_odometer);
      run_once = false;
    }
  }
  else
  {
    run_once = true;
  }

  /* Run when enabled by timer1 interrupt (Corresponds to UPDATE_FREQUENCY) */
  if(timer1_interrupt)
  {
    static float vehicle_speed_array[UPDATE_FREQUENCY] = {0.f};
    timer1_interrupt = false; 
    accumulated_speed_pulses += speed_pulses_array[irq_array_cntr]; //Accumulate latest odometer data
    
    irq_array_cntr++;
    if(irq_array_cntr >= UPDATE_FREQUENCY)
    {
      irq_array_cntr = 0;
    }

    /* Vehicle speed average */
    vehicle_speed_array[irq_array_cntr] = speed_kph;
    float avg_speed_kph = 0;
    for(byte array_cntr = 0; array_cntr < UPDATE_FREQUENCY; array_cntr++)
    {
      avg_speed_kph += vehicle_speed_array[array_cntr];
    }
    avg_speed_kph = avg_speed_kph/(float)UPDATE_FREQUENCY;
    
    /* Display vehicle data (and calculate distance since startup (km)) */
    display_vehicle_data((byte)avg_speed_kph, (current_odometer - init_odometer), current_odometer);
  }
}

/* Display vehicle data */
void display_vehicle_data(byte vehicle_speed, unsigned long vehicle_trip, unsigned long vehicle_odometer)
{
  static byte lcd_light_intensity = 0xff;

  /* LCD light intensity setpoint */
  byte lcd_light_intensity_setpoint;
  if(analogRead(LIGHT_SENS_PIN) > LIGHT_SENS_LIMIT)
  {
    lcd_light_intensity_setpoint = LCD_LIGHT_MAX;
  }
  else
  {
    lcd_light_intensity_setpoint = LCD_LIGHT_MIN;
  }

  if(lcd_light_intensity < lcd_light_intensity_setpoint)
  {
    lcd_light_intensity++;
  }
  else if(lcd_light_intensity > lcd_light_intensity_setpoint)
  {
    lcd_light_intensity--;
  }
  analogWrite(LCD_LIGHT_PIN, lcd_light_intensity);

  /* Analog speed */
  orc2a_val = KPH_TO_SPEEDO_SERVO(vehicle_speed);

  /* LCD vehicle data */
  //No lcd.clear() to avoid display flickering. Lingering artifacts are avoided anyway in the current design
  lcd.setCursor(LCD_INIT_COLUMN, LCD_UPPER);
  lcd.print(vehicle_speed);
  lcd.print("km/h  "); //'Blank space' at the end to clear lingering artifacts when speed is decreasing
  lcd.setCursor(LCD_INIT_COLUMN, LCD_LOWER);
  lcd.print(vehicle_trip);
  lcd.print("km");
  lcd.setCursor(LCD_HALF_COLUMN, LCD_LOWER);
  lcd.print(vehicle_odometer);
  lcd.print("km");
}

/* Read unsigned long data from eeprom */
unsigned long eeprom_read_u_long(unsigned int addr)
{
  unsigned long read_value = 0;
  for(byte byte_cntr = 0; byte_cntr < sizeof(read_value); byte_cntr++)
  {
    read_value |= (unsigned long)EEPROM.read(addr + byte_cntr) << (BYTE_SHIFT * byte_cntr);
  }
  return read_value;
}

/* Write unsigned long data to eeprom */
void eeprom_write_u_long(unsigned int addr, unsigned long write_value)
{
  for(byte byte_cntr = 0; byte_cntr < sizeof(write_value); byte_cntr++)
  {
    EEPROM.update((addr + byte_cntr), (byte)(write_value >> (BYTE_SHIFT * byte_cntr)));
  }
}

/* Speed sensor ISR */
void speed_isr(void)
{
  speed_irq_cntr++;
}

/* Timer1 ISR */
ISR(TIMER1_COMPA_vect)
{
  speed_pulses_array[irq_array_cntr] = speed_irq_cntr;
  speed_irq_cntr = 0;
  timer1_interrupt = true;
}

/* Timer2 ISR */
ISR(TIMER2_OVF_vect)
{
  OCR2A = orc2a_val;
}

Credits

EmilKramborg
0 projects • 1 follower
Contact

Comments

Please log in or sign up to comment.