Zalophus's DesignHouse

Wii 리모컨(Wiimote)으로 RC Car 조종하기 - 2WS (Tamiya M-03) 본문

Arduino

Wii 리모컨(Wiimote)으로 RC Car 조종하기 - 2WS (Tamiya M-03)

Zalophus Dokdo 2016. 6. 27. 17:03
반응형

이젠 벽돌이 되어버린 니텐도 Wii를 되살리기 차원에서 Wii 리모컨을 사용하여 RC Car를 조종하는 프로젝트를 시작해봅니다.

Source를 수정하여 Tamiya M-03 샤시에 적용해 보기로 했습니다.


Circuit@Home에서 소개 받았습니다!

RC car controlled by Wii Remote on Arduino http://www.circuitsathome.com/mcu/rc-car-controlled-by-wii-remote-on-arduino



USB Host를 적용하여 Bluetooth로 직접 연결하는 방식이기 때문에 구성은 매우 간단합니다.

Arduino는 Nano를 사용하였고 USB Host Shield와 연결하기 위해 Mother Board를 하나 꾸며보았습니다.

기능도 조금 추가했습니다.


바나나를 던지거나 하지는 못하지만 "A" 버튼을 누르면 레이저가 발사되듯이 Fire LED가 켜지도록 하였고 "+" 버튼은 Head Light, "-" 버튼은 Back Light로 사용할 수 있도록 하였습니다.

그리고 좌우방향 버튼으로도 Steering이 가능하도록 하였습니다.



 Arrow Up

 Left steering

 Arrow Down

 Right steering

 Arrow Left

 Gear Down

 Arrow Right

 Gear Up

 A

 Fire & Shutting

 B

 -

 +

 Head Light

 -

 Back Light

 1

 Backward

 2

 Forward

 Home

 Throttle mode change


하드웨어 (Hardware)


송신기 (Transmitter)

  • Wii 리모컨 (Wiimote)


수신기 (Reciver)

  • Arduino Nano




  • USB Host Shield
  • Bluetooth USB 어댑터 (Dongle)



  • DIY Mother Board


통신 거리는 Bluetooth 특성상 대략 10m 정도 밖에 안될 거라고 예상합니다만 그 이상도 충분합니다.



RC Car

  • Tamiya M-03




소프트웨어 (Software)


Arduino 용 라이브러리와 스케치를 포함한 파일은 github 에 있습니다. 
이 라이브러리는 Richard Ibbotson이 만든 코드 wiiblue.pde 을 기반으로하고 있습니다.


샘플 스케치 (Sketch)


TwoWheelSterringWii.ino


#include "WiiRemote.h"


#include <MemoryFree.h>

#include <Servo.h>


#define PIN_STEERING_SIGNAL        2

#define PIN_ESC_SIGNAL             4


#define PIN_HEAD_LIGHT_SIGNAL     14

#define PIN_BACK_LIGHT_SIGNAL     15


#define PIN_FIRE_SIGNAL           17


#define PIN_STEERING_SELECT       16


#define SERIAL_DEBUG               0    // 0: active mode, 1: serial debug mode


enum eAngle

{

  STEERING_ANGLE_MAX           = 165,   // to right

  STEERING_ANGLE_CENTER        = 90,

  STEERING_ANGLE_MIN           = 15,    // to left

  STEERING_ANGLE_STEP          = 5,


  STEERING_ANGLE_MAX_INVERT    = 165,   // to right

  STEERING_ANGLE_CENTER_INVERT = 90,

  STEERING_ANGLE_MIN_INVERT    = 15,    // to left


  THROTTLE_ANGLE_MAX           = 160,   // 80,

  THROTTLE_ANGLE_CENTER        = 90,

  THROTTLE_ANGLE_MIN           = 10,

};


enum eServoPulse

{

  SERVO_PULSE_MAX              = 2400,  // to left

  SERVO_PULSE_NEUTRAL          = 1550,  // 1500 Futaba compatible, 1.55msec

  SERVO_PULSE_MIN              = 600,   // to right


  SERVO_PULSE_MAX_INVERT       = 600,   // to right

  SERVO_PULSE_NEUTRAL_INVERT   = 1450,  // 1460 Futaba compatible, 1.55msec

  SERVO_PULSE_MIN_INVERT       = 2400,  // to left

};


enum eESCPulse

{

/*

 *  Futaba timing

 *

 *  0us     1072us         1522us          1922us

 *   +---------*------------+-*-+-------------*

 *   |   n/a   |   forwad   |d|d|   Reverse   |

 *   +---------*------------+-*-+-------------*

 *          Max Forwad     Neutral         Max Reverse

 *

 *   d: dead zone, +10us and -10us

 */

  ESC_PULSE_NEUTRAL     = 1522,

  ESC_PULSE_BRAKE       = 1600,

  ESC_PULSE_FWD_MAX     = 800,   //1200, // 1072

  ESC_PULSE_FWD_MIN     = 1510,

  ESC_PULSE_FWD_3RD     = (ESC_PULSE_FWD_MIN - 240),

  ESC_PULSE_FWD_2ND     = (ESC_PULSE_FWD_MIN - 160),

  ESC_PULSE_FWD_1ST     = (ESC_PULSE_FWD_MIN - 80),


  ESC_PULSE_REV_MAX     = 1700,  // 1922

  ESC_PULSE_REV_FIX     = 1650,

  ESC_PULSE_REV_MIN     = 1600,

};


enum eGear

{

  GEAR_1ST = 1,

  GEAR_2ND = 2,

  GEAR_3RD = 3,

};


WiiRemote wiiremote;


Servo SteeringServo;

Servo ESC;


void setup()

{

#if SERIAL_DEBUG

  Serial.begin(115200);


  Serial.print("\r\nfreeMemory() reports: ");

  Serial.print(freeMemory(), DEC);

  Serial.println("Serial connect...");

#endif


  SteeringServo.attach(PIN_STEERING_SIGNAL);

  SteeringServo.writeMicroseconds(SERVO_PULSE_NEUTRAL);


  ESC.attach(PIN_ESC_SIGNAL);

  ESC.writeMicroseconds(ESC_PULSE_NEUTRAL);


  pinMode(PIN_HEAD_LIGHT_SIGNAL, OUTPUT);

  pinMode(PIN_BACK_LIGHT_SIGNAL, OUTPUT);

  digitalWrite(PIN_HEAD_LIGHT_SIGNAL, LOW);

  digitalWrite(PIN_BACK_LIGHT_SIGNAL, LOW);


  pinMode(PIN_FIRE_SIGNAL, OUTPUT);

  digitalWrite(PIN_FIRE_SIGNAL, LOW);


  pinMode(PIN_STEERING_SELECT, INPUT);

  digitalWrite(PIN_STEERING_SELECT, LOW);


  wiiremote.init();


  /*

  unsigned char wiiremote_bdaddr[6] = {0x00, 0x1e, 0x35, 0xda, 0x48, 0xbc};

  wiiremote.setBDAddress(wiiremote_bdaddr, 6);

  wiiremote.setBDAddressMode(BD_ADDR_FIXED);

  */


#if SERIAL_DEBUG

  Serial.println("Wiimote connecting...");

  Serial.println("Please press 1 button and 2 button simultaneously");

#endif

}


void loop()

{

  wiiremote.task(&myapp);

}


int steering_angle          = STEERING_ANGLE_CENTER;

int steering_angle_invert   = STEERING_ANGLE_CENTER_INVERT;

int old_steering_angle      = STEERING_ANGLE_CENTER;

bool analog_throttle        = false;  // false = use "One" button as throttle

int throttle_angle          = THROTTLE_ANGLE_CENTER;

int gear                    = GEAR_1ST;

int pulse_steering;

int pulse_esc;

bool fire                   = false;                  // fire

bool head_light             = false;                  // head light

bool back_light             = false;                  // back light


void myapp(void)

{

#if SERIAL_DEBUG

  Serial.print("\r\n");

#endif


  /* Steering */

  steering_angle = getSteeringAngle();

  steering_angle_invert = getSteeringAngleInvert();

  if (digitalRead(PIN_STEERING_SELECT) == HIGH) {

    pulse_steering = map(steering_angle,

                         STEERING_ANGLE_MIN, STEERING_ANGLE_MAX,

                         SERVO_PULSE_MAX, SERVO_PULSE_MIN);

    SteeringServo.writeMicroseconds(pulse_steering);

  } else {

    pulse_steering = map(steering_angle_invert,

                         STEERING_ANGLE_MIN_INVERT, STEERING_ANGLE_MAX_INVERT,

                         SERVO_PULSE_MAX_INVERT, SERVO_PULSE_MIN_INVERT);

    SteeringServo.writeMicroseconds(pulse_steering);

  }

  if (wiiremote.buttonPressed(WIIREMOTE_UP)) {

    steering_angle = STEERING_ANGLE_MIN;

    steering_angle_invert = STEERING_ANGLE_MIN_INVERT;

    if (digitalRead(PIN_STEERING_SELECT) == HIGH) {

      pulse_steering = map(steering_angle, STEERING_ANGLE_MIN, STEERING_ANGLE_MAX, SERVO_PULSE_MAX, SERVO_PULSE_MIN);

      SteeringServo.writeMicroseconds(pulse_steering);

    } else {

      pulse_steering = map(steering_angle_invert, STEERING_ANGLE_MIN_INVERT, STEERING_ANGLE_MAX_INVERT, SERVO_PULSE_MAX_INVERT, SERVO_PULSE_MIN_INVERT);

      SteeringServo.writeMicroseconds(pulse_steering);

    }

  } else if (wiiremote.buttonPressed(WIIREMOTE_DOWN)) {

    steering_angle = STEERING_ANGLE_MAX;

    steering_angle_invert = STEERING_ANGLE_MAX_INVERT;

    if (digitalRead(PIN_STEERING_SELECT) == HIGH) {

      pulse_steering = map(steering_angle, STEERING_ANGLE_MIN, STEERING_ANGLE_MAX, SERVO_PULSE_MAX, SERVO_PULSE_MIN);

      SteeringServo.writeMicroseconds(pulse_steering);

    } else {

      pulse_steering = map(steering_angle_invert, STEERING_ANGLE_MIN_INVERT, STEERING_ANGLE_MAX_INVERT, SERVO_PULSE_MAX_INVERT, SERVO_PULSE_MIN_INVERT);

      SteeringServo.writeMicroseconds(pulse_steering);

    }

  }


#if SERIAL_DEBUG

  Serial.print("\tServo=");

  Serial.print(pulse_steering);

#endif


  /* Brake and Throttle */

  if (wiiremote.buttonPressed(WIIREMOTE_ONE)) {

    if (pulse_esc < ESC_PULSE_NEUTRAL) {

      // moving forward before press "One"

      brake();

      pulse_esc = ESC_PULSE_NEUTRAL;

    } else {

      // while stopping or moving backward, keep moving backward

      pulse_esc = ESC_PULSE_REV_FIX;

    }

  } else {

    if (analog_throttle) {

      throttle_angle = getThrottleAngle();

      pulse_esc = map(throttle_angle,

                      THROTTLE_ANGLE_MIN, THROTTLE_ANGLE_MAX,

                      ESC_PULSE_FWD_MIN, ESC_PULSE_FWD_MAX);

    } else if (wiiremote.buttonPressed(WIIREMOTE_TWO)) {

      switch (gear) {

       case GEAR_1ST:

        pulse_esc = ESC_PULSE_FWD_1ST;

        break;

       case GEAR_2ND:

        pulse_esc = ESC_PULSE_FWD_2ND;

        break;

       case GEAR_3RD:

        pulse_esc = ESC_PULSE_FWD_3RD;

        break;

       default:

        pulse_esc = ESC_PULSE_NEUTRAL;

        break;

      }

    } else {

      pulse_esc = ESC_PULSE_NEUTRAL;

    }

  }

  ESC.writeMicroseconds(pulse_esc);

  //delay(15);

#if SERIAL_DEBUG

  Serial.print("\tESC=");

  Serial.print(pulse_esc);

#endif


  /* Throttle mode */

  if (wiiremote.buttonClicked(WIIREMOTE_HOME)) {

    analog_throttle = !analog_throttle;

    if (analog_throttle) {

      wiiremote.setLED(WIIREMOTE_LED4); // analog mode

    } else {

      wiiremote.setLED(WIIREMOTE_LED1); // fixed mode, 1st gear

      gear = GEAR_1ST;

    }

  }


  /* Shift up or down */

  if (!analog_throttle) {

    if (wiiremote.buttonClicked(WIIREMOTE_RIGHT)) {

      shiftUp();

    } else if (wiiremote.buttonClicked(WIIREMOTE_LEFT)) {

      shiftDown();

    }

  }


  /* Fire */

  if (wiiremote.buttonPressed(WIIREMOTE_A)) {

    digitalWrite(PIN_FIRE_SIGNAL, HIGH);

  } else {

    digitalWrite(PIN_FIRE_SIGNAL, LOW);

  }


  /* Head light LED */

  if (wiiremote.buttonClicked(WIIREMOTE_PLUS)) {

    head_light = !head_light;

    if (head_light) {

      digitalWrite(PIN_HEAD_LIGHT_SIGNAL, HIGH);

    } else {

      digitalWrite(PIN_HEAD_LIGHT_SIGNAL, LOW);

    }

  }


  /* Back light LED */

  if (wiiremote.buttonClicked(WIIREMOTE_MINUS)) {

    back_light = !back_light;

    if (back_light) {

      digitalWrite(PIN_BACK_LIGHT_SIGNAL, HIGH);

    } else {

      digitalWrite(PIN_BACK_LIGHT_SIGNAL, LOW);

    }

  }


} // myapp


int getSteeringAngle(void)

{

  double rad;

  int deg;


  rad = acos((double) wiiremote.Report.Accel.Y);

  deg = (int) (rad * 180.0 / PI);


  /* clipping */

  if (deg > STEERING_ANGLE_MAX) { deg = STEERING_ANGLE_MAX; }

  if (deg < STEERING_ANGLE_MIN) { deg = STEERING_ANGLE_MIN; }


  return deg;

}


int getSteeringAngleInvert(void)

{

  double rad;

  int deg;


  rad = acos((double) wiiremote.Report.Accel.Y);

  deg = (int) (rad * 180.0 / PI);


  /* clipping */

  if (deg > STEERING_ANGLE_MAX_INVERT) { deg = STEERING_ANGLE_MAX_INVERT; }

  if (deg < STEERING_ANGLE_MIN_INVERT) { deg = STEERING_ANGLE_MIN_INVERT; }


  return deg;

}


int getThrottleAngle(void)

{

  double rad;

  double compensate_z;

  int deg;


  rad = asin((double) wiiremote.Report.Accel.Y);

  compensate_z = (double) wiiremote.Report.Accel.Z / cos(rad);


  rad = asin(compensate_z);

  deg = (int) (rad * 180.0 / PI);


  /* clipping */

  if (deg > THROTTLE_ANGLE_MAX) { deg = THROTTLE_ANGLE_MAX; }

  if (deg < THROTTLE_ANGLE_MIN) { deg = THROTTLE_ANGLE_MIN; }


  return deg;

}


inline void brake(void)

{

  ESC.writeMicroseconds(ESC_PULSE_BRAKE);

  delay(15);

  ESC.writeMicroseconds(ESC_PULSE_NEUTRAL);

  delay(15);

}


inline void shiftUp(void)

{

  if (gear < GEAR_3RD) {

    gear++;

    wiiremote.setLED( (WIIREMOTE_LED1 << (gear - GEAR_1ST)) );

  }

}


inline void shiftDown(void)

{

  if (gear > GEAR_1ST) {

    gear--;

    wiiremote.setLED( (WIIREMOTE_LED1 << (gear - GEAR_1ST)) );

  }

}



반응형

'Arduino' 카테고리의 다른 글

28BYJ-48 Stepper Motor  (0) 2016.12.23
Wii 리모컨(Wiimote)으로 RC Car 조종하기  (1) 2016.06.15
Comments