Blame | Last modification | View Log | RSS feed
#include "TinyWireS.h" // wrapper class for I2C slave routines
#define I2C_SLAVE_ADDR 0x26 // i2c slave address (38)
#define CMD_MAN_BASIC 0x01 // Manually set motor speed/dir (Follows: 3 bytes)
#define CMD_MAN_TIMED 0x02
#define CMD_MAN_TIMES 0x03
#define CMD_MAN_DIST 0x04
#define CMD_GET_RPM 0x0a // Read RPM's
#define CMD_GET_DIST 0x0b // Read Distance's
#define CMD_GET_DEBUG 0x0c
// M0 = Left
// M1 = Right
#define OPT_M0DIR 0
#define OPT_M1DIR 1
#define OPT_M0TIME 2
#define OPT_M1TIME 3
#define OPT_M0DIST 4
#define OPT_M1DIST 5
#define ON 1
#define OFF 0
#define TANK_WHEEL_CIRCUM 0x96 // 1 turn of wheel = 150mm travelled per track
#define TANK_WHEEL_TICK 0x1E // Distance between magnets
#define M0A 0 // Motor0 +
#define M0B 1 // Motor0 -
#define M1A 2 // Motor1 +
#define M1B 3 // Motor1 -
#define SCL 4
#define LED_S1 5 // Led Status
#define SDA 6
#define PWM1 7 // Motor1 PWM
#define PWM0 8 // Motor2 PWM
#define HE0 10 // Hall Effect 0 PCINT8
#define HE1 9 // Hall Effect 1 PCINT9
const uint8_t MLEFT = 0;
const uint8_t MRIGHT = 1;
const uint8_t MFORWARD = 0;
const uint8_t MREVERSE = 1;
const uint8_t MRELEASE = 2;
uint8_t cmd = 0;
uint8_t options = 0;
uint8_t m0Spd = 0;
uint8_t m1Spd = 0;
uint32_t m0Time = 0;
uint32_t m1Time = 0;
byte byteRcvd = 0;
uint8_t he0Count = 0;
uint8_t he1Count = 0;
uint8_t rpm0 = 0;
uint8_t rpm0T = 0;
uint8_t rpm1 = 0;
uint8_t rpm1T = 0;
uint16_t m0distrav = 0;
uint16_t m1distrav = 0;
uint16_t m0MovDis = 0;
uint16_t m1MovDis = 0;
uint8_t pcInt1Trig = 0;
uint8_t pcInt1Curr = 0;
uint8_t pcInt1Last = 0;
uint8_t pcInt1Mask = 0;
uint8_t pcInt1Chg = 0;
void setup(){
pinMode(LED_S1,OUTPUT);
digitalWrite(LED_S1,HIGH);
// Setup PWM control of motors
DDRA |= (1 << PA7); //Set OC0B to output
DDRB |= (1 << PB2); //Set OC0A to output
TCCR0A |= ((1 << COM0A1) | (1 << COM0B1) | (1 << WGM01) | (1 << WGM00));
pinMode(M0A,OUTPUT);
pinMode(M0B,OUTPUT);
pinMode(M1A,OUTPUT);
pinMode(M1B,OUTPUT);
// Hall Effect sensors
DDRB |= (1 << PCINT8); // Set interrupt pins as input
DDRB |= (1 << PCINT9);
PORTB |= (1 << PCINT8); // Enable pull-ups
PORTB |= (1 << PCINT9);
PCMSK1 |= (1 << PCINT8); //Enable interrupt on PCINT8 (Pin 2)
PCMSK1 |= (1 << PCINT9);
sei(); // Enable interrupts in SREG
GIMSK |= (1 << PCIE1); //Enable interrupts period for PCI1 (PCINT8:11)
setM0_Dir(MRELEASE);
setM1_Dir(MRELEASE);
pcInt1Last = PINB;
RBlink(LED_S1,2); // show it's alive
TinyWireS.begin(I2C_SLAVE_ADDR); // init I2C Slave mode
update_motors();
}
ISR(PCINT1_vect) {
pcInt1Curr = PINB;
pcInt1Mask = pcInt1Curr ^ pcInt1Last;
pcInt1Last = pcInt1Curr;
pcInt1Trig = 1;
}
void loop(){
if (pcInt1Trig == 1) {
pcInt1Trig = 0;
doInterrupt();
}
// Update run times
if (bitRead(options, OPT_M0TIME)) {
if (m0Time >= millis()) {
bitClear(options, OPT_M0TIME);
m0Spd = 0;
update_motors();
}
}
if (bitRead(options, OPT_M1TIME)) {
if (m1Time >= millis()) {
bitClear(options, OPT_M1TIME);
m1Spd = 0;
update_motors();
}
}
// Do comms
if (TinyWireS.available()){ // got I2C input!
doComms();
}
delay(5);
}
void doInterrupt() {
// Screen out non PC pins
if ((pcInt1Mask &= PCMSK1) == 0)
return;
// Loop through all pins on port
// Set those that have changed
uint8_t biti;
for (uint8_t i=0; i<8; i++) {
biti = 0x01 << i;
// Check that its a PC int pin
if (biti & pcInt1Mask) {
pcInt1Chg |= (1 << i);
}
}
// HE0 - Left track
if (bitRead(pcInt1Chg, PCINT8) && !bitRead(pcInt1Curr, PCINT8)) {
//rpm0 = (30*1000/(millis() - rpm0T))/5;
//rpm0T = millis();
m0distrav += TANK_WHEEL_TICK;
if (bitRead(options, OPT_M0DIST) && m0distrav >= m0MovDis) {
//m0distrav = 0;
m0Spd = 0;
bitClear(options, OPT_M0DIST);
update_motors();
}
}
// HE1 - Right track
if (bitRead(pcInt1Chg, PCINT9) && !bitRead(pcInt1Curr, PCINT9)) {
//rpm1 = (30*1000/(millis() - rpm1T))/5;
//rpm1T = millis();
m1distrav += TANK_WHEEL_TICK;
if (bitRead(options, OPT_M1DIST) && m1distrav >= m1MovDis) {
//m1distrav = 0;
m1Spd = 0;
bitClear(options, OPT_M1DIST);
update_motors();
}
}
}
void doComms() {
cmd = TinyWireS.receive(); // get the byte from master
if (cmd == CMD_MAN_BASIC) {
// Basic options, speed and direction
options = TinyWireS.receive();
m0Spd = TinyWireS.receive();
m1Spd = TinyWireS.receive();
m0distrav = 0;
m1distrav = 0;
update_motors();
} else if (cmd == CMD_MAN_TIMED) {
// Timed mode, receive 16bit timing
options = TinyWireS.receive();
m0Spd = TinyWireS.receive();
m1Spd = TinyWireS.receive();
m0Time = TinyWireS.receive() << 8; // High byte
m0Time = TinyWireS.receive(); // Low byte
m0Time += millis(); // All the current millis
m1Time = TinyWireS.receive() << 8;
m1Time = TinyWireS.receive();
m0Time += millis();
m0distrav = 0;
m1distrav = 0;
update_motors();
} else if (cmd == CMD_MAN_TIMES) {
// Timed mode, receive 8bit timing
options = TinyWireS.receive();
m0Spd = TinyWireS.receive();
m1Spd = TinyWireS.receive();
m0Time = TinyWireS.receive();
m1Time = TinyWireS.receive();
m0distrav = 0;
m1distrav = 0;
update_motors();
} else if (cmd == CMD_MAN_DIST) {
// Timed mode, receive 16bit timing
options = TinyWireS.receive();
m0Spd = TinyWireS.receive();
m1Spd = TinyWireS.receive();
m0MovDis = TinyWireS.receive() << 8;
m0MovDis |= TinyWireS.receive();
m1MovDis = TinyWireS.receive() << 8;
m1MovDis |= TinyWireS.receive();
m0distrav = 0;
m1distrav = 0;
update_motors();
} else if (cmd == CMD_GET_RPM) {
TinyWireS.send(rpm0);
TinyWireS.send(rpm1);
} else if (cmd == CMD_GET_DIST) {
TinyWireS.send(m0distrav >> 8);
TinyWireS.send(m0distrav);
TinyWireS.send(m1distrav >> 8);
TinyWireS.send(m1distrav);
} else if (cmd == CMD_GET_DEBUG) {
TinyWireS.send(m1MovDis >> 8);
TinyWireS.send(m1MovDis);
} else {
// Kill the whole buffer, dont know what this command is.
while (TinyWireS.available())
TinyWireS.receive();
}
RBlink(LED_S1,1);
}
inline void pwm0(uint8_t tog) {
TCCR0A |= ((tog << COM0A1));
}
inline void pwm1(uint8_t tog) {
TCCR0A |= ((tog << COM0B1));
}
inline void setM1_Spd(uint8_t num){
OCR0A = num;
}
inline void setM0_Spd(uint8_t num){
OCR0B = num;
}
void setM0_Dir (uint8_t dir) {
if (dir == MFORWARD) {
digitalWrite(M0A,HIGH);
digitalWrite(M0B,LOW);
} else if (dir == MREVERSE) {
digitalWrite(M0A,LOW);
digitalWrite(M0B,HIGH);
} else {
digitalWrite(M0A,HIGH);
digitalWrite(M0B,LOW);
setM0_Spd(0);
}
}
void setM1_Dir (uint8_t dir) {
if (dir == MFORWARD) {
digitalWrite(M1A,HIGH);
digitalWrite(M1B,LOW);
} else if (dir == MREVERSE) {
digitalWrite(M1A,LOW);
digitalWrite(M1B,HIGH);
} else {
digitalWrite(M1A,HIGH);
digitalWrite(M1B,LOW);
setM1_Spd(0);
}
}
void update_motors() {
// Start the tracks rolling
if (m0Spd > 0) {
pwm0(ON);
setM0_Spd(m0Spd);
if (bitRead(options, OPT_M0DIR))
setM0_Dir(MFORWARD);
else
setM0_Dir(MREVERSE);
} else {
pwm0(OFF);
setM0_Dir(MRELEASE);
}
if (m1Spd > 0) {
pwm1(ON);
setM1_Spd(m1Spd);
if (bitRead(options, OPT_M1DIR))
setM1_Dir(MFORWARD);
else
setM1_Dir(MREVERSE);
} else {
pwm1(OFF);
setM1_Dir(MRELEASE);
}
}
void Blink(byte led, byte times){ // poor man's display
for (byte i=0; i< times; i++){
digitalWrite(led,HIGH);
delay (100);
digitalWrite(led,LOW);
delay (75);
}
}
void RBlink(byte led, byte times){ // poor man's display
for (byte i=0; i< times; i++){
digitalWrite(led,LOW);
delay (100);
digitalWrite(led,HIGH);
delay (75);
}
}