본문으로 바로가기
728x90
728x90

1. EEPROM에 값을 저장하고 읽기

 

 

 

 

EEPROM에 특정 값을 쓰고 읽기

 

 

 

////////////////////  EEPROM 데이터 쓰기/읽기

#include <EEPROM.h>

#define EEPROM_TEST_FLOAT     240 // 테스트용 데이터 저장 시작 위치(offset)
#define EEPROM_TEST_INT1      (EEPROM_TEST_FLOAT + 4) // 실수형= 4바이트
#define EEPROM_TEST_INT2      (EEPROM_TEST_INT1 + 2)  // 정수형= 2바이트

//////////////// 테스트 데이터 (실수4 + 정수2 + 정수2 = 8바이트)

float FloatData = 3.14; // 실수형 데이터는 4바이트 차지함
int   Integer1Data = -12345; // 정수형 데이터는 2바이트 차지함
unsigned int   Integer2Data = 65535; // 0 ~ 65535 (2바이트)

void  WriteData() // EEPROM에 데이터 쓰기
{
  // 데이터 유형에 따라 자동으로 저장할 때 --> put 함수 사용
  
  EEPROM.put( EEPROM_TEST_FLOAT, FloatData );
  EEPROM.put( EEPROM_TEST_INT1, Integer1Data );

  // 데이터를 1-BYTE 단위로 분리해서 저장할 때 --> write 함수 사용
  
  byte  byte0 = Integer2Data & 0x00FF;  // 하위 바이트
  byte  byte1 = (Integer2Data & 0xFF00) >> 8; // 상위 바이트

  EEPROM.write( EEPROM_TEST_INT2 + 0, byte0 );
  EEPROM.write( EEPROM_TEST_INT2 + 1, byte1 );
}

void  ReadData()  // EEPROM에 저장된 데이터 읽기
{
  // 데이터 유형에 따라 자동으로 값을 읽을 때 --> get 함수 사용
  
  EEPROM.get( EEPROM_TEST_FLOAT, FloatData );
  EEPROM.get( EEPROM_TEST_INT1, Integer1Data );

  // 데이터를 BYTE 단위로 분리해서 값을 읽을 때 --> read 함수 사용
 
  byte  byte0 = EEPROM.read( EEPROM_TEST_INT2 + 0 );
  byte  byte1 = EEPROM.read( EEPROM_TEST_INT2 + 1 );

  Integer2Data = ((unsigned int)byte1 << 8) + byte0;
}

////////////////////  메인 프로그램 (setup & loop)

void setup() 
{
  Serial.begin( 9600 ); // 시리얼 통신 속도 설정

  Serial.print( "Writing values to EEPROM : " );
  WriteData(); // EEPROM에 데이터 쓰기
  Serial.println( "done!" );

  // EEPROM에 쓴 값들을 읽기 전에 모두 0으로 초기화
  FloatData = 0.0;
  Integer1Data = 0;
  Integer2Data = 0;
  Serial.println( "All values are initialized to 0." );
  
  Serial.print( "Reading values from EEPROM : " );
  ReadData();  // EEPROM에 저장된 데이터 읽기
  Serial.println( "done!" );
  
  Serial.print( "FloatData= " );  // 읽은 데이터 값들 출력
  Serial.print( FloatData );
  Serial.print( ", Integer1Data= " );
  Serial.print( Integer1Data );
  Serial.print( ", Integer2Data= " );
  Serial.println( Integer2Data );
  Serial.println();
}

void loop()
{
}

 

 

 

2. EEPROM 활용 - 바퀴모터 성능 조정값

 

모터 성능비율을 사용하여 직진성 보정하기

 

 

 

모터 성능 보정을 위한 EEPROM 데이터 저장 구조

 

 

 

 

 

 

 

 

////////////////////  EEPROM 데이터 쓰기/읽기

#include <EEPROM.h>

#define EEPROM_BASE           0
#define EEPROM_DATA_VER0      (EEPROM_BASE + 0)  // 'V'
#define EEPROM_DATA_VER1      (EEPROM_BASE + 1)  // '1'
#define EEPROM_DATA_VER2      (EEPROM_BASE + 2)  // '0'
#define EEPROM_DATA_VER3      (EEPROM_BASE + 3)  // '0'

#define EEPROM_PRODUCT_SN     (EEPROM_BASE + 4)  // Reserved
#define EEPROM_POWER_RATIOF   (EEPROM_BASE + 8)  // 1.00, 1.00
#define EEPROM_POWER_RATIOR   (EEPROM_BASE + 16) // Reserved
#define EEPROM_POWER_ADJUST   (EEPROM_BASE + 24) // Reserved

boolean IsEepromDataValid = false;

boolean CheckEepromDataHeader()
{
  if( (EEPROM.read( EEPROM_DATA_VER0 ) == 'V') &&
      (EEPROM.read( EEPROM_DATA_VER1 ) == '1') &&
      (EEPROM.read( EEPROM_DATA_VER2 ) == '0') &&
      (EEPROM.read( EEPROM_DATA_VER3 ) == '0') )
      return  true;

  return  false;
}

/////////////  좌/우 바퀴모터 속력 보정비율 (속력 = 파워 * 보정비율)

// 전진 속력 보정비율 [0 .. 1], 대부분 [0.94 ~ 1.00] 사이로 설정함
// 성능이 나쁜쪽을 1.0으로, 좋은쪽 비율을 균형에 맞도록 낮게 설정합니다.
float Power1RatioF = 1.0;  // 왼쪽 모터 (기본= 1.0)
float Power2RatioF = 0.9;  // 오른쪽 모터 (기본= 1.0)

void  ReadPowerRatio()  // EEPROM에 저장된 모터 성능비율 읽기
{
  EEPROM.get( EEPROM_POWER_RATIOF, Power1RatioF );
  EEPROM.get( EEPROM_POWER_RATIOF + 4, Power2RatioF );
}

////////////////////  부저 핀 번호

#define pinBuzzer     3 // 부저 핀 번호

////////////////////  출발/정지 버튼

#define pinBtnUp      A3  // 위쪽(UP, 앞쪽) 버튼 핀 번호

////////////////////  모터 1번(왼쪽)과 2번(오른쪽)

#define pinDIR1   7 // 1번(왼쪽)모터 방향 지정용 연결 핀
#define pinPWM1   5 // 1번(왼쪽)모터 속력 지정용 연결 핀

#define pinDIR2   8 // 2번(오른쪽)모터 방향 지정용 연결 핀
#define pinPWM2   6 // 2번(오른쪽)모터 속력 지정용 연결 핀

////////////////////  모터 회전 동작

#define FORWARD   0 // 전진 방향
#define BACKWARD  1 // 후진 방향

void  drive(int dir1, int power1, int dir2, int power2)
{
  boolean dirHighLow1, dirHighLow2;
  int     p1, p2;

  if(dir1 == FORWARD)  // 1번(왼쪽)모터 방향
    dirHighLow1 = HIGH;
  else // BACKWARD
    dirHighLow1 = LOW;
  p1 = power1 * Power1RatioF;
  
  if(dir2 == FORWARD)  // 2번(오른쪽)모터
    dirHighLow2 = LOW;
  else // BACKWARD
    dirHighLow2 = HIGH;
  p2 = power2 * Power2RatioF;
  
  digitalWrite(pinDIR1, dirHighLow1);
  analogWrite(pinPWM1, p1);

  digitalWrite(pinDIR2, dirHighLow2);
  analogWrite(pinPWM2, p2);
}

void  Forward( int power )  // 전진
{
  drive(FORWARD, power, FORWARD, power);
}

void  Backward( int power )  // 후진
{
  drive(BACKWARD, power, BACKWARD, power);
}

void  TurnLeft( int power )  // 좌회전
{
  drive(BACKWARD, power, FORWARD, power);
}

void  TurnRight( int power )  // 우회전
{
  drive(FORWARD, power, BACKWARD, power);
}

void Stop()  // 정지
{
  analogWrite(pinPWM1, 0);
  analogWrite(pinPWM2, 0);
}

////////////////////  메인 프로그램 (setup & loop)

void setup() 
{
  // 모터 제어 핀들을 모두 출력용으로 설정
  
  pinMode( pinDIR1, OUTPUT ); // 1번(왼쪽)모터 방향 핀
  pinMode( pinPWM1, OUTPUT ); // 1번(왼쪽)모터 속력 핀

  pinMode( pinDIR2, OUTPUT ); // 2번(오른쪽)모터 방향 핀
  pinMode( pinPWM2, OUTPUT ); // 2번(오른쪽)모터 속력 핀
 
  pinMode(pinBuzzer, OUTPUT); // 부저 핀을 출력 핀으로 설정
  
  pinMode(pinBtnUp, INPUT);  // 버튼 핀을 입력용 핀으로 설정

  Serial.begin( 9600 ); // 시리얼 통신 속도 설정
  
  Stop(); // 정지

  // EEPROM에 저장되어 있는 데이터(좌우 모터와 바닥면의 IR 조정값) 읽기
  if( IsEepromDataValid = CheckEepromDataHeader() )
  {
    // 이전에 EEPROM에 저장된 올바른 데이터가 있음
    
    ReadPowerRatio(); // 좌우 모터 속도 조정 비율값 읽기
    
    Serial.print( "Power1RatioF= " );
    Serial.print( Power1RatioF );      // 왼쪽 모터 성능 비율
    Serial.print( ", Power2RatioF= " );
    Serial.println( Power2RatioF );    // 오른쪽 모터 성능 비율
  }
  else
  {
    Serial.println( "Data not found from EEPROM." );
  }
  
  tone( pinBuzzer, 262 ); // 초기화가 끝났음을 "도미솔" 음 재생
  delay( 150 );
  tone( pinBuzzer, 330 );
  delay( 150 );
  tone( pinBuzzer, 392 ); 
  delay( 250 );
  noTone( pinBuzzer );  // 스피커/부저 끄기(음소거)
}

bool  DoMove = false; // 주행(=1) 또는 정지(=0)

void loop()
{
  if( digitalRead(pinBtnUp) == 0 ) // 버튼이 눌림
  {
    if( DoMove )  // 주행 중이면 정지시킴
    {
      Stop();
      
      tone( pinBuzzer, 330 ); // "미"
      delay( 100 );
      tone( pinBuzzer, 262 ); // "도"
      delay( 250 );
      noTone( pinBuzzer );
    }
      
    while( digitalRead(pinBtnUp) == 0 ) // 버튼이 올려질 때 까지 대기
      delay( 10 );

    DoMove = ! DoMove;
    
    if( DoMove )
    {
      tone( pinBuzzer, 262 ); // "도"
      delay( 100 );
      tone( pinBuzzer, 330 ); // "미"
      delay( 250 );
      noTone( pinBuzzer );
      
      Forward( 80 ); // 주행 속력 (80= 약간 느리게, 120= 약간 빠르게)
    }
  }
}

 

 

 

3. EEPROM 활용 - IR센서 감도 조정값

 

IR센서 보정 값을 사용하여 흑백(명암)값 보정하기

 

 

 

 

 

 

 

 

////////////////////  EEPROM 데이터 쓰기/읽기

#include <EEPROM.h>

#define EEPROM_BASE           0
#define EEPROM_DATA_VER0      (EEPROM_BASE + 0)  // 'V'
#define EEPROM_DATA_VER1      (EEPROM_BASE + 1)  // '1'
#define EEPROM_DATA_VER2      (EEPROM_BASE + 2)  // '0'
#define EEPROM_DATA_VER3      (EEPROM_BASE + 3)  // '0'

#define EEPROM_PRODUCT_SN     (EEPROM_BASE + 4)  // Reserved
#define EEPROM_POWER_RATIOF   (EEPROM_BASE + 8)  // 1.00, 1.00
#define EEPROM_POWER_RATIOR   (EEPROM_BASE + 16) // Reserved
#define EEPROM_POWER_ADJUST   (EEPROM_BASE + 24) // Reserved

// 라인트레이싱용 IR 센서 보정값
#define EEPROM_LT_THRESHOLD   (EEPROM_BASE + 28) // LeftIR, RightIR

boolean IsEepromDataValid = false;

boolean CheckEepromDataHeader()
{
  if( (EEPROM.read( EEPROM_DATA_VER0 ) == 'V') &&
      (EEPROM.read( EEPROM_DATA_VER1 ) == '1') &&
      (EEPROM.read( EEPROM_DATA_VER2 ) == '0') &&
      (EEPROM.read( EEPROM_DATA_VER3 ) == '0') )
      return  true;

  return  false;
}

/////////////  좌/우 바퀴모터 속력 보정비율 (속력 = 파워 * 보정비율)

// 전진 속력 보정비율 [0 .. 1], 대부분 [0.94 ~ 1.00] 사이로 설정함
// 성능이 나쁜쪽을 1.0으로, 좋은쪽 비율을 균형에 맞도록 낮게 설정합니다.
float Power1RatioF = 1.00;  // 왼쪽 모터 (기본= 1.0)
float Power2RatioF = 1.00;  // 오른쪽 모터 (기본= 1.0)

void  ReadPowerRatio()  // EEPROM에 저장된 모터 성능비율 읽기
{
  EEPROM.get( EEPROM_POWER_RATIOF, Power1RatioF );
  EEPROM.get( EEPROM_POWER_RATIOF + 4, Power2RatioF );
}

//////////  라인트레이싱용 IR 흑백 판정 기준 : 백=[0 ~ 1023]=흑

int LineTrace1Threshold = 560;  // 왼쪽 LT 흑백 초기 중간값
int LineTrace2Threshold = 560;  // 오른쪽 LT 흑백 초기 중간값

// 측정값이 (중간값 + 150) 이상일 때 확실한 검은색이라고 판단함
#define LT_THRESHOLD_SAFEZONE   150

int LineTrace1MinBlack = LineTrace1Threshold + LT_THRESHOLD_SAFEZONE;
int LineTrace2MinBlack = LineTrace2Threshold + LT_THRESHOLD_SAFEZONE;

void  ReadLtIrThreshold() // (흰색) [0 ~ 1023] (검은색)
{
  EEPROM.get( EEPROM_LT_THRESHOLD, LineTrace1Threshold );
  EEPROM.get( EEPROM_LT_THRESHOLD + 2, LineTrace2Threshold );
}

//////////////  바닥의 라인트레이스 IR센서

#define pinLT1  A6 // 1번(왼쪽) IR센서 연결 핀
#define pinLT2  A7 // 2번(오른쪽) IR센서 연결 핀

// 색상 판단: White=[0..410] .. 560 .. [710..1023]=Black
#define LT_AJDUST       60  // 현재 젤리비의 센서 측정 조정값
#define LT_MAX_WHITE   410 + LT_AJDUST // 흰색으로 판단하는 최대값
#define LT_MID_VALUE   560 + LT_AJDUST // 흑백 판단 경계값(중간값)
#define LT_MIN_BLACK   710 + LT_AJDUST // 검은색으로 판단하는 최소값

////////////////////  부저와 버튼 핀 번호

#define pinBuzzer     3  // 부저 핀 번호
#define pinButton     A3 // 버턴 핀 번호

////////////////////  모터 1번(왼쪽)과 2번(오른쪽)

#define pinDIR1   7 // 1번(왼쪽)모터 방향 지정용 연결 핀
#define pinPWM1   5 // 1번(왼쪽)모터 속력 지정용 연결 핀

#define pinDIR2   8 // 2번(오른쪽)모터 방향 지정용 연결 핀
#define pinPWM2   6 // 2번(오른쪽)모터 속력 지정용 연결 핀

////////////////////  모터 회전 동작

#define FORWARD   0 // 전진 방향
#define BACKWARD  1 // 후진 방향

void  drive(int dir1, int power1, int dir2, int power2)
{
  boolean dirHighLow1, dirHighLow2;
  int     p1, p2;

  if(dir1 == FORWARD)  // 1번(왼쪽)모터 방향
    dirHighLow1 = HIGH;
  else // BACKWARD
    dirHighLow1 = LOW;
  p1 = power1 * Power1RatioF;
  
  if(dir2 == FORWARD)  // 2번(오른쪽)모터
    dirHighLow2 = LOW;
  else // BACKWARD
    dirHighLow2 = HIGH;
  p2 = power2 * Power2RatioF;
  
  digitalWrite(pinDIR1, dirHighLow1);
  analogWrite(pinPWM1, p1);

  digitalWrite(pinDIR2, dirHighLow2);
  analogWrite(pinPWM2, p2);
}

void  Forward( int power )  // 전진
{
  drive(FORWARD, power, FORWARD, power);
}

void  Backward( int power )  // 후진
{
  drive(BACKWARD, power, BACKWARD, power);
}

void  TurnLeft( int power )  // 좌회전
{
  drive(BACKWARD, power, FORWARD, power);
}

void  TurnRight( int power )  // 우회전
{
  drive(FORWARD, power, BACKWARD, power);
}

void Stop()  // 정지
{
  analogWrite(pinPWM1, 0);
  analogWrite(pinPWM2, 0);
}

////////////////////  메인 프로그램 (setup & loop)

void setup() 
{
  // 모터 제어 핀들을 모두 출력용으로 설정
  
  pinMode( pinDIR1, OUTPUT ); // 1번(왼쪽)모터 방향 핀
  pinMode( pinPWM1, OUTPUT ); // 1번(왼쪽)모터 속력 핀

  pinMode( pinDIR2, OUTPUT ); // 2번(오른쪽)모터 방향 핀
  pinMode( pinPWM2, OUTPUT ); // 2번(오른쪽)모터 속력 핀
 
  pinMode(pinBuzzer, OUTPUT); // 부저 핀을 출력 핀으로 설정
  
  pinMode(pinButton, INPUT);  // 버튼 핀을 입력용 핀으로 설정

  pinMode( pinLT1, INPUT ); // IR 센서 입력 핀으로 설정
  pinMode( pinLT2, INPUT );

  Serial.begin( 9600 ); // 시리얼 통신 속도 설정
  
  Stop(); // 정지

  // EEPROM에 저장되어 있는 데이터(좌우 모터와 바닥면의 IR 조정값) 읽기
  if( IsEepromDataValid = CheckEepromDataHeader() )
  {
    // 이전에 EEPROM에 저장된 올바른 데이터가 있음
    
    ReadPowerRatio(); // 좌우 모터 속도 조정 비율값 읽기

    Serial.print( "Power1RatioF= " );  // 따옴표 안의 내용 출력
    Serial.print( Power1RatioF );  // 읽은 값 출력
    Serial.print( ", Power2RatioF= " );
    Serial.println( Power2RatioF );  // 읽은 값 출력 (줄넘김)
    
    ReadLtIrThreshold(); // 좌우 라인트레이싱 IR 중간값 읽기

    // B/W 중간값 보다 값이 더 클 때 검은색의 라인으로 인식할 수치 결정
    LineTrace1MinBlack = LineTrace1Threshold + LT_THRESHOLD_SAFEZONE;
    LineTrace2MinBlack = LineTrace2Threshold + LT_THRESHOLD_SAFEZONE;
    
    Serial.print( "LineTrace1Threshold= " );
    Serial.print( LineTrace1Threshold );
    Serial.print( ", LineTrace2Threshold= " );
    Serial.println( LineTrace2Threshold );
    
    Serial.print( "LineTrace1MinBlack= " );
    Serial.print( LineTrace1MinBlack );
    Serial.print( ", LineTrace2MinBlack= " );
    Serial.println( LineTrace2MinBlack );
  }
  else
  {
    Serial.println( "Data not found from EEPROM." );
  }
  
  tone( pinBuzzer, 262 ); // 초기화가 끝났음을 "도미솔" 음 재생
  delay( 150 );
  tone( pinBuzzer, 330 );
  delay( 150 );
  tone( pinBuzzer, 392 ); 
  delay( 250 );
  noTone( pinBuzzer );  // 스피커/부저 끄기(음소거)
}

bool  DoLineTrace = false; // 라인트레이싱(=1) 또는 정지(=0)

int   Power = 100; // 주행 속력 (80= 약간 느리게, 120= 빠르게)

void loop()
{
  if( digitalRead(pinButton) == 0 ) // 버튼이 눌림
  {
    if( DoLineTrace )  // 현재 라인트레이싱 중이면 정지
    {
      Stop();
      
      tone( pinBuzzer, 330 ); // "미"
      delay( 100 );
      tone( pinBuzzer, 262 ); // "도"
      delay( 250 );
      noTone( pinBuzzer );
    }
      
    while( digitalRead(pinButton) == 0 ) // 버튼이 올려질 때 까지 대기
      delay( 10 );

    DoLineTrace = ! DoLineTrace;
    
    if( DoLineTrace )  // 라인트레이싱 시작
    {
      tone( pinBuzzer, 262 ); // "도"
      delay( 100 );
      tone( pinBuzzer, 330 ); // "미"
      delay( 250 );
      noTone( pinBuzzer );
      
      Forward( Power ); // 주행 시작
    }
  }
  
  if( DoLineTrace )  // 라인트레이싱
  {
    int v1 = analogRead( pinLT1 );  // 왼쪽 IR 센서값 읽기
    int v2 = analogRead( pinLT2 );  // 오른쪽 IR 센서값 읽기
  
    if( (LineTrace1MinBlack < v1) && (LineTrace2MinBlack < v2) )
    {
      // 양쪽 IR센서 모두 검정색을 감지한 경우, (ex) 검정 교차선
      Forward( Power ); // 계속 직진
      delay( 255-Power+1 );
    }
    else if( v1 > LineTrace1MinBlack )  // 왼쪽만 검정, 좌회전
    {
      TurnLeft( Power ); // 좌회전
    }
    else if( v2 > LineTrace2MinBlack )  // 오른쪽만 검정,우회전
    {
      TurnRight( Power ); // 우회전 
    }
    else  // 양쪽 모두 흰색, 계속 전진
    {
      Forward( Power );
    }
  }
}

 

 

#define TEST_LT_IR            1 // 라인트레이싱용 IR센서 값 보기

////////////////////  EEPROM 데이터 쓰기/읽기

#include <EEPROM.h>

#define EEPROM_BASE           0
#define EEPROM_DATA_VER0      (EEPROM_BASE + 0)  // 'V'
#define EEPROM_DATA_VER1      (EEPROM_BASE + 1)  // '1'
#define EEPROM_DATA_VER2      (EEPROM_BASE + 2)  // '0'
#define EEPROM_DATA_VER3      (EEPROM_BASE + 3)  // '0'

#define EEPROM_PRODUCT_SN     (EEPROM_BASE + 4)  // Reserved
#define EEPROM_POWER_RATIOF   (EEPROM_BASE + 8)  // 1.00, 1.00
#define EEPROM_POWER_RATIOR   (EEPROM_BASE + 16) // Reserved
#define EEPROM_POWER_ADJUST   (EEPROM_BASE + 24) // Reserved

// 라인트레이싱용 IR 센서 보정값
#define EEPROM_LT_THRESHOLD   (EEPROM_BASE + 28) // LeftIR, RightIR

boolean IsEepromDataValid = false;

boolean CheckEepromDataHeader()
{
  if( (EEPROM.read( EEPROM_DATA_VER0 ) == 'V') &&
      (EEPROM.read( EEPROM_DATA_VER1 ) == '1') &&
      (EEPROM.read( EEPROM_DATA_VER2 ) == '0') &&
      (EEPROM.read( EEPROM_DATA_VER3 ) == '0') )
      return  true;

  return  false;
}

/////////////  좌/우 바퀴모터 속력 보정비율 (속력 = 파워 * 보정비율)

// 전진 속력 보정비율 [0 .. 1], 대부분 [0.94 ~ 1.00] 사이로 설정함
// 성능이 나쁜쪽을 1.0으로, 좋은쪽 비율을 균형에 맞도록 낮게 설정합니다.
float Power1RatioF = 1.00;  // 왼쪽 모터 (기본= 1.0)
float Power2RatioF = 1.00;  // 오른쪽 모터 (기본= 1.0)

void  ReadPowerRatio()  // EEPROM에 저장된 모터 성능비율 읽기
{
  EEPROM.get( EEPROM_POWER_RATIOF, Power1RatioF );
  EEPROM.get( EEPROM_POWER_RATIOF + 4, Power2RatioF );
}

//////////  라인트레이싱용 IR 흑백 판정 기준 : 백=[0 ~ 1023]=흑

int LineTrace1Threshold = 560;  // 왼쪽 LT 흑백 초기 중간값
int LineTrace2Threshold = 560;  // 오른쪽 LT 흑백 초기 중간값

// 측정값이 (중간값 + 150) 이상일 때 확실한 검은색이라고 판단함
#define LT_THRESHOLD_SAFEZONE   150

int LineTrace1MinBlack = LineTrace1Threshold + LT_THRESHOLD_SAFEZONE;
int LineTrace2MinBlack = LineTrace2Threshold + LT_THRESHOLD_SAFEZONE;

// 측정값이 (중간값 - 150) 이하일 때 확실한 흰색이라고 판단함
int LineTrace1MaxWhite = LineTrace1Threshold - LT_THRESHOLD_SAFEZONE;
int LineTrace2MaxWhite = LineTrace2Threshold - LT_THRESHOLD_SAFEZONE;

void  ReadLtIrThreshold() // (흰색) [0 ~ 1023] (검은색)
{
  EEPROM.get( EEPROM_LT_THRESHOLD, LineTrace1Threshold );
  EEPROM.get( EEPROM_LT_THRESHOLD + 2, LineTrace2Threshold );
}

//////////////  바닥의 라인트레이스 IR센서

#define pinLT1  A6 // 1번(왼쪽) IR센서 연결 핀
#define pinLT2  A7 // 2번(오른쪽) IR센서 연결 핀

// 색상 판단: White=[0..410] .. 560 .. [710..1023]=Black
#define LT_AJDUST       60  // 현재 젤리비의 센서 측정 조정값
#define LT_MAX_WHITE   410 + LT_AJDUST // 흰색으로 판단하는 최대값
#define LT_MID_VALUE   560 + LT_AJDUST // 흑백 판단 경계값(중간값)
#define LT_MIN_BLACK   710 + LT_AJDUST // 검은색으로 판단하는 최소값

////////////////////  부저와 버튼 핀 번호

#define pinBuzzer     3  // 부저 핀 번호
#define pinButton     A3 // 버턴 핀 번호

////////////////////  모터 1번(왼쪽)과 2번(오른쪽)

#define pinDIR1   7 // 1번(왼쪽)모터 방향 지정용 연결 핀
#define pinPWM1   5 // 1번(왼쪽)모터 속력 지정용 연결 핀

#define pinDIR2   8 // 2번(오른쪽)모터 방향 지정용 연결 핀
#define pinPWM2   6 // 2번(오른쪽)모터 속력 지정용 연결 핀

////////////////////  모터 회전 동작

#define FORWARD   0 // 전진 방향
#define BACKWARD  1 // 후진 방향

void  drive(int dir1, int power1, int dir2, int power2)
{
  boolean dirHighLow1, dirHighLow2;
  int     p1, p2;

  if(dir1 == FORWARD)  // 1번(왼쪽)모터 방향
    dirHighLow1 = HIGH;
  else // BACKWARD
    dirHighLow1 = LOW;
  p1 = power1 * Power1RatioF;
  
  if(dir2 == FORWARD)  // 2번(오른쪽)모터
    dirHighLow2 = LOW;
  else // BACKWARD
    dirHighLow2 = HIGH;
  p2 = power2 * Power2RatioF;
  
  digitalWrite(pinDIR1, dirHighLow1);
  analogWrite(pinPWM1, p1);

  digitalWrite(pinDIR2, dirHighLow2);
  analogWrite(pinPWM2, p2);
}

void  Forward( int power )  // 전진
{
  drive(FORWARD, power, FORWARD, power);
}

void  Backward( int power )  // 후진
{
  drive(BACKWARD, power, BACKWARD, power);
}

void  TurnLeft( int power )  // 좌회전
{
  drive(BACKWARD, power, FORWARD, power);
}

void  TurnRight( int power )  // 우회전
{
  drive(FORWARD, power, BACKWARD, power);
}

void Stop()  // 정지
{
  analogWrite(pinPWM1, 0);
  analogWrite(pinPWM2, 0);
}

////////////////////  메인 프로그램 (setup & loop)

void setup() 
{
  // 모터 제어 핀들을 모두 출력용으로 설정
  
  pinMode( pinDIR1, OUTPUT ); // 1번(왼쪽)모터 방향 핀
  pinMode( pinPWM1, OUTPUT ); // 1번(왼쪽)모터 속력 핀

  pinMode( pinDIR2, OUTPUT ); // 2번(오른쪽)모터 방향 핀
  pinMode( pinPWM2, OUTPUT ); // 2번(오른쪽)모터 속력 핀
 
  pinMode(pinBuzzer, OUTPUT); // 부저 핀을 출력 핀으로 설정
  
  pinMode(pinButton, INPUT);  // 버튼 핀을 입력용 핀으로 설정

  pinMode( pinLT1, INPUT ); // IR 센서 입력 핀으로 설정
  pinMode( pinLT2, INPUT );

  Serial.begin( 9600 ); // 시리얼 통신 속도 설정
  
  Stop(); // 정지

  // EEPROM에 저장되어 있는 데이터(좌우 모터와 바닥면의 IR 조정값) 읽기
  if( IsEepromDataValid = CheckEepromDataHeader() )
  {
    // 이전에 EEPROM에 저장된 올바른 데이터가 있음
    
    ReadPowerRatio(); // 좌우 모터 속도 조정 비율값 읽기

    Serial.println( "\n====================\n" );
    Serial.print( "Power1RatioF= " );  // 따옴표 안의 내용 출력
    Serial.print( Power1RatioF );  // 읽은 값 출력
    Serial.print( ", Power2RatioF= " );
    Serial.println( Power2RatioF );  // 읽은 값 출력 (줄넘김)
    
    ReadLtIrThreshold(); // 좌우 라인트레이싱 IR 중간값 읽기

    // B/W 중간값 보다 값이 더 클 때 검은색의 라인으로 인식할 수치 결정
    LineTrace1MinBlack = LineTrace1Threshold + LT_THRESHOLD_SAFEZONE;
    LineTrace2MinBlack = LineTrace2Threshold + LT_THRESHOLD_SAFEZONE;

    // B/W 중간값 보다 더 작을 때 확실한 흰색으로 판단할 수치 결정
    LineTrace1MaxWhite = LineTrace1Threshold - LT_THRESHOLD_SAFEZONE;
    LineTrace2MaxWhite = LineTrace2Threshold - LT_THRESHOLD_SAFEZONE;
    
    Serial.print( "1Threshold= " );
    Serial.print( LineTrace1Threshold );
    Serial.print( ", 2Threshold= " );
    Serial.println( LineTrace2Threshold );
    
    Serial.print( "1MinBlack= " );
    Serial.print( LineTrace1MinBlack );
    Serial.print( ", 2MinBlack= " );
    Serial.print( LineTrace2MinBlack );
    
    Serial.print( ", 1MaxWhite= " );
    Serial.print( LineTrace1MaxWhite );
    Serial.print( ", 2MaxWhite= " );
    Serial.println( LineTrace2MaxWhite );
  }
  else
  {
    Serial.println( "Data not found from EEPROM." );
  }
  
  tone( pinBuzzer, 262 ); // 초기화가 끝났음을 "도미솔" 음 재생
  delay( 150 );
  tone( pinBuzzer, 330 );
  delay( 150 );
  tone( pinBuzzer, 392 ); 
  delay( 250 );
  noTone( pinBuzzer );  // 스피커/부저 끄기(음소거)
}

bool  DoLineTrace = false; // 라인트레이싱(=1) 또는 정지(=0)

int   Power = 100; // 주행 속력 (80= 약간 느리게, 120= 빠르게)

void loop()
{
#if TEST_LT_IR
  if( digitalRead(pinButton) == 0 ) // 버튼이 눌림
  {
    if( DoLineTrace )  // 현재 라인트레이싱 중이면 측정 정지
      DoLineTrace = false;
    else  // 현재 라인트레이싱 중이 아니면 측정 시작
      DoLineTrace = true;
  }

  if( DoLineTrace )
  {
    int v1 = analogRead( pinLT1 );  // 왼쪽 IR 센서값 읽기
    int v2 = analogRead( pinLT2 );  // 오른쪽 IR 센서값 읽기
  
    if( (LineTrace1MinBlack < v1) && (LineTrace2MinBlack < v2) )
    { // 양쪽 IR센서 모두 검정색을 감지한 경우, (ex) 검정 교차선
      Serial.print( "[B,B] " );
      Serial.print( v1 - LineTrace1MinBlack );
      Serial.print( ", " );
      Serial.println( v2 - LineTrace2MinBlack );
    }
    else if( v1 > LineTrace1MinBlack )  // 왼쪽만 검정, 좌회전
    {
      Serial.print( "[B,W] " );
      Serial.print( v1 - LineTrace1MinBlack );
      Serial.print( ", " );
      Serial.println( LineTrace2MaxWhite - v2 );
    }
    else if( v2 > LineTrace2MinBlack )  // 오른쪽만 검정,우회전
    {
      Serial.print( "[W,B] " );
      Serial.print( LineTrace1MaxWhite - v1 );
      Serial.print( ", " );
      Serial.println( v2 - LineTrace1MinBlack );
    }
    else  // 양쪽 모두 흰색, 계속 전진
    {
      Serial.print( "[W,W] " );
      Serial.print( LineTrace1MaxWhite - v1 );
      Serial.print( ", " );
      Serial.println( LineTrace2MaxWhite - v2 );
    }
  }

  delay( 200 );
#else  
  if( digitalRead(pinButton) == 0 ) // 버튼이 눌림
  {
    if( DoLineTrace )  // 현재 라인트레이싱 중이면 정지
    {
      Stop();
      
      tone( pinBuzzer, 330 ); // "미"
      delay( 100 );
      tone( pinBuzzer, 262 ); // "도"
      delay( 250 );
      noTone( pinBuzzer );
    }
      
    while( digitalRead(pinButton) == 0 ) // 버튼이 올려질 때 까지 대기
      delay( 10 );

    DoLineTrace = ! DoLineTrace;
    
    if( DoLineTrace )  // 라인트레이싱 시작
    {
      tone( pinBuzzer, 262 ); // "도"
      delay( 100 );
      tone( pinBuzzer, 330 ); // "미"
      delay( 250 );
      noTone( pinBuzzer );
      
      Forward( Power ); // 주행 시작
    }
  }
  
  if( DoLineTrace )  // 라인트레이싱
  {
    int v1 = analogRead( pinLT1 );  // 왼쪽 IR 센서값 읽기
    int v2 = analogRead( pinLT2 );  // 오른쪽 IR 센서값 읽기
  
    if( (LineTrace1MinBlack < v1) && (LineTrace2MinBlack < v2) )
    {
      // 양쪽 IR센서 모두 검정색을 감지한 경우, (ex) 검정 교차선
      Forward( Power ); // 계속 직진
      delay( 255-Power+1 );
    }
    else if( v1 > LineTrace1MinBlack )  // 왼쪽만 검정, 좌회전
    {
      TurnLeft( Power ); // 좌회전
    }
    else if( v2 > LineTrace2MinBlack )  // 오른쪽만 검정,우회전
    {
      TurnRight( Power ); // 우회전 
    }
    else  // 양쪽 모두 흰색, 계속 전진
    {
      Forward( Power );
    }
  }
#endif  
}

 

 

아래의 소스는 EEPROM에 변수값을 저장한 루틴을 추가한 것입니다.

 

////////////////////  EEPROM 데이터 쓰기/읽기

#include <EEPROM.h>

#define EEPROM_BASE           0
#define EEPROM_DATA_VER0      (EEPROM_BASE + 0)  // 'V'
#define EEPROM_DATA_VER1      (EEPROM_BASE + 1)  // '1'
#define EEPROM_DATA_VER2      (EEPROM_BASE + 2)  // '0'
#define EEPROM_DATA_VER3      (EEPROM_BASE + 3)  // '0'

#define EEPROM_PRODUCT_SN     (EEPROM_BASE + 4)  // Reserved
#define EEPROM_POWER_RATIOF   (EEPROM_BASE + 8)  // 1.00, 1.00
#define EEPROM_POWER_RATIOR   (EEPROM_BASE + 16) // Reserved
#define EEPROM_POWER_ADJUST   (EEPROM_BASE + 24) // Reserved

// 라인트레이싱용 IR 센서 보정값
#define EEPROM_LT_THRESHOLD   (EEPROM_BASE + 28) // LeftIR, RightIR

//#define WRITE_DATA

boolean IsEepromDataValid = false;

boolean CheckEepromDataHeader()
{
  if( (EEPROM.read( EEPROM_DATA_VER0 ) == 'V') &&
      (EEPROM.read( EEPROM_DATA_VER1 ) == '1') &&
      (EEPROM.read( EEPROM_DATA_VER2 ) == '0') &&
      (EEPROM.read( EEPROM_DATA_VER3 ) == '0') )
      return  true;

  return  false;
}

/////////////  좌/우 바퀴모터 속력 보정비율 (속력 = 파워 * 보정비율)

// 전진 속력 보정비율 [0 .. 1], 대부분 [0.94 ~ 1.00] 사이로 설정함
// 성능이 나쁜쪽을 1.0으로, 좋은쪽 비율을 균형에 맞도록 낮게 설정합니다.
float Power1RatioF = 1.00;  // 왼쪽 모터 (기본= 1.0)
float Power2RatioF = 0.97;  // 오른쪽 모터 (기본= 1.0)

void  ReadPowerRatio()  // EEPROM에 저장된 모터 성능비율 읽기
{
  EEPROM.get( EEPROM_POWER_RATIOF, Power1RatioF );
  EEPROM.get( EEPROM_POWER_RATIOF + 4, Power2RatioF );
}

void  WritePowerRatio()  // EEPROM에 모터 성능비율 쓰기
{
  EEPROM.put( EEPROM_POWER_RATIOF, Power1RatioF );
  EEPROM.put( EEPROM_POWER_RATIOF + 4, Power2RatioF );
}

//////////  라인트레이싱용 IR 흑백 판정 기준 : 백=[0 ~ 1023]=흑

int LineTrace1Threshold = 590;  // 왼쪽 LT 흑백 초기 중간값
int LineTrace2Threshold = 611;  // 오른쪽 LT 흑백 초기 중간값

// 측정값이 (중간값 + 150) 이상일 때 확실한 검은색이라고 판단함
#define LT_THRESHOLD_SAFEZONE   150

int LineTrace1MinBlack = LineTrace1Threshold + LT_THRESHOLD_SAFEZONE;
int LineTrace2MinBlack = LineTrace2Threshold + LT_THRESHOLD_SAFEZONE;

void  ReadLtIrThreshold() // (흰색) [0 ~ 1023] (검은색)
{
  EEPROM.get( EEPROM_LT_THRESHOLD, LineTrace1Threshold );
  EEPROM.get( EEPROM_LT_THRESHOLD + 2, LineTrace2Threshold );
}

void  WriteLtIrThreshold() // (흰색) [0 ~ 1023] (검은색)
{
  EEPROM.put( EEPROM_LT_THRESHOLD, LineTrace1Threshold );
  EEPROM.put( EEPROM_LT_THRESHOLD + 2, LineTrace2Threshold );
}

//////////////  바닥의 라인트레이스 IR센서

#define pinLT1  A6 // 1번(왼쪽) IR센서 연결 핀
#define pinLT2  A7 // 2번(오른쪽) IR센서 연결 핀

// 색상 판단: White=[0..410] .. 560 .. [710..1023]=Black
#define LT_AJDUST       60  // 현재 젤리비의 센서 측정 조정값
#define LT_MAX_WHITE   410 + LT_AJDUST // 흰색으로 판단하는 최대값
#define LT_MID_VALUE   560 + LT_AJDUST // 흑백 판단 경계값(중간값)
#define LT_MIN_BLACK   710 + LT_AJDUST // 검은색으로 판단하는 최소값

////////////////////  부저와 버튼 핀 번호

#define pinBuzzer     3  // 부저 핀 번호
#define pinButton     A3 // 버턴 핀 번호

////////////////////  모터 1번(왼쪽)과 2번(오른쪽)

#define pinDIR1   7 // 1번(왼쪽)모터 방향 지정용 연결 핀
#define pinPWM1   5 // 1번(왼쪽)모터 속력 지정용 연결 핀

#define pinDIR2   8 // 2번(오른쪽)모터 방향 지정용 연결 핀
#define pinPWM2   6 // 2번(오른쪽)모터 속력 지정용 연결 핀

////////////////////  모터 회전 동작

#define FORWARD   0 // 전진 방향
#define BACKWARD  1 // 후진 방향

void  drive(int dir1, int power1, int dir2, int power2)
{
  boolean dirHighLow1, dirHighLow2;
  int     p1, p2;

  if(dir1 == FORWARD)  // 1번(왼쪽)모터 방향
    dirHighLow1 = HIGH;
  else // BACKWARD
    dirHighLow1 = LOW;
  p1 = power1 * Power1RatioF;
  
  if(dir2 == FORWARD)  // 2번(오른쪽)모터
    dirHighLow2 = LOW;
  else // BACKWARD
    dirHighLow2 = HIGH;
  p2 = power2 * Power2RatioF;
  
  digitalWrite(pinDIR1, dirHighLow1);
  analogWrite(pinPWM1, p1);

  digitalWrite(pinDIR2, dirHighLow2);
  analogWrite(pinPWM2, p2);
}

void  Forward( int power )  // 전진
{
  drive(FORWARD, power, FORWARD, power);
}

void  Backward( int power )  // 후진
{
  drive(BACKWARD, power, BACKWARD, power);
}

void  TurnLeft( int power )  // 좌회전
{
  drive(BACKWARD, power, FORWARD, power);
}

void  TurnRight( int power )  // 우회전
{
  drive(FORWARD, power, BACKWARD, power);
}

void Stop()  // 정지
{
  analogWrite(pinPWM1, 0);
  analogWrite(pinPWM2, 0);
}

////////////////////  메인 프로그램 (setup & loop)

void setup() 
{
  // 모터 제어 핀들을 모두 출력용으로 설정
  
  pinMode( pinDIR1, OUTPUT ); // 1번(왼쪽)모터 방향 핀
  pinMode( pinPWM1, OUTPUT ); // 1번(왼쪽)모터 속력 핀

  pinMode( pinDIR2, OUTPUT ); // 2번(오른쪽)모터 방향 핀
  pinMode( pinPWM2, OUTPUT ); // 2번(오른쪽)모터 속력 핀
 
  pinMode(pinBuzzer, OUTPUT); // 부저 핀을 출력 핀으로 설정
  
  pinMode(pinButton, INPUT);  // 버튼 핀을 입력용 핀으로 설정

  pinMode( pinLT1, INPUT ); // IR 센서 입력 핀으로 설정
  pinMode( pinLT2, INPUT );

  Serial.begin( 9600 ); // 시리얼 통신 속도 설정
  
  Stop(); // 정지


  // EEPROM에 저장되어 있는 데이터(좌우 모터와 바닥면의 IR 조정값) 읽기
  if( IsEepromDataValid = CheckEepromDataHeader() )
  {
    // 이전에 EEPROM에 저장된 올바른 데이터가 있음
    
#ifdef WRITE_DATA
  Serial.println( "Write power ratio...");
  WritePowerRatio();

  Serial.println( "Write IR threshold...");
  WriteLtIrThreshold();

#else
    ReadPowerRatio(); // 좌우 모터 속도 조정 비율값 읽기

    Serial.print( "Power1RatioF= " );  // 따옴표 안의 내용 출력
    Serial.print( Power1RatioF );  // 읽은 값 출력
    Serial.print( ", Power2RatioF= " );
    Serial.println( Power2RatioF );  // 읽은 값 출력 (줄넘김)
    
    ReadLtIrThreshold(); // 좌우 라인트레이싱 IR 중간값 읽기

#endif

    // B/W 중간값 보다 값이 더 클 때 검은색의 라인으로 인식할 수치 결정
    LineTrace1MinBlack = LineTrace1Threshold + LT_THRESHOLD_SAFEZONE;
    LineTrace2MinBlack = LineTrace2Threshold + LT_THRESHOLD_SAFEZONE;
    
    Serial.print( "LineTrace1Threshold= " );
    Serial.print( LineTrace1Threshold );
    Serial.print( ", LineTrace2Threshold= " );
    Serial.println( LineTrace2Threshold );
    
    Serial.print( "LineTrace1MinBlack= " );
    Serial.print( LineTrace1MinBlack );
    Serial.print( ", LineTrace2MinBlack= " );
    Serial.println( LineTrace2MinBlack );
  }
  else
  {
    Serial.println( "Data not found from EEPROM." );
  }
  
  tone( pinBuzzer, 262 ); // 초기화가 끝났음을 "도미솔" 음 재생
  delay( 150 );
  tone( pinBuzzer, 330 );
  delay( 150 );
  tone( pinBuzzer, 392 ); 
  delay( 250 );
  noTone( pinBuzzer );  // 스피커/부저 끄기(음소거)
}

bool  DoLineTrace = false; // 라인트레이싱(=1) 또는 정지(=0)

int   Power = 100; // 주행 속력 (80= 약간 느리게, 120= 빠르게)

void loop()
{
  if( digitalRead(pinButton) == 0 ) // 버튼이 눌림
  {
    if( DoLineTrace )  // 현재 라인트레이싱 중이면 정지
    {
      Stop();
      
      tone( pinBuzzer, 330 ); // "미"
      delay( 100 );
      tone( pinBuzzer, 262 ); // "도"
      delay( 250 );
      noTone( pinBuzzer );
    }
      
    while( digitalRead(pinButton) == 0 ) // 버튼이 올려질 때 까지 대기
      delay( 10 );

    DoLineTrace = ! DoLineTrace;
    
    if( DoLineTrace )  // 라인트레이싱 시작
    {
      tone( pinBuzzer, 262 ); // "도"
      delay( 100 );
      tone( pinBuzzer, 330 ); // "미"
      delay( 250 );
      noTone( pinBuzzer );
      
      Forward( Power ); // 주행 시작
    }
  }
  
  if( DoLineTrace )  // 라인트레이싱
  {
    int v1 = analogRead( pinLT1 );  // 왼쪽 IR 센서값 읽기
    int v2 = analogRead( pinLT2 );  // 오른쪽 IR 센서값 읽기
  
    if( (LineTrace1MinBlack < v1) && (LineTrace2MinBlack < v2) )
    {
      // 양쪽 IR센서 모두 검정색을 감지한 경우, (ex) 검정 교차선
      Forward( Power ); // 계속 직진
      delay( 255-Power+1 );
    }
    else if( v1 > LineTrace1MinBlack )  // 왼쪽만 검정, 좌회전
    {
      TurnLeft( Power ); // 좌회전
    }
    else if( v2 > LineTrace2MinBlack )  // 오른쪽만 검정,우회전
    {
      TurnRight( Power ); // 우회전 
    }
    else  // 양쪽 모두 흰색, 계속 전진
    {
      Forward( Power );
    }
  }
}

 

728x90
728x90