1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265
|
#include "ArduinoRobotMotorBoard.h"
#include "EasyTransfer2.h"
#include "Multiplexer.h"
#include "LineFollow.h"
RobotMotorBoard::RobotMotorBoard(){
//LineFollow::LineFollow();
}
/*void RobotMotorBoard::beginIRReceiver(){
IRrecv::enableIRIn();
}*/
void RobotMotorBoard::begin(){
//initialze communication
Serial1.begin(9600);
messageIn.begin(&Serial1);
messageOut.begin(&Serial1);
//init MUX
uint8_t MuxPins[]={MUXA,MUXB,MUXC};
this->IRs.begin(MuxPins,MUX_IN,3);
pinMode(MUXI,INPUT);
digitalWrite(MUXI,LOW);
isPaused=false;
}
void RobotMotorBoard::process(){
if(isPaused)return;//skip process if the mode is paused
if(mode==MODE_SIMPLE){
//Serial.println("s");
//do nothing? Simple mode is just about getting commands
}else if(mode==MODE_LINE_FOLLOW){
//do line following stuff here.
LineFollow::runLineFollow();
}else if(mode==MODE_ADJUST_MOTOR){
//Serial.println('a');
//motorAdjustment=analogRead(POT);
//setSpeed(255,255);
//delay(100);
}
}
void RobotMotorBoard::pauseMode(bool onOff){
if(onOff){
isPaused=true;
}else{
isPaused=false;
}
stopCurrentActions();
}
void RobotMotorBoard::parseCommand(){
uint8_t modeName;
uint8_t codename;
int value;
int speedL;
int speedR;
if(this->messageIn.receiveData()){
//Serial.println("data received");
uint8_t command=messageIn.readByte();
//Serial.println(command);
switch(command){
case COMMAND_SWITCH_MODE:
modeName=messageIn.readByte();
setMode(modeName);
break;
case COMMAND_RUN:
if(mode==MODE_LINE_FOLLOW)break;//in follow line mode, the motor does not follow commands
speedL=messageIn.readInt();
speedR=messageIn.readInt();
motorsWrite(speedL,speedR);
break;
case COMMAND_MOTORS_STOP:
motorsStop();
break;
case COMMAND_ANALOG_WRITE:
codename=messageIn.readByte();
value=messageIn.readInt();
_analogWrite(codename,value);
break;
case COMMAND_DIGITAL_WRITE:
codename=messageIn.readByte();
value=messageIn.readByte();
_digitalWrite(codename,value);
break;
case COMMAND_ANALOG_READ:
codename=messageIn.readByte();
_analogRead(codename);
break;
case COMMAND_DIGITAL_READ:
codename=messageIn.readByte();
_digitalRead(codename);
break;
case COMMAND_READ_IR:
_readIR();
break;
case COMMAND_READ_TRIM:
_readTrim();
break;
case COMMAND_PAUSE_MODE:
pauseMode(messageIn.readByte());//onOff state
break;
case COMMAND_LINE_FOLLOW_CONFIG:
LineFollow::config(
messageIn.readByte(), //KP
messageIn.readByte(), //KD
messageIn.readByte(), //robotSpeed
messageIn.readByte() //IntegrationTime
);
break;
}
}
//delay(5);
}
uint8_t RobotMotorBoard::parseCodename(uint8_t codename){
switch(codename){
case B_TK1:
return TK1;
case B_TK2:
return TK2;
case B_TK3:
return TK3;
case B_TK4:
return TK4;
}
}
uint8_t RobotMotorBoard::codenameToAPin(uint8_t codename){
switch(codename){
case B_TK1:
return A0;
case B_TK2:
return A1;
case B_TK3:
return A6;
case B_TK4:
return A11;
}
}
void RobotMotorBoard::setMode(uint8_t mode){
if(mode==MODE_LINE_FOLLOW){
LineFollow::calibIRs();
}
/*if(mode==SET_MOTOR_ADJUSTMENT){
save_motor_adjustment_to_EEPROM();
}
*/
/*if(mode==MODE_IR_CONTROL){
beginIRReceiver();
}*/
this->mode=mode;
//stopCurrentActions();//If line following, this should stop the motors
}
void RobotMotorBoard::stopCurrentActions(){
motorsStop();
//motorsWrite(0,0);
}
void RobotMotorBoard::motorsWrite(int speedL, int speedR){
/*Serial.print(speedL);
Serial.print(" ");
Serial.println(speedR);*/
//motor adjustment, using percentage
_refreshMotorAdjustment();
if(motorAdjustment<0){
speedR*=(1+motorAdjustment);
}else{
speedL*=(1-motorAdjustment);
}
if(speedL>0){
analogWrite(IN_A1,speedL);
analogWrite(IN_A2,0);
}else{
analogWrite(IN_A1,0);
analogWrite(IN_A2,-speedL);
}
if(speedR>0){
analogWrite(IN_B1,speedR);
analogWrite(IN_B2,0);
}else{
analogWrite(IN_B1,0);
analogWrite(IN_B2,-speedR);
}
}
void RobotMotorBoard::motorsWritePct(int speedLpct, int speedRpct){
//speedLpct, speedRpct ranges from -100 to 100
motorsWrite(speedLpct*2.55,speedRpct*2.55);
}
void RobotMotorBoard::motorsStop(){
analogWrite(IN_A1,255);
analogWrite(IN_A2,255);
analogWrite(IN_B1,255);
analogWrite(IN_B2,255);
}
/*
*
*
* Input and Output ports
*
*
*/
void RobotMotorBoard::_digitalWrite(uint8_t codename,bool value){
uint8_t pin=parseCodename(codename);
digitalWrite(pin,value);
}
void RobotMotorBoard::_analogWrite(uint8_t codename,int value){
//There's no PWM available on motor board
}
void RobotMotorBoard::_digitalRead(uint8_t codename){
uint8_t pin=parseCodename(codename);
bool value=digitalRead(pin);
messageOut.writeByte(COMMAND_DIGITAL_READ_RE);
messageOut.writeByte(codename);
messageOut.writeByte(value);
messageOut.sendData();
}
void RobotMotorBoard::_analogRead(uint8_t codename){
uint8_t pin=codenameToAPin(codename);
int value=analogRead(pin);
messageOut.writeByte(COMMAND_ANALOG_READ_RE);
messageOut.writeByte(codename);
messageOut.writeInt(value);
messageOut.sendData();
}
int RobotMotorBoard::IRread(uint8_t num){
IRs.selectPin(num-1); //To make consistant with the pins labeled on the board
return IRs.getAnalogValue();
}
void RobotMotorBoard::_readIR(){
//Serial.println("readIR");
int value;
messageOut.writeByte(COMMAND_READ_IR_RE);
for(int i=1;i<6;i++){
value=IRread(i);
messageOut.writeInt(value);
}
messageOut.sendData();
}
void RobotMotorBoard::_readTrim(){
int value=analogRead(TRIM);
messageOut.writeByte(COMMAND_READ_TRIM_RE);
messageOut.writeInt(value);
messageOut.sendData();
}
void RobotMotorBoard::_refreshMotorAdjustment(){
motorAdjustment=map(analogRead(TRIM),0,1023,-30,30)/100.0;
}
void RobotMotorBoard::reportActionDone(){
setMode(MODE_SIMPLE);
messageOut.writeByte(COMMAND_ACTION_DONE);
messageOut.sendData();
}
RobotMotorBoard RobotMotor=RobotMotorBoard();
|