本帖最后由 给你一个冷布丁 于 2015-12-26 16:32 编辑
以下是我对mBot的源代码进行理解并注释了部分,希望和大家交流一下。毕竟读代码很费劲,有错的话希望大家指出。
/*************************************************************************
* File Name : Mbot_Firmware.ino
* Author : Ander
* Updated : Ander
* Version : V1.20101
* Date : 12/29/2014
* Description : Firmware for Makeblock Electronic modules with Scratch.
* License : CC-BY-SA 3.0
* Copyright (C) 2013 - 2014 Maker Works Technology Co., Ltd. All right reserved.
* http://www.makeblock.cc/
**************************************************************************/
#include
#include
#include
Servo servos[8];
MeDCMotor dc;
MeTemperature ts;
MeRGBLed led(0,30);
MeUltrasonicSensor us;
Me7SegmentDisplay seg;
MePort generalDevice;
MeLEDMatrix ledMx;
MeBuzzer buzzer;
MeIR ir;
MeGyro gyro;
MeJoystick joystick;
MeCompass Compass;
MeHumiture humiture;
MeFlameSensor FlameSensor;
MeGasSensor GasSensor;
typedef struct MeModule
{
int device;
int port;
int slot;
int pin;
int index;
float values[3];
} MeModule;
union{
byte byteVal[4];
float floatVal;
long longVal;
}val;
union{
byte byteVal[8];
double doubleVal;
}valDouble;
union{
byte byteVal[2];
short shortVal;
}valShort;
#if defined(__AVR_ATmega32U4__)
const int analogs[12] PROGMEM = {A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11};
#else
const int analogs[8] PROGMEM = {A0,A1,A2,A3,A4,A5,A6,A7};
#endif
String mVersion = "1.2.103";
boolean isAvailable = false;
int len = 52;
char buffer[52];
byte index = 0;
byte dataLen;
byte modulesLen=0;
boolean isStart = false;
char serialRead;
#define VERSION 0
#define ULTRASONIC_SENSOR 1
#define TEMPERATURE_SENSOR 2
#define LIGHT_SENSOR 3
#define POTENTIONMETER 4
#define JOYSTICK 5
#define GYRO 6
#define SOUND_SENSOR 7
#define RGBLED 8
#define SEVSEG 9
#define MOTOR 10
#define SERVO 11
#define ENCODER 12
#define IR 13
#define IRREMOTE 14
#define PIRMOTION 15
#define INFRARED 16
#define LINEFOLLOWER 17
#define IRREMOTECODE 18
#define SHUTTER 20
#define LIMITSWITCH 21
#define BUTTON 22
#define HUMITURE 23
#define FLAMESENSOR 24
#define GASSENSOR 25
#define COMPASS 26
#define DIGITAL 30
#define ANALOG 31
#define PWM 32
#define SERVO_PIN 33
#define TONE 34
#define BUTTON_INNER 35
#define LEDMATRIX 41
#define TIMER 50
#define GET 1
#define RUN 2
#define RESET 4
#define START 5
float angleServo = 90.0;
int servo_pins[8]={0,0,0,0,0,0,0,0};
unsigned char prevc=0;
/*初始化*/
void setup(){
pinMode(13,OUTPUT);//13脚为输出模式
digitalWrite(13,HIGH);//13脚输出高
delay(300);//延时300ms
digitalWrite(13,LOW);//13脚输出低
Serial.begin(115200);//串口波特率初始化为115200
delay(500);//延时500ms
buzzer.tone(500,50); //蜂鸣器的特定音调设置
delay(50);//延时50ms
buzzerOff();//蜂鸣器关闭
ir.begin();
led.setpin(13);//LED 13管脚
led.setColor(0,0,0);//基于三基色的设置
led.show();//LED开启
gyro.begin();//IO口设置开启
}
int irDelay = 0;
int irIndex = 0;
char irRead = 0;
boolean irReady = false;
String irBuffer = "";
double lastTime = 0.0;
double currentTime = 0.0;
double lastIRTime = 0.0;
boolean buttonPressed = false;
boolean irPressed = false;
/*主循环*/
void loop(){
currentTime = millis()/1000.0-lastTime;//对一次循环周期的时间
if(ir.decode())//是否接收到数据,以下都是对接受到的数据进行处理
{
irRead = ((ir.value>>8)>>8)&0xff;
lastIRTime = millis()/1000.0;//millis表示单片机运行的时间,单位是ms
irPressed = true;
if(irRead==0xa||irRead==0xd){
irIndex = 0;
irReady = true;
}else{
irBuffer+=irRead;
irIndex++;
if(irIndex>64){
irIndex = 0;
irBuffer = "";
}
}
irDelay = 0;
}else{
irDelay++;
if(irRead>0){
if(irDelay>5000){
irRead = 0;
irDelay = 0;
}
}
}
readSerial();//串口数据读取
if(isAvailable){
unsigned char c = serialRead&0xff;
if(c==0x55&&isStart==false){
if(prevc==0xff){
index=1;
isStart = true;
}
}else{
prevc = c;
if(isStart){
if(index==2){
dataLen = c;
}else if(index>2){
dataLen--;
}
writeBuffer(index,c);
}
}
index++;
if(index>51){
index=0;
isStart=false;
}
if(isStart&&dataLen==0&&index>3){
isStart = false;
parseData();
index=0;
}
}
}
void buzzerOn(){//蜂鸣器开启
buzzer.tone(500,1000);
}
void buzzerOff(){//蜂鸣器关闭
buzzer.noTone();
}
unsigned char readBuffer(int index){
return buffer[index];
}
void writeBuffer(int index,unsigned char c){
buffer[index]=c;
}
void writeHead(){
writeSerial(0xff);
writeSerial(0x55);
}
void writeEnd(){
Serial.println();
}
void writeSerial(unsigned char c){
Serial.write(c);
}
void readSerial(){
isAvailable = false;
if(Serial.available()>0){
isAvailable = true;
serialRead = Serial.read();
}
}
/*
ff 55 len idx action device port slot data a
0 1 2 3 4 5 6 7 8
*/
void parseData(){//导入数据,并执行相应的动作
isStart = false;
int idx = readBuffer(3);
int action = readBuffer(4);
int device = readBuffer(5);
switch(action){
case GET:{
writeHead();
writeSerial(idx);
readSensor(device);
writeEnd();
}
break;
case RUN:{
runModule(device);
callOK();
}
break;
case RESET:{
//reset
dc.reset(M1);
dc.run(0);
dc.reset(M2);
dc.run(0);
buzzerOff();
callOK();
}
break;
case START:{
//start
callOK();
}
break;
}
}
void callOK(){
writeSerial(0xff);
writeSerial(0x55);
writeEnd();
}
void sendByte(char c){
writeSerial(1);
writeSerial(c);
}
void sendString(String s){
int l = s.length();
writeSerial(4);
writeSerial(l);
for(int i=0;i
writeSerial(s.charAt(i));
}
}
//1 byte 2 float 3 short 4 len+string 5 double
void sendFloat(float value){
writeSerial(2);
val.floatVal = value;
writeSerial(val.byteVal[0]);
writeSerial(val.byteVal[1]);
writeSerial(val.byteVal[2]);
writeSerial(val.byteVal[3]);
}
void sendShort(double value){
writeSerial(3);
valShort.shortVal = value;
writeSerial(valShort.byteVal[0]);
writeSerial(valShort.byteVal[1]);
writeSerial(valShort.byteVal[2]);
writeSerial(valShort.byteVal[3]);
}
void sendDouble(double value){
writeSerial(5);
valDouble.doubleVal = value;
writeSerial(valDouble.byteVal[0]);
writeSerial(valDouble.byteVal[1]);
writeSerial(valDouble.byteVal[2]);
writeSerial(valDouble.byteVal[3]);
writeSerial(valDouble.byteVal[4]);
writeSerial(valDouble.byteVal[5]);
writeSerial(valDouble.byteVal[6]);
writeSerial(valDouble.byteVal[7]);
}
short readShort(int idx){
valShort.byteVal[0] = readBuffer(idx);
valShort.byteVal[1] = readBuffer(idx+1);
return valShort.shortVal;
}
float readFloat(int idx){
val.byteVal[0] = readBuffer(idx);
val.byteVal[1] = readBuffer(idx+1);
val.byteVal[2] = readBuffer(idx+2);
val.byteVal[3] = readBuffer(idx+3);
return val.floatVal;
}
char _receiveStr[20] = {};
uint8_t _receiveUint8[16] = {};
char* readString(int idx,int len){
for(int i=0;i
_receiveStr=readBuffer(idx+i);
}
_receiveStr[len] = ' |