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