we bitmap now
This commit is contained in:
parent
d9714a88f1
commit
a5c87ab220
244
mecanum.ino
244
mecanum.ino
@ -1,21 +1,47 @@
|
|||||||
#include <boarddefs.h>
|
//#include <boarddefs.h>
|
||||||
#include <IRremote.h>
|
#include <IRremote.h>
|
||||||
#include <IRremoteInt.h>
|
//#include <IRremoteInt.h>
|
||||||
#include <ir_Lego_PF_BitStreamEncoder.h>
|
//#include <ir_Lego_PF_BitStreamEncoder.h>
|
||||||
#define IR 4
|
#define IR 4
|
||||||
IRrecv irrecv(IR);
|
IRrecv irrecv(IR);
|
||||||
|
|
||||||
|
//GPIO Wheels
|
||||||
#define WHEEL_FRONT_LEFT_F A0
|
#define WHEEL_FRONT_LEFT_F A0
|
||||||
#define WHEEL_REAR_LEFT_R A1
|
#define WHEEL_REAR_LEFT_R A1
|
||||||
#define WHEEL_REAR_RIGHT_F A2
|
#define WHEEL_REAR_RIGHT_F A2
|
||||||
#define WHEEL_FRONT_RIGHT_R A3
|
#define WHEEL_FRONT_RIGHT_R A3
|
||||||
|
|
||||||
#define WHEEL_FRONT_LEFT_R 10
|
|
||||||
#define WHEEL_REAR_LEFT_F 9
|
|
||||||
#define WHEEL_FRONT_RIGHT_F 8
|
|
||||||
#define WHEEL_REAR_RIGHT_R 7
|
#define WHEEL_REAR_RIGHT_R 7
|
||||||
|
#define WHEEL_FRONT_RIGHT_F 8
|
||||||
|
#define WHEEL_REAR_LEFT_F 9
|
||||||
|
#define WHEEL_FRONT_LEFT_R 10
|
||||||
|
|
||||||
/*
|
//Response from Remote
|
||||||
|
#define RFORWARD 4060792887
|
||||||
|
#define RBACKWARD 4060752087
|
||||||
|
#define RSTRAFE_LEFT 4060768407
|
||||||
|
#define RSTRAFE_RIGHT 4060784727
|
||||||
|
#define RSTOP 4060801047
|
||||||
|
#define RTURN_LEFT 4060750047
|
||||||
|
#define RTURN_RIGHT 4060790847
|
||||||
|
#define RDIAG_LEFT_FOR 4060786767
|
||||||
|
#define RDIAG_RIGHT_BACK 4060778607
|
||||||
|
#define RDIAG_RIGHT_FOR 4060782687
|
||||||
|
#define RDIAG_LEFT_BACK 4060766367
|
||||||
|
|
||||||
|
//direction bitmaps
|
||||||
|
#define DSTOP 0b00000000
|
||||||
|
#define DFORWARD 0b11110000
|
||||||
|
#define DBACKWARD 0b00001111
|
||||||
|
#define DSTRAFE_LEFT 0b01101001
|
||||||
|
#define DSTRAFE_RIGHT 0b10010110
|
||||||
|
#define DDIAG_LEFT_FOR 0b01100000
|
||||||
|
#define DDIAG_RIGHT_BACK 0b00000110
|
||||||
|
#define DDIAG_RIGHT_FOR 0b10010000
|
||||||
|
#define DDIAG_LEFT_BACK 0b00001001
|
||||||
|
#define DTURN_LEFT 0b10100101
|
||||||
|
#define DTURN_RIGHT 0b01011010
|
||||||
|
|
||||||
|
/* All Responses
|
||||||
* 4060792887 ^
|
* 4060792887 ^
|
||||||
* 4060752087 v
|
* 4060752087 v
|
||||||
* 4060768407 <
|
* 4060768407 <
|
||||||
@ -56,80 +82,19 @@ void setup() {
|
|||||||
pinMode(WHEEL_FRONT_LEFT_F, OUTPUT);
|
pinMode(WHEEL_FRONT_LEFT_F, OUTPUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void drive(int direction) {
|
||||||
|
digitalWrite(WHEEL_FRONT_LEFT_F, direction & 0b10000000 ? LOW : HIGH);
|
||||||
|
digitalWrite(WHEEL_FRONT_RIGHT_F, direction & 0b01000000 ? LOW : HIGH);
|
||||||
|
digitalWrite(WHEEL_REAR_LEFT_F, direction & 0b00100000 ? LOW : HIGH);
|
||||||
|
digitalWrite(WHEEL_REAR_RIGHT_F, direction & 0b00010000 ? LOW : HIGH);
|
||||||
|
|
||||||
void stop(){
|
digitalWrite(WHEEL_FRONT_LEFT_R, direction & 0b00001000 ? LOW : HIGH);
|
||||||
digitalWrite(WHEEL_REAR_RIGHT_R, HIGH);
|
digitalWrite(WHEEL_FRONT_RIGHT_R, direction & 0b00000100 ? LOW : HIGH);
|
||||||
digitalWrite(WHEEL_REAR_RIGHT_F, HIGH);
|
digitalWrite(WHEEL_REAR_LEFT_R, direction & 0b00000010 ? LOW : HIGH);
|
||||||
digitalWrite(WHEEL_REAR_LEFT_R, HIGH);
|
digitalWrite(WHEEL_REAR_RIGHT_R, direction & 0b00000001 ? LOW : HIGH);
|
||||||
digitalWrite(WHEEL_REAR_LEFT_F, HIGH);
|
|
||||||
digitalWrite(WHEEL_FRONT_RIGHT_R, HIGH);
|
|
||||||
digitalWrite(WHEEL_FRONT_RIGHT_F, HIGH);
|
|
||||||
digitalWrite(WHEEL_FRONT_LEFT_R, HIGH);
|
|
||||||
digitalWrite(WHEEL_FRONT_LEFT_F, HIGH);
|
|
||||||
}
|
|
||||||
|
|
||||||
void forward(){
|
|
||||||
digitalWrite(WHEEL_REAR_RIGHT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_REAR_LEFT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_RIGHT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_LEFT_F, LOW);
|
|
||||||
}
|
|
||||||
|
|
||||||
void backward(){
|
|
||||||
digitalWrite(WHEEL_REAR_RIGHT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_REAR_LEFT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_RIGHT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_LEFT_R, LOW);
|
|
||||||
}
|
|
||||||
|
|
||||||
void strafe_l(){
|
|
||||||
digitalWrite(WHEEL_REAR_RIGHT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_REAR_LEFT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_RIGHT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_LEFT_R, LOW);
|
|
||||||
}
|
|
||||||
|
|
||||||
void strafe_r(){
|
|
||||||
digitalWrite(WHEEL_REAR_RIGHT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_REAR_LEFT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_RIGHT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_LEFT_F, LOW);
|
|
||||||
}
|
|
||||||
|
|
||||||
void diag_l_f(){
|
|
||||||
digitalWrite(WHEEL_REAR_LEFT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_RIGHT_F, LOW);
|
|
||||||
}
|
|
||||||
|
|
||||||
void diag_r_r(){
|
|
||||||
digitalWrite(WHEEL_REAR_LEFT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_RIGHT_R, LOW);
|
|
||||||
}
|
|
||||||
|
|
||||||
void diag_r_f(){
|
|
||||||
digitalWrite(WHEEL_REAR_RIGHT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_LEFT_F, LOW);
|
|
||||||
}
|
|
||||||
|
|
||||||
void diag_l_r(){
|
|
||||||
digitalWrite(WHEEL_REAR_RIGHT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_LEFT_R, LOW);
|
|
||||||
}
|
|
||||||
|
|
||||||
void turn_l(){
|
|
||||||
digitalWrite(WHEEL_REAR_RIGHT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_REAR_LEFT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_RIGHT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_LEFT_F, LOW);
|
|
||||||
}
|
|
||||||
|
|
||||||
void turn_r(){
|
|
||||||
digitalWrite(WHEEL_REAR_RIGHT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_REAR_LEFT_R, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_RIGHT_F, LOW);
|
|
||||||
digitalWrite(WHEEL_FRONT_LEFT_R, LOW);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//MIK IR Remote.pdf S.12 I. Kübler
|
||||||
unsigned long getIRremote(){
|
unsigned long getIRremote(){
|
||||||
static unsigned long lastValue = 0;
|
static unsigned long lastValue = 0;
|
||||||
decode_results irResults;
|
decode_results irResults;
|
||||||
@ -146,66 +111,75 @@ unsigned long getIRremote(){
|
|||||||
void loop() {
|
void loop() {
|
||||||
|
|
||||||
unsigned long remote = getIRremote();
|
unsigned long remote = getIRremote();
|
||||||
static unsigned long modus;
|
static unsigned long mode;
|
||||||
|
static unsigned long lastMode = 0;
|
||||||
if(remote){
|
if(remote){
|
||||||
Serial.println(remote);
|
Serial.println(remote);
|
||||||
modus = remote;
|
mode = remote;
|
||||||
|
if(mode != lastMode){
|
||||||
|
drive(DSTOP);
|
||||||
|
delay(50);
|
||||||
|
lastMode = mode;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
if(modus == 4060792887){
|
switch(mode){
|
||||||
forward();
|
case RFORWARD:
|
||||||
}else if(modus == 4060801047){
|
drive(DFORWARD);
|
||||||
stop();
|
break;
|
||||||
}else if(modus == 4060752087){
|
case RSTOP:
|
||||||
backward();
|
drive(DSTOP);
|
||||||
}else if(modus == 4060768407){
|
break;
|
||||||
strafe_l();
|
case RBACKWARD:
|
||||||
}else if(modus == 4060784727){
|
drive(DBACKWARD);
|
||||||
strafe_r();
|
break;
|
||||||
}else if(modus == 4060750047){
|
case RSTRAFE_LEFT:
|
||||||
turn_l();
|
drive(DSTRAFE_LEFT);
|
||||||
}else if(modus == 4060790847){
|
break;
|
||||||
turn_r();
|
case RSTRAFE_RIGHT:
|
||||||
}else if(modus == 4060786767){
|
drive(DSTRAFE_RIGHT);
|
||||||
diag_l_f();
|
break;
|
||||||
}else if(modus == 4060778607){
|
case RTURN_LEFT:
|
||||||
diag_r_r();
|
drive(DTURN_LEFT);
|
||||||
}else if(modus == 4060782687){
|
break;
|
||||||
diag_r_f();
|
case RTURN_RIGHT:
|
||||||
}else if(modus == 4060766367){
|
drive(DTURN_RIGHT);
|
||||||
diag_l_r();
|
break;
|
||||||
|
case RDIAG_LEFT_FOR:
|
||||||
|
drive(DDIAG_LEFT_FOR);
|
||||||
|
break;
|
||||||
|
case RDIAG_LEFT_BACK:
|
||||||
|
drive(DDIAG_LEFT_BACK);
|
||||||
|
break;
|
||||||
|
case RDIAG_RIGHT_FOR:
|
||||||
|
drive(DDIAG_RIGHT_FOR);
|
||||||
|
break;
|
||||||
|
case RDIAG_RIGHT_BACK:
|
||||||
|
drive(DDIAG_RIGHT_BACK);
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
stop();
|
if(mode == RFORWARD){
|
||||||
forward();
|
drive(DFORWARD);
|
||||||
delay(1000);
|
}else if(mode == RSTOP){
|
||||||
stop();
|
drive(DSTOP);
|
||||||
backward();
|
}else if(mode == RBACKWARD){
|
||||||
delay(1000);
|
drive(DBACKWARD);
|
||||||
stop();
|
}else if(mode == RSTRAFE_LEFT){
|
||||||
strafe_l();
|
drive(DSTRAFE_LEFT);
|
||||||
delay(1000);
|
}else if(mode == RSTRAFE_RIGHT){
|
||||||
stop();
|
drive(DSTRAFE_RIGHT);
|
||||||
strafe_r();
|
}else if(mode == RTURN_LEFT){
|
||||||
delay(1000);
|
drive(DTURN_LEFT);
|
||||||
stop();
|
}else if(mode == RTURN_RIGHT){
|
||||||
diag_l_f();
|
drive(DTURN_RIGHT);
|
||||||
delay(1000);
|
}else if(mode == RDIAG_LEFT_FOR){
|
||||||
stop();
|
drive(DDIAG_LEFT_FOR);
|
||||||
diag_l_r();
|
}else if(mode == RDIAG_RIGHT_BACK){
|
||||||
delay(1000);
|
drive(DDIAG_RIGHT_BACK);
|
||||||
stop();
|
}else if(mode == RDIAG_RIGHT_FOR){
|
||||||
diag_r_f();
|
drive(DDIAG_RIGHT_FOR);
|
||||||
delay(1000);
|
}else if(mode == RDIAG_LEFT_BACK){
|
||||||
stop();
|
drive(DDIAG_LEFT_BACK);
|
||||||
diag_r_r();
|
}
|
||||||
delay(1000);
|
|
||||||
stop();
|
|
||||||
turn_l();
|
|
||||||
delay(1000);
|
|
||||||
stop();
|
|
||||||
turn_r();
|
|
||||||
delay(1000);
|
|
||||||
stop();
|
|
||||||
*/
|
*/
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user