/* 競技用ランサーロボット 半蔵 2.1 [7 654321 0] | | | | []---{}---[] / .\ / | \ []+--{}--+[] (c)2012 kou029w - MIT License [http://kou029w.appspot.com/mit-license.txt] */ #include #include "Motor.h" //#define LINE_BLACK //白地・黒ライン有効 //#define PIN_SENSOR ( ((PINC<<2) & ~0x03) | ((PINB>>4) & 0x03) ) const unsigned int TARGET_NONE_COUNT = 85; const unsigned long LAP_COUNT = 854; const int LANCE_ANGLE0 = 0; //度 const int LANCE_ANGLE1 = 43; const int LANCE_ANGLE2 = 54; const int LANCE_ANGLE3 = -33; const int LANCE_ANGLE4 = 34; const unsigned int LANCE_INTERVAL = 70; //ms const byte SPEED_DEFAULT = 255; const int HANDLE_DEGREE_DEFAULT = 90; //度 const unsigned int HANDLE_MIN = ( 800+30); //us const unsigned int HANDLE_MAX = (2300+30); //us const int LANCE_DEGREE_DEFAULT = 90; //度 const unsigned int LANCE_MIN = 544; //us const unsigned int LANCE_MAX = 2400; //us const byte PIN_LED = 4; const byte PIN_ROT = 2; const byte PIN_SENSOR_0 = 12; const byte PIN_SENSOR_1 = 13; const byte PIN_SENSOR_2 = 14; const byte PIN_SENSOR_3 = 15; const byte PIN_SENSOR_4 = 16; const byte PIN_SENSOR_5 = 17; const byte PIN_SENSOR_6 = 18; const byte PIN_SENSOR_7 = 19; const byte PIN_SERVO_HANDLE = 10; const byte PIN_SERVO_LANCE = 9; const byte PIN_MOTOR_LEFT_1 = 5; const byte PIN_MOTOR_LEFT_2 = 7; const byte PIN_MOTOR_RIGHT_1 = 6; const byte PIN_MOTOR_RIGHT_2 = 8; const byte MODE_STOP = 0x10; const byte MODE_TRACE = 0x11; const byte MODE_LEFT = 0x12; //左カーブ const byte MODE_RIGHT = 0x13; //右カーブ const byte TARGET_NONE = 0x40; const byte TARGET_PARALLEL = 0x41; //平行標的 const byte TARGET_VERTICAL = 0x42; //垂直標的 const byte TARGET_CYLINDER = 0x43; //円筒標的 const byte MASK_MODE_TRACE = 0b01111110; const byte MASK_CHECK_MARKER = 0b10000001; const byte MASK_CHECK_MARKER_RIGHT = 0b00000001; const byte MASK_CHECK_MARKER_LEFT = 0b10000000; /**************************************/ Servo servoHandle; Servo servoLance; Motor motorR; Motor motorL; byte mode; byte target; unsigned int counterOld; char lanceAngle; /**************************************/ void trace(byte sensor){ switch( sensor & MASK_MODE_TRACE ){ case 0b01000000: handle(-20); motorMode(GO, GO, 0x40, 0xff); lanceAngle = 0; break; case 0b01100000: handle(-16); motorMode(GO, GO, 0xff, 0xff); lanceAngle = 0; break; case 0b00100000: handle(-12); motorMode(GO, GO, 0xff, 0xff); lanceAngle = 0; break; case 0b00110000: handle(-5); motorMode(GO, GO, 0xff, 0xff); break; case 0b00010000: handle(-2); motorMode(GO, GO, 0xff, 0xff); break; case 0b00011000: handle(0); motorMode(GO, GO, 0xff, 0xff); break; case 0b00001000: handle(2); motorMode(GO, GO, 0xff, 0xff); break; case 0b00001100: handle(5); motorMode(GO, GO, 0xff, 0xff); break; case 0b00000100: handle(7); motorMode(GO, GO, 0xff, 0xff); break; case 0b00000110: handle(10); motorMode(GO, GO, 0xff, 0xff); break; case 0b00000010: handle(12); motorMode(GO, GO, 0xff, 0xff); break; } } void motorMode(byte motorLeftMode, byte motorRightMode, byte motorLeftSpeed, byte motorRightSpeed){ motorL.mode( motorLeftMode, motorLeftSpeed); motorR.mode(motorRightMode, motorRightSpeed); } void handle(int degree){ servoHandle.write(HANDLE_DEGREE_DEFAULT + degree); } void lance(int degree){ servoLance.write(LANCE_DEGREE_DEFAULT - degree); } /* ロータリーエンコーダーの変化を見る todo:外部割り込み使ってみたい、、、 */ volatile unsigned long counter = 0; void count(){ static byte rot[2] = {0}; //rot[0]:今の状態, rot[1]:前回の状態 rot[0] = digitalRead(PIN_ROT); if(rot[0] != rot[1]){ rot[1] = rot[0]; counter++; } } void sensorInit(){ pinMode(PIN_SENSOR_0, INPUT); pinMode(PIN_SENSOR_1, INPUT); pinMode(PIN_SENSOR_2, INPUT); pinMode(PIN_SENSOR_3, INPUT); pinMode(PIN_SENSOR_4, INPUT); pinMode(PIN_SENSOR_5, INPUT); pinMode(PIN_SENSOR_6, INPUT); pinMode(PIN_SENSOR_7, INPUT); } byte sensorRead(){ byte sensor = 0; if(digitalRead(PIN_SENSOR_0)) sensor += 0b00000001; if(digitalRead(PIN_SENSOR_1)) sensor += 0b00000010; if(digitalRead(PIN_SENSOR_2)) sensor += 0b00000100; if(digitalRead(PIN_SENSOR_3)) sensor += 0b00001000; if(digitalRead(PIN_SENSOR_4)) sensor += 0b00010000; if(digitalRead(PIN_SENSOR_5)) sensor += 0b00100000; if(digitalRead(PIN_SENSOR_6)) sensor += 0b01000000; if(digitalRead(PIN_SENSOR_7)) sensor += 0b10000000; return sensor; } void setup() { //サーボ servoHandle.attach(PIN_SERVO_HANDLE, HANDLE_MIN, HANDLE_MAX); servoLance.attach(PIN_SERVO_LANCE, LANCE_MIN, LANCE_MAX); handle(0); lance(0); //モーター motorL.attach( PIN_MOTOR_LEFT_1, PIN_MOTOR_LEFT_2); motorR.attach(PIN_MOTOR_RIGHT_1, PIN_MOTOR_RIGHT_2); motorMode(STOP, STOP, 0, 0); //センサー sensorInit(); //エンコーダー pinMode(PIN_ROT, INPUT); //LED pinMode(PIN_LED, OUTPUT); digitalWrite(PIN_LED, HIGH); //モード mode = MODE_STOP; delay(1000); /* スタート */ digitalWrite(PIN_LED, LOW); mode = MODE_TRACE; handle(0); lance(0); motorMode(GO, GO, 0xff, 0xff); } void loop(){ //センサーを見る byte sensor = 0; #ifdef LINE_BLACK //黒ライン // sensor = PIN_SENSOR; sensor = sensorRead(); #else // sensor = ~PIN_SENSOR; sensor = ~sensorRead(); #endif //ロータリーエンコーダーの変化を見る count(); //ランスの動作を決定する switch(target){ case TARGET_NONE: lanceAngle = LANCE_ANGLE0; if(counter - counterOld > TARGET_NONE_COUNT ) target = 0; break; default: switch( sensor & MASK_CHECK_MARKER ){ case 0x81: target = TARGET_NONE; counterOld = counter; break; case 0x01: lanceAngle = LANCE_ANGLE1; target = TARGET_PARALLEL; break; case 0x80: lanceAngle = LANCE_ANGLE3; target = TARGET_VERTICAL; break; } break; } if( lanceAngle == LANCE_ANGLE1 && counter%LAP_COUNT > LAP_COUNT/2) lanceAngle = LANCE_ANGLE4; static unsigned long millis_lance = 0; if(millis() - millis_lance > LANCE_INTERVAL){ millis_lance = millis(); switch(lanceAngle){ case LANCE_ANGLE1: lanceAngle = LANCE_ANGLE2; break; case LANCE_ANGLE2: lanceAngle = LANCE_ANGLE1; break; } } //ランスの動作を決定する switch(target){ case TARGET_NONE: lanceAngle = LANCE_ANGLE0; if(counter - counterOld > TARGET_NONE_COUNT ) target = 0; break; case TARGET_PARALLEL: case TARGET_VERTICAL: case TARGET_CYLINDER: default: switch( sensor & MASK_CHECK_MARKER ){ case 0x81: target = TARGET_NONE; counterOld = counter; break; case 0x01: lanceAngle = LANCE_ANGLE1; target = TARGET_PARALLEL; break; case 0x80: lanceAngle = LANCE_ANGLE3; target = TARGET_VERTICAL; break; } break; } //全体の動作を決定する switch(mode){ case MODE_TRACE: trace(sensor); if( counter > LAP_COUNT*6 - LAP_COUNT/14 ){ // 6周したら、円筒標的を狙いに行く mode = MODE_STOP; } break; case MODE_STOP: default: digitalWrite(PIN_LED, HIGH); handle(0); lanceAngle = -90; motorMode(GO, GO, 0xff, 0xff); if( counter - counterOld > LAP_COUNT/21 ){ motorMode(STOP, STOP, 0xff, 0xff); } } lance(lanceAngle); }