I add the arduino library to the file
This commit is contained in:
commit
55f5139939
|
|
@ -0,0 +1,65 @@
|
|||
# Makeblock Library v3.27
|
||||
|
||||
Arduino Library for Makeblock Electronic Modules
|
||||
|
||||
# Copyright notice
|
||||
|
||||
In makeblock's library, some of the modules are derived from other open source projects, and also part of some code is inspired by the algorithms of other individuals or organizations. We will retain the copyright of the original open source code.
|
||||
|
||||
These modules is derived from other open source projects:
|
||||
|
||||
- MeRGBLed
|
||||
- MeHumitureSensor
|
||||
- Me7SegmentDisplay
|
||||
- MeOneWire
|
||||
- MeStepper
|
||||
|
||||
and these modules is inspired by some projects:
|
||||
|
||||
- MeUSBHost
|
||||
|
||||
As an open source library, we respect all contributors to the open source community and thank you very much for everyone's supervision.
|
||||
|
||||
If you have a discussion about licensing issues, please contact me (myan@makeblock.com -- Mark Yan)
|
||||
|
||||
### How to use:
|
||||
|
||||
1. Download the source from the git https://codeload.github.com/Makeblock-official/Makeblock-Libraries/zip/master
|
||||
|
||||
2. In the Arduino IDE: "Sketch-> Include Library-> Add .ZIP Library-> select the downloaded file-> Open"
|
||||
|
||||
3. Click "File-> Examples". There are some test programs in "MakeBlockDrive->"
|
||||
|
||||
4. Depending on the type of board you're using, you need to modify the header file to match.
|
||||
|
||||
For example, if you're using a mCore. You should change `#include <MeOrion.h>` to `#include <MeMCore.h>`
|
||||
Corresponding boards and there header file are:
|
||||
|
||||
Orion <--------> MeOrion.h
|
||||
|
||||
BaseBoard <----> MeBaseBoard.h
|
||||
|
||||
mCore <--------> MeMCore.h
|
||||
|
||||
Shield <-------> MeShield.h
|
||||
|
||||
Auriga <-------> MeAuriga.h
|
||||
|
||||
MegaPi <-------> MeMegaPi.h
|
||||
|
||||
### Revision of history:
|
||||
|
||||
|Author | Time | Version | Descr |
|
||||
|:-------- | :-----: | :----: | :----- |
|
||||
|Mark Yan | 2015/07/24 | 3.0.0 | Rebuild the old lib.|
|
||||
|Rafael Lee | 2015/09/02 | 3.1.0 | Added some comments and macros.|
|
||||
|Lawrence | 2015/09/09 | 3.2.0 | Include some Arduino's official headfiles which path specified.|
|
||||
|Mark Yan | 2015/11/02 | 3.2.1 | fix bug on MACOS.|
|
||||
|Mark Yan | 2016/01/21 | 3.2.2 | fix some library bugs.|
|
||||
|Mark Yan | 2016/05/17 | 3.2.3 | add support for MegaPi and Auriga Board.|
|
||||
|Mark Yan | 2016/07/27 | 3.2.4 | fix some JIRA issue, add PID motion for Megapi/Auriga on board encoder motor.|
|
||||
|Mark Yan | 2018/05/16 | 3.2.5 | Correct copyright information.|
|
||||
|Vincent He | 2019/01/04 | 3.2.6 | 1.Mbot /ranger adds the function of communication variables. 2.Solve the blocking problem of 9g steering gear. 3.Solve the problem that the intelligent steering gear cannot read back the parameters. 4.Add version number function. 5.High power code motor reinforcement version query function. 6.Solve the problem of SetColor (uint8_t index, long value) function error in mergharp.cpp. 7.The mBot board cannot extinguish the RGB. First upload the program with the RGB in any color, and then upload the program with the RGB in all colors. The RGB cannot extinguish (MeRGBLed bled. CPP file). 8.In the MegaPi firmware, SLOT1 is changed to slot_num instead of parameter transmission in the command processing stepper motor.|
|
||||
|Vincent He | 2019/09/02 | 3.2.7 | 1.fix the problem that the electronic compass Mecompass is hung on the Orion mainboard 7 or 8 ports and communication will be hung dead. 2.fix the problem that the function getPointFast() in MeHumitureSensor.cpp does not normally output the value. 3.fix the problem that compile smartservo_test.ino firmware error report using the arduino1.6.5 environment with mBlock V3.4.12. 4.remove MeSuperVariable.cpp/MeSuperVariable.h. 5.fix the problem that ultrasonic module can only measure the maximum range of 375cm,and the maximum range of normal requirements is 400cm.|
|
||||
|
||||
### Learn more from Makeblock official website: www.makeblock.com
|
||||
|
|
@ -0,0 +1,712 @@
|
|||
/*************************************************************************
|
||||
* File Name : baseboard_firmware.ino
|
||||
* Author : Ander, Mark Yan
|
||||
* Updated : Ander, Mark Yan
|
||||
* Version : V0b.01.104
|
||||
* Date : 07/06/2016
|
||||
* Description : Firmware for Makeblock Electronic modules with Scratch.
|
||||
* License : CC-BY-SA 3.0
|
||||
* Copyright (C) 2013 - 2016 Maker Works Technology Co., Ltd. All right reserved.
|
||||
* http://www.makeblock.cc/
|
||||
**************************************************************************/
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
#include <Arduino.h>
|
||||
#include <MeBaseBoard.h>
|
||||
|
||||
Servo servos[8];
|
||||
MeDCMotor dc;
|
||||
MeTemperature ts;
|
||||
MeRGBLed led;
|
||||
MeUltrasonicSensor us;
|
||||
Me7SegmentDisplay seg;
|
||||
MePort generalDevice;
|
||||
MeInfraredReceiver *ir = NULL;
|
||||
MeGyro gyro;
|
||||
MeJoystick joystick;
|
||||
MeStepper steppers[2];
|
||||
MeBuzzer buzzer;
|
||||
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;
|
||||
MeModule modules[12];
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
int analogs[12]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11};
|
||||
#endif
|
||||
#if defined(__AVR_ATmega328P__) or defined(__AVR_ATmega168__)
|
||||
int analogs[8]={A0,A1,A2,A3,A4,A5,A6,A7};
|
||||
MeEncoderMotor encoders[2];
|
||||
#endif
|
||||
#if defined(__AVR_ATmega1280__)|| defined(__AVR_ATmega2560__)
|
||||
int analogs[16]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15};
|
||||
#endif
|
||||
String mVersion = "0b.01.104";
|
||||
boolean isAvailable = false;
|
||||
boolean isBluetooth = false;
|
||||
|
||||
int len = 52;
|
||||
char buffer[32];
|
||||
char bufferBt[32];
|
||||
byte index = 0;
|
||||
byte dataLen;
|
||||
byte modulesLen=0;
|
||||
boolean isStart = false;
|
||||
unsigned char irRead;
|
||||
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 PULSEIN 37
|
||||
#define ULTRASONIC_ARDUINO 36
|
||||
#define STEPPER 40
|
||||
#define LEDMATRIX 41
|
||||
#define TIMER 50
|
||||
#define TOUCH_SENSOR 51
|
||||
|
||||
#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;
|
||||
double lastTime = 0.0;
|
||||
double currentTime = 0.0;
|
||||
uint8_t keyPressed = 0;
|
||||
uint8_t command_index = 0;
|
||||
|
||||
void setup(){
|
||||
pinMode(13,OUTPUT);
|
||||
digitalWrite(13,HIGH);
|
||||
delay(300);
|
||||
digitalWrite(13,LOW);
|
||||
Serial.begin(115200);
|
||||
delay(500);
|
||||
buzzerOn();
|
||||
delay(100);
|
||||
buzzerOff();
|
||||
#if defined(__AVR_ATmega328P__) or defined(__AVR_ATmega168__)
|
||||
encoders[0] = MeEncoderMotor(SLOT_1);
|
||||
encoders[1] = MeEncoderMotor(SLOT_2);
|
||||
encoders[0].begin();
|
||||
encoders[1].begin();
|
||||
delay(500);
|
||||
encoders[0].runSpeed(0);
|
||||
encoders[1].runSpeed(0);
|
||||
#else
|
||||
Serial1.begin(115200);
|
||||
#endif
|
||||
gyro.begin();
|
||||
Serial.print("Version: ");
|
||||
Serial.println(mVersion);
|
||||
}
|
||||
void loop(){
|
||||
currentTime = millis()/1000.0-lastTime;
|
||||
if(ir != NULL)
|
||||
{
|
||||
ir->loop();
|
||||
}
|
||||
readSerial();
|
||||
steppers[0].runSpeedToPosition();
|
||||
steppers[1].runSpeedToPosition();
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
unsigned char readBuffer(int index){
|
||||
return isBluetooth?bufferBt[index]:buffer[index];
|
||||
}
|
||||
void writeBuffer(int index,unsigned char c){
|
||||
if(isBluetooth){
|
||||
bufferBt[index]=c;
|
||||
}else{
|
||||
buffer[index]=c;
|
||||
}
|
||||
}
|
||||
void writeHead(){
|
||||
writeSerial(0xff);
|
||||
writeSerial(0x55);
|
||||
}
|
||||
void writeEnd(){
|
||||
Serial.println();
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
Serial1.println();
|
||||
#endif
|
||||
}
|
||||
void writeSerial(unsigned char c){
|
||||
Serial.write(c);
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
Serial1.write(c);
|
||||
#endif
|
||||
}
|
||||
void readSerial(){
|
||||
isAvailable = false;
|
||||
if(Serial.available()>0){
|
||||
isAvailable = true;
|
||||
isBluetooth = false;
|
||||
serialRead = Serial.read();
|
||||
}
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
if(Serial1.available()>0){
|
||||
isAvailable = true;
|
||||
isBluetooth = true;
|
||||
serialRead = Serial1.read();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
/*
|
||||
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);
|
||||
command_index = (uint8_t)idx;
|
||||
int action = readBuffer(4);
|
||||
int device = readBuffer(5);
|
||||
switch(action){
|
||||
case GET:{
|
||||
if(device != ULTRASONIC_SENSOR){
|
||||
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);
|
||||
dc.reset(PORT_1);
|
||||
dc.run(0);
|
||||
dc.reset(PORT_2);
|
||||
dc.run(0);
|
||||
|
||||
#if defined(__AVR_ATmega328P__)
|
||||
encoders[0].runSpeed(0);
|
||||
encoders[1].runSpeed(0);
|
||||
#endif
|
||||
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<l;i++){
|
||||
writeSerial(s.charAt(i));
|
||||
}
|
||||
}
|
||||
void sendFloat(float value){
|
||||
writeSerial(0x2);
|
||||
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]);
|
||||
}
|
||||
void sendDouble(double value){
|
||||
writeSerial(2);
|
||||
valDouble.doubleVal = value;
|
||||
writeSerial(valDouble.byteVal[0]);
|
||||
writeSerial(valDouble.byteVal[1]);
|
||||
writeSerial(valDouble.byteVal[2]);
|
||||
writeSerial(valDouble.byteVal[3]);
|
||||
}
|
||||
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;
|
||||
}
|
||||
long readLong(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.longVal;
|
||||
}
|
||||
void runModule(int device){
|
||||
//0xff 0x55 0x6 0x0 0x1 0xa 0x9 0x0 0x0 0xa
|
||||
int port = readBuffer(6);
|
||||
int pin = port;
|
||||
switch(device){
|
||||
case MOTOR:{
|
||||
int speed = readShort(7);
|
||||
dc.reset(port);
|
||||
dc.run(speed);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
int leftSpeed = readShort(6);
|
||||
dc.reset(M1);
|
||||
dc.run(leftSpeed);
|
||||
int rightSpeed = readShort(8);
|
||||
dc.reset(M2);
|
||||
dc.run(rightSpeed);
|
||||
}
|
||||
break;
|
||||
case STEPPER:{
|
||||
int maxSpeed = readShort(7);
|
||||
long distance = readLong(9);
|
||||
if(port==PORT_1){
|
||||
steppers[0] = MeStepper(PORT_1);
|
||||
steppers[0].moveTo(distance);
|
||||
steppers[0].setMaxSpeed(maxSpeed);
|
||||
steppers[0].setSpeed(maxSpeed);
|
||||
}else if(port==PORT_2){
|
||||
steppers[1] = MeStepper(PORT_2);
|
||||
steppers[1].moveTo(distance);
|
||||
steppers[1].setMaxSpeed(maxSpeed);
|
||||
steppers[1].setSpeed(maxSpeed);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case ENCODER:{
|
||||
int slot = readBuffer(7);
|
||||
int maxSpeed = readShort(8);
|
||||
float distance = readFloat(10);
|
||||
#if defined(__AVR_ATmega328P__)
|
||||
if(slot==SLOT_1){
|
||||
encoders[0].move(distance,maxSpeed);
|
||||
}else if(slot==SLOT_2){
|
||||
encoders[1].move(distance,maxSpeed);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
case RGBLED:{
|
||||
int slot = readBuffer(7);
|
||||
int idx = readBuffer(8);
|
||||
int r = readBuffer(9);
|
||||
int g = readBuffer(10);
|
||||
int b = readBuffer(11);
|
||||
led.reset(port,slot);
|
||||
if(idx>0)
|
||||
{
|
||||
led.setColorAt(idx-1,r,g,b);
|
||||
}
|
||||
else
|
||||
{
|
||||
led.setColor(r,g,b);
|
||||
}
|
||||
led.show();
|
||||
}
|
||||
break;
|
||||
case SERVO:{
|
||||
int slot = readBuffer(7);
|
||||
pin = slot==1?mePort[port].s1:mePort[port].s2;
|
||||
int v = readBuffer(8);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(!sv.attached())
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SEVSEG:{
|
||||
if(seg.getPort()!=port){
|
||||
seg.reset(port);
|
||||
}
|
||||
float v = readFloat(7);
|
||||
seg.display(v);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
generalDevice.dWrite1(v);
|
||||
}
|
||||
break;
|
||||
case SHUTTER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
if(v<2){
|
||||
generalDevice.dWrite1(v);
|
||||
}else{
|
||||
generalDevice.dWrite2(v-2);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
digitalWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case PWM:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
analogWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case TONE:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int hz = readShort(7);
|
||||
int ms = readShort(9);
|
||||
if(ms>0){
|
||||
buzzer.tone(pin, hz, ms);
|
||||
}else{
|
||||
buzzer.noTone(pin);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SERVO_PIN:{
|
||||
int v = readBuffer(7);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(!sv.attached())
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
lastTime = millis()/1000.0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int searchServoPin(int pin){
|
||||
for(int i=0;i<8;i++){
|
||||
if(servo_pins[i] == pin){
|
||||
return i;
|
||||
}
|
||||
if(servo_pins[i]==0){
|
||||
servo_pins[i] = pin;
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
void readSensor(int device){
|
||||
/**************************************************
|
||||
ff 55 len idx action device port slot data a
|
||||
0 1 2 3 4 5 6 7 8
|
||||
***************************************************/
|
||||
float value=0.0;
|
||||
int port,slot,pin;
|
||||
port = readBuffer(6);
|
||||
pin = port;
|
||||
switch(device){
|
||||
case ULTRASONIC_SENSOR:{
|
||||
if(us.getPort()!=port){
|
||||
us.reset(port);
|
||||
}
|
||||
value = us.distanceCm();
|
||||
writeHead();
|
||||
writeSerial(command_index);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case TEMPERATURE_SENSOR:{
|
||||
slot = readBuffer(7);
|
||||
if(ts.getPort()!=port||ts.getSlot()!=slot){
|
||||
ts.reset(port,slot);
|
||||
}
|
||||
value = ts.temperature();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:
|
||||
case SOUND_SENSOR:
|
||||
case POTENTIONMETER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.aRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
slot = readBuffer(7);
|
||||
if(joystick.getPort() != port){
|
||||
joystick.reset(port);
|
||||
}
|
||||
value = joystick.read(slot);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case INFRARED:
|
||||
{
|
||||
if(ir == NULL)
|
||||
{
|
||||
ir = new MeInfraredReceiver(port);
|
||||
ir->begin();
|
||||
}
|
||||
else if(ir->getPort() != port)
|
||||
{
|
||||
delete ir;
|
||||
ir = new MeInfraredReceiver(port);
|
||||
ir->begin();
|
||||
}
|
||||
irRead = ir->getCode();
|
||||
if((irRead < 255) && (irRead > 0))
|
||||
{
|
||||
sendFloat((float)irRead);
|
||||
}
|
||||
else
|
||||
{
|
||||
sendFloat(0);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case PIRMOTION:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LINEFOLLOWER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin1(),INPUT);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead1()*2+generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIMITSWITCH:{
|
||||
slot = readBuffer(7);
|
||||
if(generalDevice.getPort()!=port||generalDevice.getSlot()!=slot){
|
||||
generalDevice.reset(port,slot);
|
||||
}
|
||||
if(slot==1){
|
||||
pinMode(generalDevice.pin1(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead1();
|
||||
}else{
|
||||
pinMode(generalDevice.pin2(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead2();
|
||||
}
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
// case COMPASS:{
|
||||
// if(Compass.getPort()!=port){
|
||||
// Compass.reset(port);
|
||||
// Compass.setpin(Compass.pin1(),Compass.pin2());
|
||||
// }
|
||||
// double CompassAngle;
|
||||
// CompassAngle = Compass.getAngle();
|
||||
// sendDouble(CompassAngle);
|
||||
// }
|
||||
// break;
|
||||
case HUMITURE:{
|
||||
uint8_t index = readBuffer(7);
|
||||
if(humiture.getPort()!=port){
|
||||
humiture.reset(port);
|
||||
}
|
||||
uint8_t HumitureData;
|
||||
humiture.update();
|
||||
HumitureData = humiture.getValue(index);
|
||||
sendByte(HumitureData);
|
||||
}
|
||||
break;
|
||||
case FLAMESENSOR:{
|
||||
if(FlameSensor.getPort()!=port){
|
||||
FlameSensor.reset(port);
|
||||
FlameSensor.setpin(FlameSensor.pin2(),FlameSensor.pin1());
|
||||
}
|
||||
int16_t FlameData;
|
||||
FlameData = FlameSensor.readAnalog();
|
||||
sendShort(FlameData);
|
||||
}
|
||||
break;
|
||||
case GASSENSOR:{
|
||||
if(GasSensor.getPort()!=port){
|
||||
GasSensor.reset(port);
|
||||
GasSensor.setpin(GasSensor.pin2(),GasSensor.pin1());
|
||||
}
|
||||
int16_t GasData;
|
||||
GasData = GasSensor.readAnalog();
|
||||
sendShort(GasData);
|
||||
}
|
||||
break;
|
||||
case GYRO:{
|
||||
int axis = readBuffer(7);
|
||||
gyro.update();
|
||||
if(axis == 1){
|
||||
value = gyro.getAngleX();
|
||||
sendFloat(value);
|
||||
}else if(axis == 2){
|
||||
value = gyro.getAngleY();
|
||||
sendFloat(value);
|
||||
}else if(axis == 3){
|
||||
value = gyro.getAngleZ();
|
||||
sendFloat(value);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case VERSION:{
|
||||
sendString(mVersion);
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(digitalRead(pin));
|
||||
}
|
||||
break;
|
||||
case ANALOG:{
|
||||
pin = analogs[pin];
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(analogRead(pin));
|
||||
}
|
||||
break;
|
||||
case PULSEIN:{
|
||||
int pw = readShort(7);
|
||||
pinMode(pin, INPUT);
|
||||
sendShort(pulseIn(pin,HIGH,pw));
|
||||
}
|
||||
break;
|
||||
case ULTRASONIC_ARDUINO:{
|
||||
int trig = readBuffer(6);
|
||||
int echo = readBuffer(7);
|
||||
pinMode(trig,OUTPUT);
|
||||
digitalWrite(trig,LOW);
|
||||
delayMicroseconds(2);
|
||||
digitalWrite(trig,HIGH);
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(trig,LOW);
|
||||
pinMode(echo, INPUT);
|
||||
sendFloat(pulseIn(echo,HIGH,30000)/58.0);
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
sendFloat((float)currentTime);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
File diff suppressed because it is too large
Load Diff
|
|
@ -0,0 +1,28 @@
|
|||
1. 气体传感器,火焰传感器传输格式为 int16
|
||||
2. pulsein(35) 的编号修改成 37
|
||||
3. 默认开启的最小模式 直流电机,光线传感器,旋转电位器,声音传感器,摇杆,人体热射电传感器
|
||||
寻线传感器,快门线模块,限位器,按键,内部按键(mbot),火焰,气体,超声波模块,伺服舵机
|
||||
|
||||
4. 步进电机的距离用的是 long 结构
|
||||
|
||||
5. 编码电机的距离用的是 long 结构
|
||||
|
||||
资源情况:
|
||||
|
||||
RAM FLASH
|
||||
默认 1103(剩余945,最好不要使用超过450) 11184(剩余21072) UNO, mCore, Shield
|
||||
1136(剩余1424,最好不要超过785) 14460(剩余14212) 32U4
|
||||
|
||||
|
||||
|
||||
DEV_TEMPERATURE_SENSOR 18 1186
|
||||
DEV_GYRO 70 3144
|
||||
DEV_RGBLED 47 870
|
||||
DEV_SEVSEG 10 2710
|
||||
DEV_ENCODER 11 3874
|
||||
DEV_IR 59 2324
|
||||
DEV_INFRARED 57 2090
|
||||
DEV_HUMITURE 3 536
|
||||
DEV_COMPASS 330 5588
|
||||
DEV_LEDMATRIX 85 3072
|
||||
DEV_STEPPER 112 2978
|
||||
File diff suppressed because it is too large
Load Diff
|
|
@ -0,0 +1,815 @@
|
|||
/*************************************************************************
|
||||
* File Name : mbot_firmware.ino
|
||||
* Author : Ander, Mark Yan
|
||||
* Updated : Ander, Mark Yan
|
||||
* Version : V06.01.107
|
||||
* Date : 01/03/2017
|
||||
* Description : Firmware for Makeblock Electronic modules with Scratch.
|
||||
* License : CC-BY-SA 3.0
|
||||
* Copyright (C) 2013 - 2016 Maker Works Technology Co., Ltd. All right reserved.
|
||||
* http://www.makeblock.cc/
|
||||
**************************************************************************/
|
||||
#include <Wire.h>
|
||||
#include <MeMCore.h>
|
||||
|
||||
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;
|
||||
MeTouchSensor touchSensor;
|
||||
Me4Button buttonSensor;
|
||||
|
||||
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 = "06.01.107";
|
||||
boolean isAvailable = false;
|
||||
|
||||
int len = 52;
|
||||
char buffer[52];
|
||||
byte index = 0;
|
||||
byte dataLen;
|
||||
byte modulesLen=0;
|
||||
boolean isStart = false;
|
||||
char serialRead;
|
||||
uint8_t command_index = 0;
|
||||
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;
|
||||
|
||||
#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 TEMPERATURE_SENSOR_1 27
|
||||
#define DIGITAL 30
|
||||
#define ANALOG 31
|
||||
#define PWM 32
|
||||
#define SERVO_PIN 33
|
||||
#define TONE 34
|
||||
#define BUTTON_INNER 35
|
||||
#define ULTRASONIC_ARDUINO 36
|
||||
#define PULSEIN 37
|
||||
#define STEPPER 40
|
||||
#define LEDMATRIX 41
|
||||
#define TIMER 50
|
||||
#define TOUCH_SENSOR 51
|
||||
#define JOYSTICK_MOVE 52
|
||||
#define COMMON_COMMONCMD 60
|
||||
//Secondary command
|
||||
#define SET_STARTER_MODE 0x10
|
||||
#define SET_AURIGA_MODE 0x11
|
||||
#define SET_MEGAPI_MODE 0x12
|
||||
#define GET_BATTERY_POWER 0x70
|
||||
#define GET_AURIGA_MODE 0x71
|
||||
#define GET_MEGAPI_MODE 0x72
|
||||
#define ENCODER_BOARD 61
|
||||
//Read type
|
||||
#define ENCODER_BOARD_POS 0x01
|
||||
#define ENCODER_BOARD_SPEED 0x02
|
||||
|
||||
#define ENCODER_PID_MOTION 62
|
||||
//Secondary command
|
||||
#define ENCODER_BOARD_POS_MOTION 0x01
|
||||
#define ENCODER_BOARD_SPEED_MOTION 0x02
|
||||
#define ENCODER_BOARD_PWM_MOTION 0x03
|
||||
#define ENCODER_BOARD_SET_CUR_POS_ZERO 0x04
|
||||
#define ENCODER_BOARD_CAR_POS_MOTION 0x05
|
||||
|
||||
#define PM25SENSOR 63
|
||||
//Secondary command
|
||||
#define GET_PM1_0 0x01
|
||||
#define GET_PM2_5 0x02
|
||||
#define GET_PM10 0x03
|
||||
|
||||
#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;
|
||||
boolean buttonPressed = false;
|
||||
uint8_t keyPressed = KEY_NULL;
|
||||
|
||||
/*
|
||||
* function list
|
||||
*/
|
||||
void readButtonInner(uint8_t pin, int8_t s);
|
||||
void buzzerOn();
|
||||
void buzzerOff();
|
||||
unsigned char readBuffer(int index);
|
||||
void writeBuffer(int index,unsigned char c);
|
||||
void writeHead();
|
||||
void writeEnd();
|
||||
void writeSerial(unsigned char c);
|
||||
void readSerial();
|
||||
void parseData();
|
||||
void callOK();
|
||||
void sendByte(char c);
|
||||
void sendString(String s);
|
||||
void sendFloat(float value);
|
||||
void sendShort(double value);
|
||||
void sendDouble(double value);
|
||||
short readShort(int idx);
|
||||
float readFloat(int idx);
|
||||
char* readString(int idx,int len);
|
||||
uint8_t* readUint8(int idx,int len);
|
||||
void runModule(int device);
|
||||
int searchServoPin(int pin);
|
||||
void readSensor(int device);
|
||||
|
||||
|
||||
void readButtonInner(uint8_t pin, int8_t s)
|
||||
{
|
||||
pin = pgm_read_byte(&analogs[pin]);
|
||||
pinMode(pin,INPUT);
|
||||
boolean currentPressed = !(analogRead(pin)>10);
|
||||
|
||||
if(buttonPressed == currentPressed){
|
||||
return;
|
||||
}
|
||||
buttonPressed = currentPressed;
|
||||
writeHead();
|
||||
writeSerial(0x80);
|
||||
sendByte(currentPressed);
|
||||
writeEnd();
|
||||
}
|
||||
|
||||
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);
|
||||
command_index = (uint8_t)idx;
|
||||
int action = readBuffer(4);
|
||||
int device = readBuffer(5);
|
||||
switch(action){
|
||||
case GET:{
|
||||
if(device != ULTRASONIC_SENSOR){
|
||||
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<l;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<len;i++){
|
||||
_receiveStr[i]=readBuffer(idx+i);
|
||||
}
|
||||
_receiveStr[len] = '\0';
|
||||
return _receiveStr;
|
||||
}
|
||||
uint8_t* readUint8(int idx,int len){
|
||||
for(int i=0;i<len;i++){
|
||||
if(i>15){
|
||||
break;
|
||||
}
|
||||
_receiveUint8[i] = readBuffer(idx+i);
|
||||
}
|
||||
return _receiveUint8;
|
||||
}
|
||||
void runModule(int device){
|
||||
//0xff 0x55 0x6 0x0 0x2 0x22 0x9 0x0 0x0 0xa
|
||||
int port = readBuffer(6);
|
||||
int pin = port;
|
||||
switch(device){
|
||||
case MOTOR:{
|
||||
int speed = readShort(7);
|
||||
if(dc.getPort()!=port){
|
||||
dc.reset(port);
|
||||
}
|
||||
dc.run(speed);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
int leftSpeed = readShort(6);
|
||||
dc.reset(M1);
|
||||
dc.run(leftSpeed);
|
||||
int rightSpeed = readShort(8);
|
||||
dc.reset(M2);
|
||||
dc.run(rightSpeed);
|
||||
}
|
||||
break;
|
||||
case RGBLED:{
|
||||
int slot = readBuffer(7);
|
||||
int idx = readBuffer(8);
|
||||
int r = readBuffer(9);
|
||||
int g = readBuffer(10);
|
||||
int b = readBuffer(11);
|
||||
if((led.getPort() != port) || led.getSlot() != slot)
|
||||
{
|
||||
led.reset(port,slot);
|
||||
}
|
||||
if(idx>0)
|
||||
{
|
||||
led.setColorAt(idx-1,r,g,b);
|
||||
}
|
||||
else
|
||||
{
|
||||
led.setColor(r,g,b);
|
||||
}
|
||||
led.show();
|
||||
}
|
||||
break;
|
||||
case SERVO:{
|
||||
int slot = readBuffer(7);
|
||||
pin = slot==1?mePort[port].s1:mePort[port].s2;
|
||||
int v = readBuffer(8);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(!sv.attached())
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SEVSEG:{
|
||||
if(seg.getPort()!=port){
|
||||
seg.reset(port);
|
||||
}
|
||||
float v = readFloat(7);
|
||||
seg.display(v);
|
||||
}
|
||||
break;
|
||||
case LEDMATRIX:{
|
||||
if(ledMx.getPort()!=port){
|
||||
ledMx.reset(port);
|
||||
}
|
||||
int action = readBuffer(7);
|
||||
if(action==1){
|
||||
int px = buffer[8];
|
||||
int py = buffer[9];
|
||||
int len = readBuffer(10);
|
||||
char *s = readString(11,len);
|
||||
ledMx.drawStr(px,py,s);
|
||||
}else if(action==2){
|
||||
int px = readBuffer(8);
|
||||
int py = readBuffer(9);
|
||||
uint8_t *ss = readUint8(10,16);
|
||||
ledMx.drawBitmap(px,py,16,ss);
|
||||
}else if(action==3){
|
||||
int point = readBuffer(8);
|
||||
int hours = readBuffer(9);
|
||||
int minutes = readBuffer(10);
|
||||
ledMx.showClock(hours,minutes,point);
|
||||
}else if(action == 4){
|
||||
ledMx.showNum(readFloat(8),3);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
generalDevice.dWrite1(v);
|
||||
}
|
||||
break;
|
||||
case IR:{
|
||||
String Str_data;
|
||||
int len = readBuffer(2)-3;
|
||||
for(int i=0;i<len;i++){
|
||||
Str_data+=(char)readBuffer(6+i);
|
||||
}
|
||||
ir.sendString(Str_data);
|
||||
Str_data = "";
|
||||
}
|
||||
break;
|
||||
case SHUTTER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
if(v<2){
|
||||
generalDevice.dWrite1(v);
|
||||
}else{
|
||||
generalDevice.dWrite2(v-2);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
digitalWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case PWM:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
analogWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case TONE:{
|
||||
int hz = readShort(6);
|
||||
int tone_time = readShort(8);
|
||||
if(hz>0){
|
||||
buzzer.tone(hz,tone_time);
|
||||
}else{
|
||||
buzzer.noTone();
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SERVO_PIN:{
|
||||
int v = readBuffer(7);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(!sv.attached())
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
lastTime = millis()/1000.0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int searchServoPin(int pin){
|
||||
for(int i=0;i<8;i++){
|
||||
if(servo_pins[i] == pin){
|
||||
return i;
|
||||
}
|
||||
if(servo_pins[i]==0){
|
||||
servo_pins[i] = pin;
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
void readSensor(int device){
|
||||
/**************************************************
|
||||
ff 55 len idx action device port slot data a
|
||||
0 1 2 3 4 5 6 7 8
|
||||
0xff 0x55 0x4 0x3 0x1 0x1 0x1 0xa
|
||||
***************************************************/
|
||||
float value=0.0;
|
||||
int port,slot,pin;
|
||||
port = readBuffer(6);
|
||||
pin = port;
|
||||
switch(device){
|
||||
case ULTRASONIC_SENSOR:{
|
||||
if(us.getPort()!=port){
|
||||
us.reset(port);
|
||||
}
|
||||
value = (float)us.distanceCm();
|
||||
writeHead();
|
||||
writeSerial(command_index);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case TEMPERATURE_SENSOR:{
|
||||
slot = readBuffer(7);
|
||||
if(ts.getPort()!=port||ts.getSlot()!=slot){
|
||||
ts.reset(port,slot);
|
||||
}
|
||||
value = ts.temperature();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:
|
||||
case SOUND_SENSOR:
|
||||
case POTENTIONMETER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.aRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
slot = readBuffer(7);
|
||||
if(joystick.getPort() != port){
|
||||
joystick.reset(port);
|
||||
}
|
||||
value = joystick.read(slot);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case IR:{
|
||||
if(irReady){
|
||||
sendString(irBuffer);
|
||||
irReady = false;
|
||||
irBuffer = "";
|
||||
}
|
||||
}
|
||||
break;
|
||||
case IRREMOTE:{
|
||||
unsigned char r = readBuffer(7);
|
||||
if(millis()/1000.0-lastIRTime>0.2){
|
||||
sendByte(0);
|
||||
}else{
|
||||
sendByte(irRead==r);
|
||||
}
|
||||
//irRead = 0;
|
||||
irIndex = 0;
|
||||
}
|
||||
break;
|
||||
case IRREMOTECODE:{
|
||||
if(irRead<0xff){
|
||||
sendByte(irRead);
|
||||
}
|
||||
irRead = 0;
|
||||
irIndex = 0;
|
||||
}
|
||||
break;
|
||||
case PIRMOTION:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LINEFOLLOWER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin1(),INPUT);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead1()*2+generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIMITSWITCH:{
|
||||
slot = readBuffer(7);
|
||||
if(generalDevice.getPort()!=port||generalDevice.getSlot()!=slot){
|
||||
generalDevice.reset(port,slot);
|
||||
}
|
||||
if(slot==1){
|
||||
pinMode(generalDevice.pin1(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead1();
|
||||
}else{
|
||||
pinMode(generalDevice.pin2(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead2();
|
||||
}
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case BUTTON_INNER:{
|
||||
//pin = analogs[pin];
|
||||
pin = pgm_read_byte(&analogs[pin]);
|
||||
char s = readBuffer(7);
|
||||
pinMode(pin,INPUT);
|
||||
boolean currentPressed = !(analogRead(pin)>10);
|
||||
sendByte(s^(currentPressed?1:0));
|
||||
buttonPressed = currentPressed;
|
||||
}
|
||||
break;
|
||||
case COMPASS:{
|
||||
if(Compass.getPort()!=port){
|
||||
Compass.reset(port);
|
||||
Compass.setpin(Compass.pin1(),Compass.pin2());
|
||||
}
|
||||
sendFloat(Compass.getAngle());
|
||||
}
|
||||
break;
|
||||
case HUMITURE:{
|
||||
uint8_t index = readBuffer(7);
|
||||
if(humiture.getPort()!=port){
|
||||
humiture.reset(port);
|
||||
}
|
||||
uint8_t HumitureData;
|
||||
humiture.update();
|
||||
HumitureData = humiture.getValue(index);
|
||||
sendByte(HumitureData);
|
||||
}
|
||||
break;
|
||||
case FLAMESENSOR:{
|
||||
if(FlameSensor.getPort()!=port){
|
||||
FlameSensor.reset(port);
|
||||
FlameSensor.setpin(FlameSensor.pin2(),FlameSensor.pin1());
|
||||
}
|
||||
int16_t FlameData;
|
||||
FlameData = FlameSensor.readAnalog();
|
||||
sendShort(FlameData);
|
||||
}
|
||||
break;
|
||||
case GASSENSOR:{
|
||||
if(GasSensor.getPort()!=port){
|
||||
GasSensor.reset(port);
|
||||
GasSensor.setpin(GasSensor.pin2(),GasSensor.pin1());
|
||||
}
|
||||
int16_t GasData;
|
||||
GasData = GasSensor.readAnalog();
|
||||
sendShort(GasData);
|
||||
}
|
||||
break;
|
||||
case GYRO:{
|
||||
int axis = readBuffer(7);
|
||||
gyro.update();
|
||||
value = gyro.getAngle(axis);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case VERSION:{
|
||||
sendString(mVersion);
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(digitalRead(pin));
|
||||
}
|
||||
break;
|
||||
case ANALOG:{
|
||||
//pin = analogs[pin];
|
||||
pin = pgm_read_byte(&analogs[pin]);
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(analogRead(pin));
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
sendFloat(currentTime);
|
||||
}
|
||||
break;
|
||||
case TOUCH_SENSOR:
|
||||
{
|
||||
if(touchSensor.getPort() != port){
|
||||
touchSensor.reset(port);
|
||||
}
|
||||
sendByte(touchSensor.touched());
|
||||
}
|
||||
break;
|
||||
case BUTTON:
|
||||
{
|
||||
if(buttonSensor.getPort() != port){
|
||||
buttonSensor.reset(port);
|
||||
}
|
||||
sendByte(keyPressed == readBuffer(7));
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void setup(){
|
||||
pinMode(13,OUTPUT);
|
||||
digitalWrite(13,HIGH);
|
||||
delay(300);
|
||||
digitalWrite(13,LOW);
|
||||
Serial.begin(115200);
|
||||
delay(500);
|
||||
buzzer.tone(500,50);
|
||||
delay(50);
|
||||
buzzerOff();
|
||||
ir.begin();
|
||||
led.setpin(13);
|
||||
led.setColor(0,0,0);
|
||||
led.show();
|
||||
gyro.begin();
|
||||
Serial.print("Version: ");
|
||||
Serial.println(mVersion);
|
||||
ledMx.setBrightness(6);
|
||||
ledMx.setColorIndex(1);
|
||||
}
|
||||
|
||||
void loop(){
|
||||
readButtonInner(7,0);
|
||||
keyPressed = buttonSensor.pressed();
|
||||
currentTime = millis()/1000.0-lastTime;
|
||||
if(ir.decode())
|
||||
{
|
||||
irRead = ((ir.value>>8)>>8)&0xff;
|
||||
lastIRTime = millis()/1000.0;
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,731 @@
|
|||
/*************************************************************************
|
||||
* File Name : mega2560_firmware.ino
|
||||
* Author : Ander, Mark Yan
|
||||
* Updated : Ander, Mark Yan
|
||||
* Version : V0d.01.105
|
||||
* Date : 07/06/2016
|
||||
* Description : Firmware for Makeblock Electronic modules with Scratch.
|
||||
* License : CC-BY-SA 3.0
|
||||
* Copyright (C) 2013 - 2016 Maker Works Technology Co., Ltd. All right reserved.
|
||||
* http://www.makeblock.cc/
|
||||
**************************************************************************/
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
#include <Arduino.h>
|
||||
#include <MeOrion.h>
|
||||
|
||||
Servo servos[8];
|
||||
MeDCMotor dc;
|
||||
MeTemperature ts;
|
||||
MeRGBLed led;
|
||||
MeUltrasonicSensor us;
|
||||
Me7SegmentDisplay seg;
|
||||
MePort generalDevice;
|
||||
MeInfraredReceiver *ir = NULL;
|
||||
MeGyro gyro;
|
||||
MeJoystick joystick;
|
||||
MeStepper steppers[2];
|
||||
MeBuzzer buzzer;
|
||||
MeHumiture humiture;
|
||||
MeFlameSensor FlameSensor;
|
||||
MeGasSensor GasSensor;
|
||||
MeTouchSensor touchSensor;
|
||||
Me4Button buttonSensor;
|
||||
|
||||
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;
|
||||
MeModule modules[12];
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
int analogs[12]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11};
|
||||
#endif
|
||||
#if defined(__AVR_ATmega328P__) or defined(__AVR_ATmega168__)
|
||||
int analogs[8]={A0,A1,A2,A3,A4,A5,A6,A7};
|
||||
MeEncoderMotor encoders[2];
|
||||
#endif
|
||||
#if defined(__AVR_ATmega1280__)|| defined(__AVR_ATmega2560__)
|
||||
int analogs[16]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15};
|
||||
#endif
|
||||
String mVersion = "0d.01.105";
|
||||
boolean isAvailable = false;
|
||||
boolean isBluetooth = false;
|
||||
|
||||
int len = 52;
|
||||
char buffer[52];
|
||||
char bufferBt[52];
|
||||
byte index = 0;
|
||||
byte dataLen;
|
||||
byte modulesLen=0;
|
||||
boolean isStart = false;
|
||||
unsigned char irRead;
|
||||
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 PULSEIN 37
|
||||
#define ULTRASONIC_ARDUINO 36
|
||||
#define STEPPER 40
|
||||
#define LEDMATRIX 41
|
||||
#define TIMER 50
|
||||
#define TOUCH_SENSOR 51
|
||||
|
||||
#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;
|
||||
double lastTime = 0.0;
|
||||
double currentTime = 0.0;
|
||||
uint8_t keyPressed = 0;
|
||||
uint8_t command_index = 0;
|
||||
|
||||
void setup(){
|
||||
pinMode(13,OUTPUT);
|
||||
digitalWrite(13,HIGH);
|
||||
delay(300);
|
||||
digitalWrite(13,LOW);
|
||||
Serial.begin(115200);
|
||||
delay(500);
|
||||
buzzerOn();
|
||||
delay(100);
|
||||
buzzerOff();
|
||||
#if defined(__AVR_ATmega328P__) or defined(__AVR_ATmega168__)
|
||||
encoders[0] = MeEncoderMotor(SLOT_1);
|
||||
encoders[1] = MeEncoderMotor(SLOT_2);
|
||||
encoders[0].begin();
|
||||
encoders[1].begin();
|
||||
delay(500);
|
||||
encoders[0].runSpeed(0);
|
||||
encoders[1].runSpeed(0);
|
||||
#else
|
||||
Serial1.begin(115200);
|
||||
#endif
|
||||
gyro.begin();
|
||||
Serial.print("Version: ");
|
||||
Serial.println(mVersion);
|
||||
}
|
||||
void loop(){
|
||||
keyPressed = buttonSensor.pressed();
|
||||
currentTime = millis()/1000.0-lastTime;
|
||||
if(ir != NULL)
|
||||
{
|
||||
ir->loop();
|
||||
}
|
||||
readSerial();
|
||||
steppers[0].runSpeedToPosition();
|
||||
steppers[1].runSpeedToPosition();
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
unsigned char readBuffer(int index){
|
||||
return isBluetooth?bufferBt[index]:buffer[index];
|
||||
}
|
||||
void writeBuffer(int index,unsigned char c){
|
||||
if(isBluetooth){
|
||||
bufferBt[index]=c;
|
||||
}else{
|
||||
buffer[index]=c;
|
||||
}
|
||||
}
|
||||
void writeHead(){
|
||||
writeSerial(0xff);
|
||||
writeSerial(0x55);
|
||||
}
|
||||
void writeEnd(){
|
||||
Serial.println();
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
Serial1.println();
|
||||
#endif
|
||||
}
|
||||
void writeSerial(unsigned char c){
|
||||
Serial.write(c);
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
Serial1.write(c);
|
||||
#endif
|
||||
}
|
||||
void readSerial(){
|
||||
isAvailable = false;
|
||||
if(Serial.available()>0){
|
||||
isAvailable = true;
|
||||
isBluetooth = false;
|
||||
serialRead = Serial.read();
|
||||
}
|
||||
//#if defined(__AVR_ATmega32U4__)
|
||||
// if(Serial1.available()>0){
|
||||
// isAvailable = true;
|
||||
// isBluetooth = false;
|
||||
// serialRead = Serial1.read();
|
||||
// }
|
||||
// #endif
|
||||
}
|
||||
/*
|
||||
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);
|
||||
command_index = (uint8_t)idx;
|
||||
int action = readBuffer(4);
|
||||
int device = readBuffer(5);
|
||||
switch(action){
|
||||
case GET:{
|
||||
if(device != ULTRASONIC_SENSOR){
|
||||
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);
|
||||
dc.reset(PORT_1);
|
||||
dc.run(0);
|
||||
dc.reset(PORT_2);
|
||||
dc.run(0);
|
||||
|
||||
#if defined(__AVR_ATmega328P__)
|
||||
encoders[0].runSpeed(0);
|
||||
encoders[1].runSpeed(0);
|
||||
#endif
|
||||
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<l;i++){
|
||||
writeSerial(s.charAt(i));
|
||||
}
|
||||
}
|
||||
void sendFloat(float value){
|
||||
writeSerial(0x2);
|
||||
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]);
|
||||
}
|
||||
void sendDouble(double value){
|
||||
writeSerial(2);
|
||||
valDouble.doubleVal = value;
|
||||
writeSerial(valDouble.byteVal[0]);
|
||||
writeSerial(valDouble.byteVal[1]);
|
||||
writeSerial(valDouble.byteVal[2]);
|
||||
writeSerial(valDouble.byteVal[3]);
|
||||
}
|
||||
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;
|
||||
}
|
||||
long readLong(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.longVal;
|
||||
}
|
||||
void runModule(int device){
|
||||
//0xff 0x55 0x6 0x0 0x1 0xa 0x9 0x0 0x0 0xa
|
||||
int port = readBuffer(6);
|
||||
int pin = port;
|
||||
switch(device){
|
||||
case MOTOR:{
|
||||
int speed = readShort(7);
|
||||
dc.reset(port);
|
||||
dc.run(speed);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
int leftSpeed = readShort(6);
|
||||
dc.reset(M1);
|
||||
dc.run(leftSpeed);
|
||||
int rightSpeed = readShort(8);
|
||||
dc.reset(M2);
|
||||
dc.run(rightSpeed);
|
||||
}
|
||||
break;
|
||||
case STEPPER:{
|
||||
int maxSpeed = readShort(7);
|
||||
long distance = readLong(9);
|
||||
if(port==PORT_1){
|
||||
steppers[0] = MeStepper(PORT_1);
|
||||
steppers[0].moveTo(distance);
|
||||
steppers[0].setMaxSpeed(maxSpeed);
|
||||
steppers[0].setSpeed(maxSpeed);
|
||||
}else if(port==PORT_2){
|
||||
steppers[1] = MeStepper(PORT_2);
|
||||
steppers[1].moveTo(distance);
|
||||
steppers[1].setMaxSpeed(maxSpeed);
|
||||
steppers[1].setSpeed(maxSpeed);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case ENCODER:{
|
||||
int slot = readBuffer(7);
|
||||
int maxSpeed = readShort(8);
|
||||
float distance = readFloat(10);
|
||||
#if defined(__AVR_ATmega328P__)
|
||||
if(slot==SLOT_1){
|
||||
encoders[0].move(distance,maxSpeed);
|
||||
}else if(slot==SLOT_2){
|
||||
encoders[1].move(distance,maxSpeed);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
case RGBLED:{
|
||||
int slot = readBuffer(7);
|
||||
int idx = readBuffer(8);
|
||||
int r = readBuffer(9);
|
||||
int g = readBuffer(10);
|
||||
int b = readBuffer(11);
|
||||
led.reset(port,slot);
|
||||
if(idx>0)
|
||||
{
|
||||
led.setColorAt(idx-1,r,g,b);
|
||||
}
|
||||
else
|
||||
{
|
||||
led.setColor(r,g,b);
|
||||
}
|
||||
led.show();
|
||||
}
|
||||
break;
|
||||
case SERVO:{
|
||||
int slot = readBuffer(7);
|
||||
pin = slot==1?mePort[port].s1:mePort[port].s2;
|
||||
int v = readBuffer(8);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(!sv.attached())
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SEVSEG:{
|
||||
if(seg.getPort()!=port){
|
||||
seg.reset(port);
|
||||
}
|
||||
float v = readFloat(7);
|
||||
seg.display(v);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
generalDevice.dWrite1(v);
|
||||
}
|
||||
break;
|
||||
case SHUTTER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
if(v<2){
|
||||
generalDevice.dWrite1(v);
|
||||
}else{
|
||||
generalDevice.dWrite2(v-2);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
digitalWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case PWM:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
analogWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case TONE:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int hz = readShort(7);
|
||||
int ms = readShort(9);
|
||||
if(ms>0){
|
||||
buzzer.tone(pin, hz, ms);
|
||||
}else{
|
||||
buzzer.noTone(pin);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SERVO_PIN:{
|
||||
int v = readBuffer(7);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(!sv.attached())
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
lastTime = millis()/1000.0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int searchServoPin(int pin){
|
||||
for(int i=0;i<8;i++){
|
||||
if(servo_pins[i] == pin){
|
||||
return i;
|
||||
}
|
||||
if(servo_pins[i]==0){
|
||||
servo_pins[i] = pin;
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
void readSensor(int device){
|
||||
/**************************************************
|
||||
ff 55 len idx action device port slot data a
|
||||
0 1 2 3 4 5 6 7 8
|
||||
***************************************************/
|
||||
float value=0.0;
|
||||
int port,slot,pin;
|
||||
port = readBuffer(6);
|
||||
pin = port;
|
||||
switch(device){
|
||||
case ULTRASONIC_SENSOR:{
|
||||
if(us.getPort()!=port){
|
||||
us.reset(port);
|
||||
}
|
||||
value = us.distanceCm();
|
||||
writeHead();
|
||||
writeSerial(command_index);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case TEMPERATURE_SENSOR:{
|
||||
slot = readBuffer(7);
|
||||
if(ts.getPort()!=port||ts.getSlot()!=slot){
|
||||
ts.reset(port,slot);
|
||||
}
|
||||
value = ts.temperature();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:
|
||||
case SOUND_SENSOR:
|
||||
case POTENTIONMETER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.aRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
slot = readBuffer(7);
|
||||
if(joystick.getPort() != port){
|
||||
joystick.reset(port);
|
||||
}
|
||||
value = joystick.read(slot);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case INFRARED:
|
||||
{
|
||||
if(ir == NULL)
|
||||
{
|
||||
ir = new MeInfraredReceiver(port);
|
||||
ir->begin();
|
||||
}
|
||||
else if(ir->getPort() != port)
|
||||
{
|
||||
delete ir;
|
||||
ir = new MeInfraredReceiver(port);
|
||||
ir->begin();
|
||||
}
|
||||
irRead = ir->getCode();
|
||||
if((irRead < 255) && (irRead > 0))
|
||||
{
|
||||
sendFloat((float)irRead);
|
||||
}
|
||||
else
|
||||
{
|
||||
sendFloat(0);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case PIRMOTION:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LINEFOLLOWER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin1(),INPUT);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead1()*2+generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIMITSWITCH:{
|
||||
slot = readBuffer(7);
|
||||
if(generalDevice.getPort()!=port||generalDevice.getSlot()!=slot){
|
||||
generalDevice.reset(port,slot);
|
||||
}
|
||||
if(slot==1){
|
||||
pinMode(generalDevice.pin1(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead1();
|
||||
}else{
|
||||
pinMode(generalDevice.pin2(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead2();
|
||||
}
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
// case COMPASS:{
|
||||
// if(Compass.getPort()!=port){
|
||||
// Compass.reset(port);
|
||||
// Compass.setpin(Compass.pin1(),Compass.pin2());
|
||||
// }
|
||||
// double CompassAngle;
|
||||
// CompassAngle = Compass.getAngle();
|
||||
// sendDouble(CompassAngle);
|
||||
// }
|
||||
// break;
|
||||
case HUMITURE:{
|
||||
uint8_t index = readBuffer(7);
|
||||
if(humiture.getPort()!=port){
|
||||
humiture.reset(port);
|
||||
}
|
||||
uint8_t HumitureData;
|
||||
humiture.update();
|
||||
HumitureData = humiture.getValue(index);
|
||||
sendByte(HumitureData);
|
||||
}
|
||||
break;
|
||||
case FLAMESENSOR:{
|
||||
if(FlameSensor.getPort()!=port){
|
||||
FlameSensor.reset(port);
|
||||
FlameSensor.setpin(FlameSensor.pin2(),FlameSensor.pin1());
|
||||
}
|
||||
int16_t FlameData;
|
||||
FlameData = FlameSensor.readAnalog();
|
||||
sendShort(FlameData);
|
||||
}
|
||||
break;
|
||||
case GASSENSOR:{
|
||||
if(GasSensor.getPort()!=port){
|
||||
GasSensor.reset(port);
|
||||
GasSensor.setpin(GasSensor.pin2(),GasSensor.pin1());
|
||||
}
|
||||
int16_t GasData;
|
||||
GasData = GasSensor.readAnalog();
|
||||
sendShort(GasData);
|
||||
}
|
||||
break;
|
||||
case GYRO:{
|
||||
int axis = readBuffer(7);
|
||||
gyro.update();
|
||||
if(axis == 1){
|
||||
value = gyro.getAngleX();
|
||||
sendFloat(value);
|
||||
}else if(axis == 2){
|
||||
value = gyro.getAngleY();
|
||||
sendFloat(value);
|
||||
}else if(axis == 3){
|
||||
value = gyro.getAngleZ();
|
||||
sendFloat(value);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case VERSION:{
|
||||
sendString(mVersion);
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(digitalRead(pin));
|
||||
}
|
||||
break;
|
||||
case ANALOG:{
|
||||
pin = analogs[pin];
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(analogRead(pin));
|
||||
}
|
||||
break;
|
||||
case PULSEIN:{
|
||||
int pw = readShort(7);
|
||||
pinMode(pin, INPUT);
|
||||
sendShort(pulseIn(pin,HIGH,pw));
|
||||
}
|
||||
break;
|
||||
case ULTRASONIC_ARDUINO:{
|
||||
int trig = readBuffer(6);
|
||||
int echo = readBuffer(7);
|
||||
pinMode(trig,OUTPUT);
|
||||
digitalWrite(trig,LOW);
|
||||
delayMicroseconds(2);
|
||||
digitalWrite(trig,HIGH);
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(trig,LOW);
|
||||
pinMode(echo, INPUT);
|
||||
sendFloat(pulseIn(echo,HIGH,30000)/58.0);
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
sendFloat((float)currentTime);
|
||||
}
|
||||
break;
|
||||
case TOUCH_SENSOR:
|
||||
{
|
||||
if(touchSensor.getPort() != port){
|
||||
touchSensor.reset(port);
|
||||
}
|
||||
sendByte(touchSensor.touched());
|
||||
}
|
||||
break;
|
||||
case BUTTON:
|
||||
{
|
||||
if(buttonSensor.getPort() != port){
|
||||
buttonSensor.reset(port);
|
||||
}
|
||||
sendByte(keyPressed == readBuffer(7));
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,104 @@
|
|||
float RELAX_ANGLE = 0; //<2F>
|
||||
void WriteBalancedDataToEEPROM(void)
|
||||
{
|
||||
EEPROM.write(BALANCED_CAR_PARTITION_CHECK, EEPROM_IF_HAVEPID_CHECK1);
|
||||
EEPROM.write(BALANCED_CAR_PARTITION_CHECK + 1, EEPROM_IF_HAVEPID_CHECK2);
|
||||
EEPROM.write(BALANCED_CAR_START_ADDR, EEPROM_CHECK_START);
|
||||
|
||||
EEPROM.put(BALANCED_CAR_NATURAL_BALANCE, RELAX_ANGLE);
|
||||
EEPROM.put(BALANCED_CAR_ANGLE_PID_ADDR, PID_angle.P);
|
||||
EEPROM.put(BALANCED_CAR_ANGLE_PID_ADDR+4, PID_angle.I);
|
||||
EEPROM.put(BALANCED_CAR_ANGLE_PID_ADDR+8, PID_angle.D);
|
||||
|
||||
EEPROM.put(BALANCED_CAR_SPEED_PID_ADDR, PID_speed.P);
|
||||
EEPROM.put(BALANCED_CAR_SPEED_PID_ADDR+4, PID_speed.I);
|
||||
EEPROM.put(BALANCED_CAR_SPEED_PID_ADDR+8, PID_speed.D);
|
||||
|
||||
EEPROM.put(BALANCED_CAR_DIR_PID_ADDR, PID_turn.P);
|
||||
EEPROM.write(BALANCED_CAR_END_ADDR, EEPROM_CHECK_END);
|
||||
|
||||
EEPROM.write(AURIGA_MODE_START_ADDR, EEPROM_CHECK_START);
|
||||
EEPROM.write(BALANCED_CAR_SPEED_PID_ADDR, megapi_mode);
|
||||
EEPROM.write(AURIGA_MODE_END_ADDR, EEPROM_CHECK_END);
|
||||
}
|
||||
|
||||
void WriteAurigaModeToEEPROM(void)
|
||||
{
|
||||
EEPROM.write(MEGAPI_MODE_PARTITION_CHECK, EEPROM_IF_HAVEPID_CHECK1);
|
||||
EEPROM.write(MEGAPI_MODE_PARTITION_CHECK + 1, EEPROM_IF_HAVEPID_CHECK2);
|
||||
EEPROM.write(MEGAPI_MODE_START_ADDR, EEPROM_CHECK_START);
|
||||
EEPROM.write(MEGAPI_MODE_CONFIGURE, megapi_mode);
|
||||
EEPROM.write(MEGAPI_MODE_END_ADDR, EEPROM_CHECK_END);
|
||||
}
|
||||
|
||||
int readEEPROM(void)
|
||||
{
|
||||
if((EEPROM.read(BALANCED_CAR_PARTITION_CHECK) == EEPROM_IF_HAVEPID_CHECK1) && (EEPROM.read(BALANCED_CAR_PARTITION_CHECK + 1) == EEPROM_IF_HAVEPID_CHECK2))
|
||||
{
|
||||
if((EEPROM.read(BALANCED_CAR_START_ADDR) == EEPROM_CHECK_START) && (EEPROM.read(BALANCED_CAR_END_ADDR) == EEPROM_CHECK_END))
|
||||
{
|
||||
EEPROM.get(BALANCED_CAR_NATURAL_BALANCE, RELAX_ANGLE);
|
||||
EEPROM.get(BALANCED_CAR_ANGLE_PID_ADDR, PID_angle.P);
|
||||
EEPROM.get(BALANCED_CAR_ANGLE_PID_ADDR+4, PID_angle.I);
|
||||
EEPROM.get(BALANCED_CAR_ANGLE_PID_ADDR+8, PID_angle.D);
|
||||
|
||||
EEPROM.get(BALANCED_CAR_SPEED_PID_ADDR, PID_speed.P);
|
||||
EEPROM.get(BALANCED_CAR_SPEED_PID_ADDR+4, PID_speed.I);
|
||||
EEPROM.get(BALANCED_CAR_SPEED_PID_ADDR+8, PID_speed.D);
|
||||
|
||||
EEPROM.get(BALANCED_CAR_DIR_PID_ADDR, PID_turn.P);
|
||||
#ifdef DEBUG_INFO
|
||||
Serial.println( "Read data from EEPROM:");
|
||||
Serial.print(RELAX_ANGLE);
|
||||
Serial.print( " ");
|
||||
Serial.print(PID_angle.P);
|
||||
Serial.print( " ");
|
||||
Serial.print(PID_angle.I);
|
||||
Serial.print( " ");
|
||||
Serial.print(PID_angle.D);
|
||||
Serial.print( " ");
|
||||
Serial.print(PID_speed.P);
|
||||
Serial.print( " ");
|
||||
Serial.print(PID_speed.I);
|
||||
Serial.print( " ");
|
||||
Serial.print(PID_speed.D);
|
||||
Serial.print( " ");
|
||||
Serial.println(PID_turn.P);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.println( "Data area damage on balanced car pid!" );
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
#ifdef DEBUG_INFO
|
||||
Serial.println( "First written Balanced data!" );
|
||||
#endif
|
||||
WriteBalancedDataToEEPROM();
|
||||
}
|
||||
|
||||
if((EEPROM.read(AURIGA_MODE_PARTITION_CHECK) == EEPROM_IF_HAVEPID_CHECK1) && (EEPROM.read(AURIGA_MODE_PARTITION_CHECK + 1) == EEPROM_IF_HAVEPID_CHECK2))
|
||||
{
|
||||
if((EEPROM.read(AURIGA_MODE_START_ADDR) == EEPROM_CHECK_START) && (EEPROM.read(AURIGA_MODE_END_ADDR) == EEPROM_CHECK_END))
|
||||
{
|
||||
EEPROM.get(AURIGA_MODE_CONFIGURE, megapi_mode);
|
||||
#ifdef DEBUG_INFO
|
||||
Serial.print( "Read auriga_mode from EEPROM:");
|
||||
Serial.println(auriga_mode);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.println( "Data area damage on auriga mode!" );
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
#ifdef DEBUG_INFO
|
||||
Serial.println( "First written auriga mode!" );
|
||||
#endif
|
||||
WriteAurigaModeToEEPROM();
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,168 @@
|
|||
void encodersInit()
|
||||
{
|
||||
encoders[0].reset(SLOT1);
|
||||
encoders[1].reset(SLOT2);
|
||||
encoders[2].reset(SLOT3);
|
||||
encoders[3].reset(SLOT4);
|
||||
attachInterrupt(encoders[0].getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(encoders[1].getIntNum(), isr_process_encoder2, RISING);
|
||||
attachInterrupt(encoders[2].getIntNum(), isr_process_encoder3, RISING);
|
||||
attachInterrupt(encoders[3].getIntNum(), isr_process_encoder4, RISING);
|
||||
|
||||
measurement_speed_time = lasttime_speed = lasttime_angle = millis();
|
||||
encoders[0].setPulsePos(0);
|
||||
encoders[1].setPulsePos(0);
|
||||
encoders[2].setPulsePos(0);
|
||||
encoders[3].setPulsePos(0);
|
||||
PID_speed_left.Setpoint = 0;
|
||||
PID_speed_right.Setpoint = 0;
|
||||
}
|
||||
void encodersUpdate()
|
||||
{
|
||||
for(int i=0;i<4;i++)
|
||||
{
|
||||
encoders[i].loop();
|
||||
}
|
||||
}
|
||||
void onEncoderMovingFinish(int slot,int extId)
|
||||
{
|
||||
writeHead();
|
||||
writeSerial(extId);
|
||||
sendByte(slot);
|
||||
writeEnd();
|
||||
}
|
||||
void PWM_Calcu()
|
||||
{
|
||||
double speed1;
|
||||
double speed2;
|
||||
if((millis() - lasttime_speed) > 20)
|
||||
{
|
||||
speed1 = encoders[0].getCurrentSpeed();
|
||||
speed2 = encoders[1].getCurrentSpeed();
|
||||
|
||||
#ifdef DEBUG_INFO
|
||||
Serial.print("S1: ");
|
||||
Serial.print(speed1);
|
||||
Serial.print(" S2: ");
|
||||
Serial.print(speed2);
|
||||
Serial.print("left: ");
|
||||
Serial.print(PID_speed_left.Setpoint);
|
||||
Serial.print(" right: ");
|
||||
Serial.println(PID_speed_right.Setpoint);
|
||||
#endif
|
||||
|
||||
if(abs(abs(PID_speed_left.Setpoint) - abs(PID_speed_right.Setpoint)) >= 0)
|
||||
{
|
||||
encoders[0].setMotorPwm(PID_speed_left.Setpoint);
|
||||
encoders[1].setMotorPwm(PID_speed_right.Setpoint);
|
||||
return;
|
||||
}
|
||||
|
||||
if((abs(PID_speed_left.Setpoint) == 0) && (abs(PID_speed_right.Setpoint) == 0))
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
if(abs(speed1) - abs(speed2) >= 0)
|
||||
{
|
||||
if(PID_speed_left.Setpoint > 0)
|
||||
{
|
||||
encoders[0].setMotorPwm(PID_speed_left.Setpoint - (abs(speed1) - abs(speed2)));
|
||||
encoders[1].setMotorPwm(PID_speed_right.Setpoint);
|
||||
}
|
||||
else
|
||||
{
|
||||
encoders[0].setMotorPwm(PID_speed_left.Setpoint + (abs(speed1) - abs(speed2)));
|
||||
encoders[1].setMotorPwm(PID_speed_right.Setpoint);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if(PID_speed_right.Setpoint > 0)
|
||||
{
|
||||
encoders[0].setMotorPwm(PID_speed_left.Setpoint);
|
||||
encoders[1].setMotorPwm(PID_speed_right.Setpoint - (abs(speed2) - abs(speed1)));
|
||||
}
|
||||
else
|
||||
{
|
||||
encoders[0].setMotorPwm(PID_speed_left.Setpoint);
|
||||
encoders[1].setMotorPwm(PID_speed_right.Setpoint + (abs(speed2) - abs(speed1)));
|
||||
}
|
||||
}
|
||||
lasttime_speed = millis();
|
||||
}
|
||||
}
|
||||
|
||||
void Forward(void)
|
||||
{
|
||||
// Encoder_1.setMotorPwm(-moveSpeed);
|
||||
// Encoder_2.setMotorPwm(moveSpeed);
|
||||
PID_speed_left.Setpoint = -moveSpeed;
|
||||
PID_speed_right.Setpoint = moveSpeed;
|
||||
move_status = MOVE_FORWARD;
|
||||
PWM_Calcu();
|
||||
}
|
||||
|
||||
void Backward(void)
|
||||
{
|
||||
// Encoder_1.setMotorPwm(moveSpeed);
|
||||
// Encoder_2.setMotorPwm(-moveSpeed);
|
||||
PID_speed_left.Setpoint = moveSpeed;
|
||||
PID_speed_right.Setpoint = -moveSpeed;
|
||||
move_status = MOVE_BACKWARD;
|
||||
PWM_Calcu();
|
||||
}
|
||||
|
||||
void Stop(void)
|
||||
{
|
||||
encoders[0].setMotorPwm(0);
|
||||
encoders[1].setMotorPwm(0);
|
||||
move_status = MOVE_STOP;
|
||||
}
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(encoders[0].getPortB()) == 0)
|
||||
{
|
||||
encoders[0].pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
encoders[0].pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(encoders[1].getPortB()) == 0)
|
||||
{
|
||||
encoders[1].pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
encoders[1].pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder3(void)
|
||||
{
|
||||
if(digitalRead(encoders[2].getPortB()) == 0)
|
||||
{
|
||||
encoders[2].pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
encoders[2].pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder4(void)
|
||||
{
|
||||
if(digitalRead(encoders[3].getPortB()) == 0)
|
||||
{
|
||||
encoders[3].pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
encoders[3].pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,697 @@
|
|||
void runModule(int device)
|
||||
{
|
||||
//0xff 0x55 0x6 0x0 0x1 0xa 0x9 0x0 0x0 0xa
|
||||
int port = readBuffer(6);
|
||||
int pin = port;
|
||||
int speed;
|
||||
long position;
|
||||
long distance;
|
||||
int type;
|
||||
int slot;
|
||||
int extId;
|
||||
switch(device)
|
||||
{
|
||||
case MOTOR:
|
||||
{
|
||||
speed = readShort(7);
|
||||
dc.reset(port);
|
||||
dc.run(speed);
|
||||
}
|
||||
break;
|
||||
case ENCODER_BOARD:
|
||||
slot = readBuffer(7);
|
||||
type = readBuffer(8);
|
||||
switch(type){
|
||||
case ENCODER_BOARD_RUN:
|
||||
{
|
||||
if(port == 0)
|
||||
{
|
||||
int speed_value = readShort(9);
|
||||
Serial.println(speed_value);
|
||||
encoders[slot-1].runSpeed(speed_value);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case ENCODER_BOARD_MOVE:
|
||||
{
|
||||
if(port == 0)
|
||||
{
|
||||
int speed_value = readShort(9);
|
||||
distance = readLong(11);
|
||||
extId = readBuffer(3);
|
||||
encoders[slot-1].move(distance,speed_value,onEncoderMovingFinish,extId);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case ENCODER_BOARD_MOVE_TO:
|
||||
{
|
||||
if(port == 0)
|
||||
{
|
||||
int speed_value = readShort(9);
|
||||
position = readLong(11);
|
||||
extId = readBuffer(3);
|
||||
encoders[slot-1].moveTo(position,speed_value,onEncoderMovingFinish,extId);
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
case JOYSTICK:
|
||||
{
|
||||
int leftSpeed = readShort(6);
|
||||
dc.reset(M1);
|
||||
dc.run(leftSpeed);
|
||||
int rightSpeed = readShort(8);
|
||||
dc.reset(M2);
|
||||
dc.run(rightSpeed);
|
||||
}
|
||||
break;
|
||||
case STEPPER_BOARD:
|
||||
{
|
||||
type = readBuffer(7);
|
||||
switch(type){
|
||||
case STEPPER_BOARD_RUN:
|
||||
speed = readShort(8);
|
||||
steppers[port-1].setSpeed(speed);
|
||||
break;
|
||||
case STEPPER_BOARD_MOVE:
|
||||
speed = readShort(8);
|
||||
distance = readLong(10);
|
||||
extId = readBuffer(3);
|
||||
steppers[port-1].setSpeed(speed);
|
||||
steppers[port-1].move(distance,onStepperMovingFinish,extId);
|
||||
break;
|
||||
case STEPPER_BOARD_MOVE_TO:
|
||||
speed = readShort(8);
|
||||
position = readLong(10);
|
||||
extId = readBuffer(3);
|
||||
steppers[port-1].setSpeed(speed);
|
||||
steppers[port-1].moveTo(position,onStepperMovingFinish,extId);
|
||||
break;
|
||||
case STEPPER_BOARD_SETTING:
|
||||
int microsteps = readBuffer(8);
|
||||
int acceleration = readShort(9);
|
||||
steppers[port-1].setMicroStep(microsteps);
|
||||
steppers[port-1].setAcceleration(acceleration);
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case RGBLED:
|
||||
{
|
||||
slot = readBuffer(7);
|
||||
int idx = readBuffer(8);
|
||||
int r = readBuffer(9);
|
||||
int g = readBuffer(10);
|
||||
int b = readBuffer(11);
|
||||
if(port != 0)
|
||||
{
|
||||
led.reset(port,slot);
|
||||
}
|
||||
if(idx>0)
|
||||
{
|
||||
led.setColorAt(idx-1,r,g,b);
|
||||
}
|
||||
else
|
||||
{
|
||||
led.setColor(r,g,b);
|
||||
}
|
||||
led.show();
|
||||
}
|
||||
break;
|
||||
|
||||
case RGBLED_DISPLAY:
|
||||
{
|
||||
slot = readBuffer(7);
|
||||
int idx = readBuffer(8);
|
||||
int r = readBuffer(9);
|
||||
int g = readBuffer(10);
|
||||
int b = readBuffer(11);
|
||||
if(port != 0)
|
||||
{
|
||||
led.reset(port,slot);
|
||||
}
|
||||
if(idx>0)
|
||||
{
|
||||
led.setColorAt(idx-1,r,g,b);
|
||||
}
|
||||
else
|
||||
{
|
||||
led.setColor(r,g,b);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case RGBLED_SHOW:
|
||||
{
|
||||
slot = readBuffer(7);
|
||||
if(port != 0)
|
||||
{
|
||||
led.reset(port,slot);
|
||||
}
|
||||
led.show();
|
||||
}
|
||||
break;
|
||||
case COMMON_COMMONCMD:
|
||||
{
|
||||
int8_t subcmd = port;
|
||||
int8_t cmd_data = readBuffer(7);
|
||||
if(SET_MEGAPI_MODE == subcmd)
|
||||
{
|
||||
Stop();
|
||||
if((cmd_data == BALANCED_MODE) ||
|
||||
(cmd_data == AUTOMATIC_OBSTACLE_AVOIDANCE_MODE) ||
|
||||
(cmd_data == BLUETOOTH_MODE) ||
|
||||
(cmd_data == IR_REMOTE_MODE))
|
||||
{
|
||||
megapi_mode = cmd_data;
|
||||
EEPROM.write(MEGAPI_MODE_CONFIGURE, megapi_mode);
|
||||
}
|
||||
else
|
||||
{
|
||||
megapi_mode = BLUETOOTH_MODE;
|
||||
EEPROM.write(MEGAPI_MODE_CONFIGURE, megapi_mode);
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SERVO:
|
||||
{
|
||||
slot = readBuffer(7);
|
||||
pin = slot==1?mePort[port].s1:mePort[port].s2;
|
||||
int v = readBuffer(8);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(port > 0)
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
else
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SEVSEG:
|
||||
{
|
||||
if(seg.getPort() != port)
|
||||
{
|
||||
seg.reset(port);
|
||||
}
|
||||
float v = readFloat(7);
|
||||
seg.display(v);
|
||||
}
|
||||
break;
|
||||
case LEDMATRIX:
|
||||
{
|
||||
if(ledMx.getPort()!=port)
|
||||
{
|
||||
ledMx.reset(port);
|
||||
ledMx.setBrightness(6);
|
||||
ledMx.setColorIndex(1);
|
||||
}
|
||||
int action = readBuffer(7);
|
||||
if(action==1)
|
||||
{
|
||||
char px = readBuffer(8);
|
||||
char py = readBuffer(9);
|
||||
int len = readBuffer(10);
|
||||
char *s = readString(11,len);
|
||||
ledMx.drawStr(px,py,s);
|
||||
}
|
||||
else if(action==2)
|
||||
{
|
||||
char px = readBuffer(8);
|
||||
char py = readBuffer(9);
|
||||
uint8_t *ss = readUint8(10,16);
|
||||
ledMx.drawBitmap(px,py,16,ss);
|
||||
}
|
||||
else if(action==3)
|
||||
{
|
||||
int point = readBuffer(8);
|
||||
int hours = readBuffer(9);
|
||||
int minutes = readBuffer(10);
|
||||
ledMx.showClock(hours,minutes,point);
|
||||
}else if(action == 4)
|
||||
{
|
||||
ledMx.showNum(readFloat(8),3);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:
|
||||
{
|
||||
if(generalDevice.getPort() != port)
|
||||
{
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
generalDevice.dWrite1(v);
|
||||
}
|
||||
break;
|
||||
case SHUTTER:
|
||||
{
|
||||
if(generalDevice.getPort() != port)
|
||||
{
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
if(v < 2)
|
||||
{
|
||||
generalDevice.dWrite1(v);
|
||||
}
|
||||
else
|
||||
{
|
||||
generalDevice.dWrite2(v-2);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case DIGITAL:
|
||||
{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
digitalWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case PWM:
|
||||
{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
analogWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case TONE:
|
||||
{
|
||||
pinMode(pin,OUTPUT);
|
||||
int hz = readShort(7);
|
||||
int ms = readShort(9);
|
||||
if(ms > 0)
|
||||
{
|
||||
buzzer.tone(pin, hz, ms);
|
||||
}
|
||||
else
|
||||
{
|
||||
buzzer.noTone(pin);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SERVO_PIN:
|
||||
{
|
||||
int v = readBuffer(7);
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
sv.attach(pin);
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case PRESSURE_SENSOR:
|
||||
{
|
||||
pressureSensor.begin();
|
||||
}
|
||||
break;
|
||||
case TIMER:
|
||||
{
|
||||
lastTime = millis()/1000.0;
|
||||
}
|
||||
break;
|
||||
case JOYSTICK_MOVE:
|
||||
{
|
||||
if(port == 0)
|
||||
{
|
||||
//if needed balance mode, add here
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int searchServoPin(int pin)
|
||||
{
|
||||
for(int i=0;i<8;i++)
|
||||
{
|
||||
if(servo_pins[i] == pin)
|
||||
{
|
||||
return i;
|
||||
}
|
||||
if(servo_pins[i] == 0)
|
||||
{
|
||||
servo_pins[i] = pin;
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
void readSensor(int device)
|
||||
{
|
||||
/**************************************************
|
||||
ff 55 len idx action device port slot data a
|
||||
0 1 2 3 4 5 6 7 8
|
||||
***************************************************/
|
||||
float value=0.0;
|
||||
int8_t port,slot,pin;
|
||||
port = readBuffer(6);
|
||||
pin = port;
|
||||
switch(device)
|
||||
{
|
||||
case ULTRASONIC_SENSOR:
|
||||
{
|
||||
if(us == NULL)
|
||||
{
|
||||
us = new MeUltrasonicSensor(port);
|
||||
}
|
||||
else if(us->getPort() != port)
|
||||
{
|
||||
delete us;
|
||||
us = new MeUltrasonicSensor(port);
|
||||
}
|
||||
value = us->distanceCm();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case TEMPERATURE_SENSOR:
|
||||
{
|
||||
slot = readBuffer(7);
|
||||
if(ts.getPort() != port || ts.getSlot() != slot)
|
||||
{
|
||||
ts.reset(port,slot);
|
||||
}
|
||||
value = ts.temperature();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:
|
||||
case SOUND_SENSOR:
|
||||
case TEMPERATURE_SENSOR_1:
|
||||
case POTENTIONMETER:
|
||||
{
|
||||
if(generalDevice.getPort() != port)
|
||||
{
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.aRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:
|
||||
{
|
||||
slot = readBuffer(7);
|
||||
if(joystick.getPort() != port)
|
||||
{
|
||||
joystick.reset(port);
|
||||
}
|
||||
value = joystick.read(slot);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case INFRARED:
|
||||
{
|
||||
if(ir == NULL)
|
||||
{
|
||||
ir = new MeInfraredReceiver(port);
|
||||
ir->begin();
|
||||
}
|
||||
else if(ir->getPort() != port)
|
||||
{
|
||||
delete ir;
|
||||
ir = new MeInfraredReceiver(port);
|
||||
ir->begin();
|
||||
}
|
||||
irRead = ir->getCode();
|
||||
if((irRead < 255) && (irRead > 0))
|
||||
{
|
||||
sendFloat((float)irRead);
|
||||
}
|
||||
else
|
||||
{
|
||||
sendFloat(0);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case PIRMOTION:
|
||||
{
|
||||
if(generalDevice.getPort() != port)
|
||||
{
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LINEFOLLOWER:
|
||||
{
|
||||
if(generalDevice.getPort() != port)
|
||||
{
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin1(),INPUT);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead1()*2+generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIMITSWITCH:
|
||||
{
|
||||
slot = readBuffer(7);
|
||||
if(generalDevice.getPort() != port || generalDevice.getSlot() != slot)
|
||||
{
|
||||
generalDevice.reset(port,slot);
|
||||
}
|
||||
if(slot == 1)
|
||||
{
|
||||
pinMode(generalDevice.pin1(),INPUT_PULLUP);
|
||||
value = generalDevice.dRead1();
|
||||
}
|
||||
else
|
||||
{
|
||||
pinMode(generalDevice.pin2(),INPUT_PULLUP);
|
||||
value = generalDevice.dRead2();
|
||||
}
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case COMPASS:
|
||||
{
|
||||
if(Compass.getPort() != port)
|
||||
{
|
||||
Compass.reset(port);
|
||||
Compass.setpin(Compass.pin1(),Compass.pin2());
|
||||
}
|
||||
double CompassAngle;
|
||||
CompassAngle = Compass.getAngle();
|
||||
sendDouble(CompassAngle);
|
||||
}
|
||||
break;
|
||||
case HUMITURE:
|
||||
{
|
||||
uint8_t index = readBuffer(7);
|
||||
if(humiture.getPort() != port)
|
||||
{
|
||||
humiture.reset(port);
|
||||
}
|
||||
uint8_t HumitureData;
|
||||
humiture.update();
|
||||
HumitureData = humiture.getValue(index);
|
||||
sendByte(HumitureData);
|
||||
}
|
||||
break;
|
||||
case FLAMESENSOR:
|
||||
{
|
||||
if(FlameSensor.getPort() != port)
|
||||
{
|
||||
FlameSensor.reset(port);
|
||||
FlameSensor.setpin(FlameSensor.pin2(),FlameSensor.pin1());
|
||||
}
|
||||
int16_t FlameData;
|
||||
FlameData = FlameSensor.readAnalog();
|
||||
sendShort(FlameData);
|
||||
}
|
||||
break;
|
||||
case GASSENSOR:
|
||||
{
|
||||
if(GasSensor.getPort() != port)
|
||||
{
|
||||
GasSensor.reset(port);
|
||||
GasSensor.setpin(GasSensor.pin2(),GasSensor.pin1());
|
||||
}
|
||||
int16_t GasData;
|
||||
GasData = GasSensor.readAnalog();
|
||||
sendShort(GasData);
|
||||
}
|
||||
break;
|
||||
case ANGULAR_SENSOR:
|
||||
{
|
||||
slot = readBuffer(7);
|
||||
pin = slot==1?mePort[port].s1:mePort[port].s2;
|
||||
sendShort(analogRead(pin));
|
||||
}
|
||||
break;
|
||||
case GYRO:
|
||||
{
|
||||
int axis = readBuffer(7);
|
||||
if(port == 0)
|
||||
{
|
||||
gyro.update();
|
||||
value = gyro.getAngle(axis);
|
||||
sendFloat(value);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case VERSION:
|
||||
{
|
||||
sendString(mVersion);
|
||||
}
|
||||
break;
|
||||
case DIGITAL:
|
||||
{
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(digitalRead(pin));
|
||||
}
|
||||
break;
|
||||
case ANALOG:
|
||||
{
|
||||
pin = analogs[pin];
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(analogRead(pin));
|
||||
}
|
||||
break;
|
||||
case PULSEIN:
|
||||
{
|
||||
int pw = readShort(7);
|
||||
pinMode(pin, INPUT);
|
||||
sendShort(pulseIn(pin,HIGH,pw));
|
||||
}
|
||||
break;
|
||||
case ULTRASONIC_ARDUINO:
|
||||
{
|
||||
int trig = readBuffer(6);
|
||||
int echo = readBuffer(7);
|
||||
pinMode(trig,OUTPUT);
|
||||
digitalWrite(trig,LOW);
|
||||
delayMicroseconds(2);
|
||||
digitalWrite(trig,HIGH);
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(trig,LOW);
|
||||
pinMode(echo, INPUT);
|
||||
sendFloat(pulseIn(echo,HIGH,30000)/58.0);
|
||||
}
|
||||
break;
|
||||
case PRESSURE_SENSOR:
|
||||
{
|
||||
int action = readBuffer(6);
|
||||
switch(action){
|
||||
case 1:
|
||||
{
|
||||
sendLong(pressureSensor.readPressure());
|
||||
}
|
||||
break;
|
||||
case 2:
|
||||
{
|
||||
sendLong(pressureSensor.readTemperature());
|
||||
}
|
||||
break;
|
||||
case 3:
|
||||
{
|
||||
sendFloat(pressureSensor.readAltitude());
|
||||
}
|
||||
break;
|
||||
case 4:
|
||||
{
|
||||
sendFloat(pressureSensor.readAltitude(101500));
|
||||
}
|
||||
break;
|
||||
case 5:
|
||||
{
|
||||
sendLong(pressureSensor.readSealevelPressure());
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TIMER:
|
||||
{
|
||||
sendFloat((float)currentTime);
|
||||
}
|
||||
break;
|
||||
case ENCODER_BOARD:
|
||||
{
|
||||
if(port == 0)
|
||||
{
|
||||
slot = readBuffer(7);
|
||||
uint8_t read_type = readBuffer(8);
|
||||
switch(read_type)
|
||||
{
|
||||
case ENCODER_BOARD_POS:
|
||||
{
|
||||
sendLong(encoders[slot-1].getPulsePos());
|
||||
}
|
||||
break;
|
||||
case ENCODER_BOARD_SPEED:
|
||||
{
|
||||
sendFloat(encoders[slot-1].getCurrentSpeed());
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
case STEPPER_BOARD:
|
||||
{
|
||||
if(port == 0)
|
||||
{
|
||||
slot = readBuffer(7);
|
||||
uint8_t read_type = readBuffer(8);
|
||||
switch(read_type)
|
||||
{
|
||||
case STEPPER_BOARD_POS:
|
||||
{
|
||||
sendLong(steppers[slot-1].currentPosition());
|
||||
}
|
||||
break;
|
||||
case STEPPER_BOARD_SPEED:
|
||||
{
|
||||
sendFloat(steppers[slot-1].speed());
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
case COMMON_COMMONCMD:
|
||||
{
|
||||
int8_t subcmd = port;
|
||||
if(GET_BATTERY_POWER == subcmd)
|
||||
{
|
||||
//do nothing
|
||||
}
|
||||
}
|
||||
break;
|
||||
}//switch
|
||||
}
|
||||
void resetAll()
|
||||
{
|
||||
encoders[0].setMotorPwm(0);
|
||||
encoders[1].setMotorPwm(0);
|
||||
encoders[2].setMotorPwm(0);
|
||||
encoders[3].setMotorPwm(0);
|
||||
encoders[0].setPulsePos(0);
|
||||
encoders[1].setPulsePos(0);
|
||||
encoders[2].setPulsePos(0);
|
||||
encoders[3].setPulsePos(0);
|
||||
PID_speed_left.Setpoint = 0;
|
||||
PID_speed_right.Setpoint = 0;
|
||||
dc.reset(M1);
|
||||
dc.run(0);
|
||||
dc.reset(M2);
|
||||
dc.run(0);
|
||||
dc.reset(PORT_1);
|
||||
dc.run(0);
|
||||
dc.reset(PORT_2);
|
||||
dc.run(0);
|
||||
callOK();
|
||||
}
|
||||
|
|
@ -0,0 +1,197 @@
|
|||
Servo servos[8];
|
||||
MeMegaPiDCMotor dc;
|
||||
MeTemperature ts;
|
||||
MeRGBLed led;
|
||||
MeUltrasonicSensor *us = NULL;
|
||||
Me7SegmentDisplay seg;
|
||||
MePort generalDevice;
|
||||
MeLEDMatrix ledMx;
|
||||
MeInfraredReceiver *ir = NULL;
|
||||
MeGyro gyro;
|
||||
MeCompass Compass;
|
||||
MeJoystick joystick;
|
||||
MeBuzzer buzzer;
|
||||
MeHumiture humiture;
|
||||
MeFlameSensor FlameSensor;
|
||||
MeGasSensor GasSensor;
|
||||
MePressureSensor pressureSensor;
|
||||
MeSerial mySerial(PORT_9);
|
||||
MeStepperOnBoard steppers[4];
|
||||
MeEncoderOnBoard encoders[4];
|
||||
long encodersPosition[4] = {0,0,0,0};
|
||||
long steppersPosition[4] = {0,0,0,0};
|
||||
boolean encodersMoving[4] = {false,false,false,false};
|
||||
boolean steppersMoving[4] = {false,false,false,false};
|
||||
|
||||
int16_t servo_pins[8]={0,0,0,0,0,0,0,0};
|
||||
int16_t moveSpeed = 255;
|
||||
|
||||
#define MOVE_STOP 0x00
|
||||
#define MOVE_FORWARD 0x01
|
||||
#define MOVE_BACKWARD 0x02
|
||||
|
||||
int16_t move_status = MOVE_STOP;
|
||||
|
||||
#define BLUETOOTH_MODE 0x00
|
||||
#define AUTOMATIC_OBSTACLE_AVOIDANCE_MODE 0x01
|
||||
#define BALANCED_MODE 0x02
|
||||
#define IR_REMOTE_MODE 0x03
|
||||
|
||||
//#define POWER_PORT A4
|
||||
//#define BUZZER_PORT 45
|
||||
//#define RGBLED_PORT 44
|
||||
|
||||
#define DATA_SERIAL 0
|
||||
#define DATA_SERIAL1 1
|
||||
#define DATA_SERIAL2 2
|
||||
#define DATA_SERIAL3 3
|
||||
|
||||
uint8_t megapi_mode = BLUETOOTH_MODE;
|
||||
uint8_t index = 0;
|
||||
uint8_t dataLen;
|
||||
uint8_t modulesLen=0;
|
||||
uint8_t irRead = 0;
|
||||
uint8_t prevc=0;
|
||||
uint8_t BluetoothSource = DATA_SERIAL;
|
||||
char serialRead;
|
||||
char buffer[52];
|
||||
char bufferBt1[52];
|
||||
char bufferBt2[52];
|
||||
|
||||
char buf[64];
|
||||
char bufindex;
|
||||
|
||||
double lastTime = 0.0;
|
||||
double currentTime = 0.0;
|
||||
float angleServo = 90.0;
|
||||
|
||||
boolean isStart = false;
|
||||
boolean isAvailable = false;
|
||||
|
||||
#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 PIRMOTION 15
|
||||
#define INFRARED 16
|
||||
#define LINEFOLLOWER 17
|
||||
#define RGBLED_DISPLAY 18
|
||||
#define RGBLED_SHOW 19
|
||||
#define SHUTTER 20
|
||||
#define LIMITSWITCH 21
|
||||
#define BUTTON 22
|
||||
#define HUMITURE 23
|
||||
#define FLAMESENSOR 24
|
||||
#define GASSENSOR 25
|
||||
#define COMPASS 26
|
||||
#define TEMPERATURE_SENSOR_1 27
|
||||
#define ANGULAR_SENSOR 28
|
||||
#define PRESSURE_SENSOR 29
|
||||
#define DIGITAL 30
|
||||
#define ANALOG 31
|
||||
#define PWM 32
|
||||
#define SERVO_PIN 33
|
||||
#define TONE 34
|
||||
#define PULSEIN 35
|
||||
#define ULTRASONIC_ARDUINO 36
|
||||
#define STEPPER 40
|
||||
#define LEDMATRIX 41
|
||||
#define TIMER 50
|
||||
#define JOYSTICK_MOVE 52
|
||||
#define COMMON_COMMONCMD 60
|
||||
//Secondary command
|
||||
#define SET_STARTER_MODE 0x10
|
||||
#define SET_AURIGA_MODE 0x11
|
||||
#define SET_MEGAPI_MODE 0x12
|
||||
#define GET_BATTERY_POWER 0x70
|
||||
|
||||
#define ENCODER_BOARD 61
|
||||
//Motion type
|
||||
#define ENCODER_BOARD_RUN 0x01
|
||||
#define ENCODER_BOARD_MOVE 0x02
|
||||
#define ENCODER_BOARD_MOVE_TO 0x03
|
||||
#define ENCODER_BOARD_SETTING 0x04
|
||||
//Read type
|
||||
#define ENCODER_BOARD_POS 0x01
|
||||
#define ENCODER_BOARD_SPEED 0x02
|
||||
|
||||
#define STEPPER_BOARD 62
|
||||
//Motion type
|
||||
#define STEPPER_BOARD_RUN 0x01
|
||||
#define STEPPER_BOARD_MOVE 0x02
|
||||
#define STEPPER_BOARD_MOVE_TO 0x03
|
||||
#define STEPPER_BOARD_SETTING 0x04
|
||||
//Read type
|
||||
#define STEPPER_BOARD_POS 0x01
|
||||
#define STEPPER_BOARD_SPEED 0x02
|
||||
|
||||
#define GET 1
|
||||
#define RUN 2
|
||||
#define RESET 4
|
||||
#define START 5
|
||||
|
||||
|
||||
typedef struct MeModule
|
||||
{
|
||||
int16_t device;
|
||||
int16_t port;
|
||||
int16_t slot;
|
||||
int16_t pin;
|
||||
int16_t 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;
|
||||
MeModule modules[12];
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
int analogs[12]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11};
|
||||
#endif
|
||||
#if defined(__AVR_ATmega328P__) or defined(__AVR_ATmega168__)
|
||||
int analogs[8]={A0,A1,A2,A3,A4,A5,A6,A7};
|
||||
#endif
|
||||
#if defined(__AVR_ATmega1280__)|| defined(__AVR_ATmega2560__)
|
||||
int analogs[16]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15};
|
||||
#endif
|
||||
long measurement_speed_time = 0;
|
||||
long lasttime_angle = 0;
|
||||
long lasttime_speed = 0;
|
||||
long last_Pulse_pos_encoder1 = 0;
|
||||
long last_Pulse_pos_encoder2 = 0;
|
||||
long last_Pulse_pos_encoder3 = 0;
|
||||
long last_Pulse_pos_encoder4 = 0;
|
||||
//////////////////////////////////////////////////////////////////////////////////////
|
||||
typedef struct
|
||||
{
|
||||
double P, I, D;
|
||||
double Setpoint, Output, Integral,differential, last_error;
|
||||
} PID;
|
||||
|
||||
PID PID_angle, PID_speed, PID_turn;
|
||||
PID PID_speed_left, PID_speed_right;
|
||||
|
|
@ -0,0 +1,40 @@
|
|||
/*************************************************************************
|
||||
* File Name : Firmware_for_MegaPi.ino
|
||||
* Author : myan
|
||||
* Updated : myan
|
||||
* Version : V0e.01.101
|
||||
* Date : 02/20/2016
|
||||
* Description : Firmware for Makeblock Electronic modules with Scratch.
|
||||
* License : CC-BY-SA 3.0
|
||||
* Copyright (C) 2013 - 2016 Maker Works Technology Co., Ltd. All right reserved.
|
||||
* http://www.makeblock.cc/
|
||||
**************************************************************************/
|
||||
#include <Arduino.h>
|
||||
#include <MeMegaPi.h>
|
||||
#include "MeEEPROM.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
#include "init.h"
|
||||
//#define DEBUG_INFO
|
||||
String mVersion = "0e.01.101";
|
||||
void setup()
|
||||
{
|
||||
delay(5);
|
||||
Serial.begin(115200);
|
||||
Serial2.begin(115200);
|
||||
Serial3.begin(115200);
|
||||
delay(100);
|
||||
Serial.print("Version: ");
|
||||
Serial.println(mVersion);
|
||||
encodersInit();
|
||||
steppersInit();
|
||||
delay(100);
|
||||
}
|
||||
void loop()
|
||||
{
|
||||
parserRead();
|
||||
encodersUpdate();
|
||||
steppersUpdate();
|
||||
}
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,276 @@
|
|||
void parserRead()
|
||||
{
|
||||
|
||||
currentTime = millis()/1000.0-lastTime;
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
unsigned char readBuffer(int index)
|
||||
{
|
||||
if(BluetoothSource == DATA_SERIAL)
|
||||
{
|
||||
return buffer[index];
|
||||
}
|
||||
else if(BluetoothSource == DATA_SERIAL2)
|
||||
{
|
||||
return bufferBt1[index];
|
||||
}
|
||||
else if(BluetoothSource == DATA_SERIAL3)
|
||||
{
|
||||
return bufferBt2[index];
|
||||
}
|
||||
}
|
||||
|
||||
void writeBuffer(int index,unsigned char c)
|
||||
{
|
||||
if(BluetoothSource == DATA_SERIAL)
|
||||
{
|
||||
buffer[index]=c;
|
||||
}
|
||||
else if(BluetoothSource == DATA_SERIAL2)
|
||||
{
|
||||
bufferBt1[index]=c;
|
||||
}
|
||||
else if(BluetoothSource == DATA_SERIAL3)
|
||||
{
|
||||
bufferBt2[index]=c;
|
||||
}
|
||||
}
|
||||
void writeSerial(unsigned char c)
|
||||
{
|
||||
Serial.write(c);
|
||||
Serial2.write(c);
|
||||
Serial3.write(c);
|
||||
}
|
||||
|
||||
void readSerial(void)
|
||||
{
|
||||
isAvailable = false;
|
||||
BluetoothSource = DATA_SERIAL;
|
||||
if(Serial.available() > 0)
|
||||
{
|
||||
isAvailable = true;
|
||||
BluetoothSource = DATA_SERIAL;
|
||||
serialRead = Serial.read();
|
||||
}
|
||||
|
||||
if(Serial2.available() > 0)
|
||||
{
|
||||
isAvailable = true;
|
||||
BluetoothSource = DATA_SERIAL2;
|
||||
serialRead = Serial2.read();
|
||||
}
|
||||
|
||||
if(Serial3.available() > 0)
|
||||
{
|
||||
isAvailable = true;
|
||||
BluetoothSource = DATA_SERIAL3;
|
||||
serialRead = Serial3.read();
|
||||
}
|
||||
}
|
||||
void writeHead(void)
|
||||
{
|
||||
writeSerial(0xff);
|
||||
writeSerial(0x55);
|
||||
}
|
||||
|
||||
void writeEnd(void)
|
||||
{
|
||||
Serial.println();
|
||||
Serial2.println();
|
||||
Serial3.println();
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
ff 55 len idx action device port slot data a
|
||||
0 1 2 3 4 5 6 7 8
|
||||
*/
|
||||
void parseData(void)
|
||||
{
|
||||
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
|
||||
resetAll();
|
||||
}
|
||||
break;
|
||||
case START:
|
||||
{
|
||||
//start
|
||||
callOK();
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void callOK(void)
|
||||
{
|
||||
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<l;i++)
|
||||
{
|
||||
writeSerial(s.charAt(i));
|
||||
}
|
||||
}
|
||||
|
||||
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 sendLong(long value)
|
||||
{
|
||||
writeSerial(6);
|
||||
val.longVal = value;
|
||||
writeSerial(val.byteVal[0]);
|
||||
writeSerial(val.byteVal[1]);
|
||||
writeSerial(val.byteVal[2]);
|
||||
writeSerial(val.byteVal[3]);
|
||||
}
|
||||
|
||||
void sendShort(short value)
|
||||
{
|
||||
writeSerial(3);
|
||||
valShort.shortVal = value;
|
||||
writeSerial(valShort.byteVal[0]);
|
||||
writeSerial(valShort.byteVal[1]);
|
||||
}
|
||||
|
||||
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]);
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
long readLong(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.longVal;
|
||||
}
|
||||
|
||||
char _receiveStr[20] = {};
|
||||
uint8_t _receiveUint8[16] = {};
|
||||
|
||||
char* readString(int idx,int len)
|
||||
{
|
||||
for(int i=0;i<len;i++)
|
||||
{
|
||||
_receiveStr[i]=readBuffer(idx+i);
|
||||
}
|
||||
_receiveStr[len] = '\0';
|
||||
return _receiveStr;
|
||||
}
|
||||
|
||||
uint8_t* readUint8(int idx,int len)
|
||||
{
|
||||
for(int i=0;i<len;i++)
|
||||
{
|
||||
if(i > 15)
|
||||
{
|
||||
break;
|
||||
}
|
||||
_receiveUint8[i] = readBuffer(idx+i);
|
||||
}
|
||||
return _receiveUint8;
|
||||
}
|
||||
|
|
@ -0,0 +1,28 @@
|
|||
//blue red green black
|
||||
//A+ A- B+ B-
|
||||
void steppersInit()
|
||||
{
|
||||
steppers[0] = MeStepperOnBoard(SLOT1);
|
||||
steppers[1] = MeStepperOnBoard(SLOT2);
|
||||
steppers[2] = MeStepperOnBoard(SLOT3);
|
||||
steppers[3] = MeStepperOnBoard(SLOT4);
|
||||
for(int i=0;i<4;i++){
|
||||
steppers[i].setMaxSpeed(10000);
|
||||
steppers[i].setAcceleration(10000);
|
||||
steppers[i].setMicroStep(16);
|
||||
}
|
||||
}
|
||||
void steppersUpdate()
|
||||
{
|
||||
for(int i=0;i<4;i++){
|
||||
steppers[i].update();
|
||||
}
|
||||
}
|
||||
void onStepperMovingFinish(int slot,int extId)
|
||||
{
|
||||
writeHead();
|
||||
writeSerial(extId);
|
||||
sendByte(slot);
|
||||
writeEnd();
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,734 @@
|
|||
/*************************************************************************
|
||||
* File Name : orion_firmware.ino
|
||||
* Author : Ander, Mark Yan
|
||||
* Updated : Ander, Mark Yan
|
||||
* Version : V0a.01.106
|
||||
* Date : 01/03/2017
|
||||
* Description : Firmware for Makeblock Electronic modules with Scratch.
|
||||
* License : CC-BY-SA 3.0
|
||||
* Copyright (C) 2013 - 2016 Maker Works Technology Co., Ltd. All right reserved.
|
||||
* http://www.makeblock.cc/
|
||||
**************************************************************************/
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
#include <Arduino.h>
|
||||
#include <MeOrion.h>
|
||||
|
||||
Servo servos[8];
|
||||
MeDCMotor dc;
|
||||
MeTemperature ts;
|
||||
MeRGBLed led;
|
||||
MeUltrasonicSensor us;
|
||||
Me7SegmentDisplay seg;
|
||||
MePort generalDevice;
|
||||
MeInfraredReceiver *ir = NULL;
|
||||
MeGyro gyro;
|
||||
MeJoystick joystick;
|
||||
MeStepper steppers[2];
|
||||
MeBuzzer buzzer;
|
||||
MeHumiture humiture;
|
||||
MeFlameSensor FlameSensor;
|
||||
MeGasSensor GasSensor;
|
||||
MeTouchSensor touchSensor;
|
||||
Me4Button buttonSensor;
|
||||
|
||||
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;
|
||||
MeModule modules[12];
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
int analogs[12]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11};
|
||||
#endif
|
||||
#if defined(__AVR_ATmega328P__) or defined(__AVR_ATmega168__)
|
||||
int analogs[8]={A0,A1,A2,A3,A4,A5,A6,A7};
|
||||
MeEncoderMotor encoders[2];
|
||||
#endif
|
||||
#if defined(__AVR_ATmega1280__)|| defined(__AVR_ATmega2560__)
|
||||
int analogs[16]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15};
|
||||
#endif
|
||||
String mVersion = "0a.01.106";
|
||||
boolean isAvailable = false;
|
||||
boolean isBluetooth = false;
|
||||
|
||||
int len = 52;
|
||||
char buffer[52];
|
||||
char bufferBt[52];
|
||||
byte index = 0;
|
||||
byte dataLen;
|
||||
byte modulesLen=0;
|
||||
boolean isStart = false;
|
||||
unsigned char irRead;
|
||||
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 PULSEIN 37
|
||||
#define ULTRASONIC_ARDUINO 36
|
||||
#define STEPPER 40
|
||||
#define LEDMATRIX 41
|
||||
#define TIMER 50
|
||||
#define TOUCH_SENSOR 51
|
||||
|
||||
#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;
|
||||
double lastTime = 0.0;
|
||||
double currentTime = 0.0;
|
||||
uint8_t keyPressed = 0;
|
||||
uint8_t command_index = 0;
|
||||
|
||||
void setup(){
|
||||
pinMode(13,OUTPUT);
|
||||
digitalWrite(13,HIGH);
|
||||
delay(300);
|
||||
digitalWrite(13,LOW);
|
||||
Serial.begin(115200);
|
||||
delay(500);
|
||||
buzzerOn();
|
||||
delay(100);
|
||||
buzzerOff();
|
||||
#if defined(__AVR_ATmega328P__) or defined(__AVR_ATmega168__)
|
||||
encoders[0] = MeEncoderMotor(SLOT_1);
|
||||
encoders[1] = MeEncoderMotor(SLOT_2);
|
||||
encoders[0].begin();
|
||||
encoders[1].begin();
|
||||
delay(500);
|
||||
encoders[0].runSpeed(0);
|
||||
encoders[1].runSpeed(0);
|
||||
#else
|
||||
Serial1.begin(115200);
|
||||
#endif
|
||||
gyro.begin();
|
||||
Serial.print("Version: ");
|
||||
Serial.println(mVersion);
|
||||
}
|
||||
void loop(){
|
||||
keyPressed = buttonSensor.pressed();
|
||||
currentTime = millis()/1000.0-lastTime;
|
||||
if(ir != NULL)
|
||||
{
|
||||
ir->loop();
|
||||
}
|
||||
readSerial();
|
||||
steppers[0].runSpeedToPosition();
|
||||
steppers[1].runSpeedToPosition();
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
unsigned char readBuffer(int index){
|
||||
return isBluetooth?bufferBt[index]:buffer[index];
|
||||
}
|
||||
void writeBuffer(int index,unsigned char c){
|
||||
if(isBluetooth){
|
||||
bufferBt[index]=c;
|
||||
}else{
|
||||
buffer[index]=c;
|
||||
}
|
||||
}
|
||||
void writeHead(){
|
||||
writeSerial(0xff);
|
||||
writeSerial(0x55);
|
||||
}
|
||||
void writeEnd(){
|
||||
Serial.println();
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
Serial1.println();
|
||||
#endif
|
||||
}
|
||||
void writeSerial(unsigned char c){
|
||||
Serial.write(c);
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
Serial1.write(c);
|
||||
#endif
|
||||
}
|
||||
void readSerial(){
|
||||
isAvailable = false;
|
||||
if(Serial.available()>0){
|
||||
isAvailable = true;
|
||||
isBluetooth = false;
|
||||
serialRead = Serial.read();
|
||||
}
|
||||
//#if defined(__AVR_ATmega32U4__)
|
||||
// if(Serial1.available()>0){
|
||||
// isAvailable = true;
|
||||
// isBluetooth = false;
|
||||
// serialRead = Serial1.read();
|
||||
// }
|
||||
// #endif
|
||||
}
|
||||
/*
|
||||
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);
|
||||
command_index = (uint8_t)idx;
|
||||
int action = readBuffer(4);
|
||||
int device = readBuffer(5);
|
||||
switch(action){
|
||||
case GET:{
|
||||
if(device != ULTRASONIC_SENSOR){
|
||||
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);
|
||||
dc.reset(PORT_1);
|
||||
dc.run(0);
|
||||
dc.reset(PORT_2);
|
||||
dc.run(0);
|
||||
|
||||
#if defined(__AVR_ATmega328P__)
|
||||
encoders[0].runSpeed(0);
|
||||
encoders[1].runSpeed(0);
|
||||
#endif
|
||||
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<l;i++){
|
||||
writeSerial(s.charAt(i));
|
||||
}
|
||||
}
|
||||
void sendFloat(float value){
|
||||
writeSerial(0x2);
|
||||
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]);
|
||||
}
|
||||
void sendDouble(double value){
|
||||
writeSerial(2);
|
||||
valDouble.doubleVal = value;
|
||||
writeSerial(valDouble.byteVal[0]);
|
||||
writeSerial(valDouble.byteVal[1]);
|
||||
writeSerial(valDouble.byteVal[2]);
|
||||
writeSerial(valDouble.byteVal[3]);
|
||||
}
|
||||
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;
|
||||
}
|
||||
long readLong(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.longVal;
|
||||
}
|
||||
void runModule(int device){
|
||||
//0xff 0x55 0x6 0x0 0x1 0xa 0x9 0x0 0x0 0xa
|
||||
int port = readBuffer(6);
|
||||
int pin = port;
|
||||
switch(device){
|
||||
case MOTOR:{
|
||||
int speed = readShort(7);
|
||||
dc.reset(port);
|
||||
dc.run(speed);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
int leftSpeed = readShort(6);
|
||||
dc.reset(M1);
|
||||
dc.run(leftSpeed);
|
||||
int rightSpeed = readShort(8);
|
||||
dc.reset(M2);
|
||||
dc.run(rightSpeed);
|
||||
}
|
||||
break;
|
||||
case STEPPER:{
|
||||
int maxSpeed = readShort(7);
|
||||
long distance = readLong(9);
|
||||
if(port==PORT_1){
|
||||
steppers[0] = MeStepper(PORT_1);
|
||||
steppers[0].moveTo(distance);
|
||||
steppers[0].setMaxSpeed(maxSpeed);
|
||||
steppers[0].setSpeed(maxSpeed);
|
||||
}else if(port==PORT_2){
|
||||
steppers[1] = MeStepper(PORT_2);
|
||||
steppers[1].moveTo(distance);
|
||||
steppers[1].setMaxSpeed(maxSpeed);
|
||||
steppers[1].setSpeed(maxSpeed);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case ENCODER:{
|
||||
int slot = readBuffer(7);
|
||||
int maxSpeed = readShort(8);
|
||||
float distance = readFloat(10);
|
||||
#if defined(__AVR_ATmega328P__)
|
||||
if(slot==SLOT_1){
|
||||
encoders[0].move(distance,maxSpeed);
|
||||
}else if(slot==SLOT_2){
|
||||
encoders[1].move(distance,maxSpeed);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
case RGBLED:{
|
||||
int slot = readBuffer(7);
|
||||
int idx = readBuffer(8);
|
||||
int r = readBuffer(9);
|
||||
int g = readBuffer(10);
|
||||
int b = readBuffer(11);
|
||||
if((led.getPort() != port) || led.getSlot() != slot)
|
||||
{
|
||||
led.reset(port,slot);
|
||||
}
|
||||
if(idx>0)
|
||||
{
|
||||
led.setColorAt(idx-1,r,g,b);
|
||||
}
|
||||
else
|
||||
{
|
||||
led.setColor(r,g,b);
|
||||
}
|
||||
led.show();
|
||||
}
|
||||
break;
|
||||
case SERVO:{
|
||||
int slot = readBuffer(7);
|
||||
pin = slot==1?mePort[port].s1:mePort[port].s2;
|
||||
int v = readBuffer(8);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(!sv.attached())
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SEVSEG:{
|
||||
if(seg.getPort()!=port){
|
||||
seg.reset(port);
|
||||
}
|
||||
float v = readFloat(7);
|
||||
seg.display(v);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
generalDevice.dWrite1(v);
|
||||
}
|
||||
break;
|
||||
case SHUTTER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
if(v<2){
|
||||
generalDevice.dWrite1(v);
|
||||
}else{
|
||||
generalDevice.dWrite2(v-2);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
digitalWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case PWM:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
analogWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case TONE:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int hz = readShort(7);
|
||||
int ms = readShort(9);
|
||||
if(ms>0){
|
||||
buzzer.tone(pin, hz, ms);
|
||||
}else{
|
||||
buzzer.noTone(pin);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SERVO_PIN:{
|
||||
int v = readBuffer(7);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(!sv.attached())
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
lastTime = millis()/1000.0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int searchServoPin(int pin){
|
||||
for(int i=0;i<8;i++){
|
||||
if(servo_pins[i] == pin){
|
||||
return i;
|
||||
}
|
||||
if(servo_pins[i]==0){
|
||||
servo_pins[i] = pin;
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
void readSensor(int device){
|
||||
/**************************************************
|
||||
ff 55 len idx action device port slot data a
|
||||
0 1 2 3 4 5 6 7 8
|
||||
***************************************************/
|
||||
float value=0.0;
|
||||
int port,slot,pin;
|
||||
port = readBuffer(6);
|
||||
pin = port;
|
||||
switch(device){
|
||||
case ULTRASONIC_SENSOR:{
|
||||
if(us.getPort()!=port){
|
||||
us.reset(port);
|
||||
}
|
||||
value = us.distanceCm();
|
||||
writeHead();
|
||||
writeSerial(command_index);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case TEMPERATURE_SENSOR:{
|
||||
slot = readBuffer(7);
|
||||
if(ts.getPort()!=port||ts.getSlot()!=slot){
|
||||
ts.reset(port,slot);
|
||||
}
|
||||
value = ts.temperature();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:
|
||||
case SOUND_SENSOR:
|
||||
case POTENTIONMETER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.aRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
slot = readBuffer(7);
|
||||
if(joystick.getPort() != port){
|
||||
joystick.reset(port);
|
||||
}
|
||||
value = joystick.read(slot);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case INFRARED:
|
||||
{
|
||||
if(ir == NULL)
|
||||
{
|
||||
ir = new MeInfraredReceiver(port);
|
||||
ir->begin();
|
||||
}
|
||||
else if(ir->getPort() != port)
|
||||
{
|
||||
delete ir;
|
||||
ir = new MeInfraredReceiver(port);
|
||||
ir->begin();
|
||||
}
|
||||
irRead = ir->getCode();
|
||||
if((irRead < 255) && (irRead > 0))
|
||||
{
|
||||
sendFloat((float)irRead);
|
||||
}
|
||||
else
|
||||
{
|
||||
sendFloat(0);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case PIRMOTION:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LINEFOLLOWER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin1(),INPUT);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead1()*2+generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIMITSWITCH:{
|
||||
slot = readBuffer(7);
|
||||
if(generalDevice.getPort()!=port||generalDevice.getSlot()!=slot){
|
||||
generalDevice.reset(port,slot);
|
||||
}
|
||||
if(slot==1){
|
||||
pinMode(generalDevice.pin1(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead1();
|
||||
}else{
|
||||
pinMode(generalDevice.pin2(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead2();
|
||||
}
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
// case COMPASS:{
|
||||
// if(Compass.getPort()!=port){
|
||||
// Compass.reset(port);
|
||||
// Compass.setpin(Compass.pin1(),Compass.pin2());
|
||||
// }
|
||||
// double CompassAngle;
|
||||
// CompassAngle = Compass.getAngle();
|
||||
// sendDouble(CompassAngle);
|
||||
// }
|
||||
// break;
|
||||
case HUMITURE:{
|
||||
uint8_t index = readBuffer(7);
|
||||
if(humiture.getPort()!=port){
|
||||
humiture.reset(port);
|
||||
}
|
||||
uint8_t HumitureData;
|
||||
humiture.update();
|
||||
HumitureData = humiture.getValue(index);
|
||||
sendByte(HumitureData);
|
||||
}
|
||||
break;
|
||||
case FLAMESENSOR:{
|
||||
if(FlameSensor.getPort()!=port){
|
||||
FlameSensor.reset(port);
|
||||
FlameSensor.setpin(FlameSensor.pin2(),FlameSensor.pin1());
|
||||
}
|
||||
int16_t FlameData;
|
||||
FlameData = FlameSensor.readAnalog();
|
||||
sendShort(FlameData);
|
||||
}
|
||||
break;
|
||||
case GASSENSOR:{
|
||||
if(GasSensor.getPort()!=port){
|
||||
GasSensor.reset(port);
|
||||
GasSensor.setpin(GasSensor.pin2(),GasSensor.pin1());
|
||||
}
|
||||
int16_t GasData;
|
||||
GasData = GasSensor.readAnalog();
|
||||
sendShort(GasData);
|
||||
}
|
||||
break;
|
||||
case GYRO:{
|
||||
int axis = readBuffer(7);
|
||||
gyro.update();
|
||||
if(axis == 1){
|
||||
value = gyro.getAngleX();
|
||||
sendFloat(value);
|
||||
}else if(axis == 2){
|
||||
value = gyro.getAngleY();
|
||||
sendFloat(value);
|
||||
}else if(axis == 3){
|
||||
value = gyro.getAngleZ();
|
||||
sendFloat(value);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case VERSION:{
|
||||
sendString(mVersion);
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(digitalRead(pin));
|
||||
}
|
||||
break;
|
||||
case ANALOG:{
|
||||
pin = analogs[pin];
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(analogRead(pin));
|
||||
}
|
||||
break;
|
||||
case PULSEIN:{
|
||||
int pw = readShort(7);
|
||||
pinMode(pin, INPUT);
|
||||
sendShort(pulseIn(pin,HIGH,pw));
|
||||
}
|
||||
break;
|
||||
case ULTRASONIC_ARDUINO:{
|
||||
int trig = readBuffer(6);
|
||||
int echo = readBuffer(7);
|
||||
pinMode(trig,OUTPUT);
|
||||
digitalWrite(trig,LOW);
|
||||
delayMicroseconds(2);
|
||||
digitalWrite(trig,HIGH);
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(trig,LOW);
|
||||
pinMode(echo, INPUT);
|
||||
sendFloat(pulseIn(echo,HIGH,30000)/58.0);
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
sendFloat((float)currentTime);
|
||||
}
|
||||
break;
|
||||
case TOUCH_SENSOR:
|
||||
{
|
||||
if(touchSensor.getPort() != port){
|
||||
touchSensor.reset(port);
|
||||
}
|
||||
sendByte(touchSensor.touched());
|
||||
}
|
||||
break;
|
||||
case BUTTON:
|
||||
{
|
||||
if(buttonSensor.getPort() != port){
|
||||
buttonSensor.reset(port);
|
||||
}
|
||||
sendByte(keyPressed == readBuffer(7));
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,736 @@
|
|||
/*************************************************************************
|
||||
* File Name : shield_firmware.ino
|
||||
* Author : Ander, Mark Yan
|
||||
* Updated : Ander, Mark Yan
|
||||
* Version : V0c.01.105
|
||||
* Date : 07/06/2016
|
||||
* Description : Firmware for Makeblock Electronic modules with Scratch.
|
||||
* License : CC-BY-SA 3.0
|
||||
* Copyright (C) 2013 - 2016 Maker Works Technology Co., Ltd. All right reserved.
|
||||
* http://www.makeblock.cc/
|
||||
**************************************************************************/
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
#include <Arduino.h>
|
||||
#include <MeShield.h>
|
||||
|
||||
Servo servos[8];
|
||||
MeDCMotor dc;
|
||||
MeTemperature ts;
|
||||
MeRGBLed led;
|
||||
MeUltrasonicSensor us;
|
||||
Me7SegmentDisplay seg;
|
||||
MePort generalDevice;
|
||||
MeInfraredReceiver *ir = NULL;
|
||||
MeGyro gyro;
|
||||
MeJoystick joystick;
|
||||
MeStepper steppers[4];
|
||||
MeBuzzer buzzer;
|
||||
MeHumiture humiture;
|
||||
MeFlameSensor FlameSensor;
|
||||
MeGasSensor GasSensor;
|
||||
MeTouchSensor touchSensor;
|
||||
Me4Button buttonSensor;
|
||||
|
||||
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;
|
||||
MeModule modules[12];
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
int analogs[12]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11};
|
||||
#endif
|
||||
#if defined(__AVR_ATmega328P__) or defined(__AVR_ATmega168__)
|
||||
int analogs[8]={A0,A1,A2,A3,A4,A5,A6,A7};
|
||||
MeEncoderMotor encoders[2];
|
||||
#endif
|
||||
#if defined(__AVR_ATmega1280__)|| defined(__AVR_ATmega2560__)
|
||||
int analogs[16]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15};
|
||||
#endif
|
||||
String mVersion = "0c.01.105";
|
||||
boolean isAvailable = false;
|
||||
boolean isBluetooth = false;
|
||||
|
||||
int len = 52;
|
||||
char buffer[52];
|
||||
char bufferBt[52];
|
||||
byte index = 0;
|
||||
byte dataLen;
|
||||
byte modulesLen=0;
|
||||
boolean isStart = false;
|
||||
unsigned char irRead;
|
||||
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 PULSEIN 37
|
||||
#define ULTRASONIC_ARDUINO 36
|
||||
#define STEPPER 40
|
||||
#define LEDMATRIX 41
|
||||
#define TIMER 50
|
||||
#define TOUCH_SENSOR 51
|
||||
|
||||
#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;
|
||||
double lastTime = 0.0;
|
||||
double currentTime = 0.0;
|
||||
uint8_t keyPressed = 0;
|
||||
uint8_t command_index = 0;
|
||||
|
||||
void setup(){
|
||||
pinMode(13,OUTPUT);
|
||||
digitalWrite(13,HIGH);
|
||||
delay(300);
|
||||
digitalWrite(13,LOW);
|
||||
Serial.begin(115200);
|
||||
delay(500);
|
||||
buzzerOn();
|
||||
delay(100);
|
||||
buzzerOff();
|
||||
#if defined(__AVR_ATmega328P__) or defined(__AVR_ATmega168__)
|
||||
encoders[0] = MeEncoderMotor(SLOT_1);
|
||||
encoders[1] = MeEncoderMotor(SLOT_2);
|
||||
encoders[0].begin();
|
||||
encoders[1].begin();
|
||||
delay(500);
|
||||
encoders[0].runSpeed(0);
|
||||
encoders[1].runSpeed(0);
|
||||
#else
|
||||
Serial1.begin(115200);
|
||||
#endif
|
||||
gyro.begin();
|
||||
Serial.print("Version: ");
|
||||
Serial.println(mVersion);
|
||||
}
|
||||
void loop(){
|
||||
keyPressed = buttonSensor.pressed();
|
||||
currentTime = millis()/1000.0-lastTime;
|
||||
if(ir != NULL)
|
||||
{
|
||||
ir->loop();
|
||||
}
|
||||
readSerial();
|
||||
steppers[0].runSpeedToPosition();
|
||||
steppers[1].runSpeedToPosition();
|
||||
steppers[2].runSpeedToPosition();
|
||||
steppers[3].runSpeedToPosition();
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
unsigned char readBuffer(int index){
|
||||
return isBluetooth?bufferBt[index]:buffer[index];
|
||||
}
|
||||
void writeBuffer(int index,unsigned char c){
|
||||
if(isBluetooth){
|
||||
bufferBt[index]=c;
|
||||
}else{
|
||||
buffer[index]=c;
|
||||
}
|
||||
}
|
||||
void writeHead(){
|
||||
writeSerial(0xff);
|
||||
writeSerial(0x55);
|
||||
}
|
||||
void writeEnd(){
|
||||
Serial.println();
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
Serial1.println();
|
||||
#endif
|
||||
}
|
||||
void writeSerial(unsigned char c){
|
||||
Serial.write(c);
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
Serial1.write(c);
|
||||
#endif
|
||||
}
|
||||
void readSerial(){
|
||||
isAvailable = false;
|
||||
if(Serial.available()>0){
|
||||
isAvailable = true;
|
||||
isBluetooth = false;
|
||||
serialRead = Serial.read();
|
||||
}
|
||||
//#if defined(__AVR_ATmega32U4__)
|
||||
// if(Serial1.available()>0){
|
||||
// isAvailable = true;
|
||||
// isBluetooth = false;
|
||||
// serialRead = Serial1.read();
|
||||
// }
|
||||
// #endif
|
||||
}
|
||||
/*
|
||||
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);
|
||||
command_index = (uint8_t)idx;
|
||||
int action = readBuffer(4);
|
||||
int device = readBuffer(5);
|
||||
switch(action){
|
||||
case GET:{
|
||||
if(device != ULTRASONIC_SENSOR){
|
||||
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);
|
||||
dc.reset(PORT_1);
|
||||
dc.run(0);
|
||||
dc.reset(PORT_2);
|
||||
dc.run(0);
|
||||
|
||||
#if defined(__AVR_ATmega328P__)
|
||||
encoders[0].runSpeed(0);
|
||||
encoders[1].runSpeed(0);
|
||||
#endif
|
||||
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<l;i++){
|
||||
writeSerial(s.charAt(i));
|
||||
}
|
||||
}
|
||||
void sendFloat(float value){
|
||||
writeSerial(0x2);
|
||||
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]);
|
||||
}
|
||||
void sendDouble(double value){
|
||||
writeSerial(2);
|
||||
valDouble.doubleVal = value;
|
||||
writeSerial(valDouble.byteVal[0]);
|
||||
writeSerial(valDouble.byteVal[1]);
|
||||
writeSerial(valDouble.byteVal[2]);
|
||||
writeSerial(valDouble.byteVal[3]);
|
||||
}
|
||||
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;
|
||||
}
|
||||
long readLong(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.longVal;
|
||||
}
|
||||
void runModule(int device){
|
||||
//0xff 0x55 0x6 0x0 0x1 0xa 0x9 0x0 0x0 0xa
|
||||
int port = readBuffer(6);
|
||||
int pin = port;
|
||||
switch(device){
|
||||
case MOTOR:{
|
||||
int speed = readShort(7);
|
||||
dc.reset(port);
|
||||
dc.run(speed);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
int leftSpeed = readShort(6);
|
||||
dc.reset(M1);
|
||||
dc.run(leftSpeed);
|
||||
int rightSpeed = readShort(8);
|
||||
dc.reset(M2);
|
||||
dc.run(rightSpeed);
|
||||
}
|
||||
break;
|
||||
case STEPPER:{
|
||||
int maxSpeed = readShort(7);
|
||||
long distance = readLong(9);
|
||||
if(port==PORT_1){
|
||||
steppers[0] = MeStepper(PORT_1);
|
||||
steppers[0].moveTo(distance);
|
||||
steppers[0].setMaxSpeed(maxSpeed);
|
||||
steppers[0].setSpeed(maxSpeed);
|
||||
}else if(port==PORT_2){
|
||||
steppers[1] = MeStepper(PORT_2);
|
||||
steppers[1].moveTo(distance);
|
||||
steppers[1].setMaxSpeed(maxSpeed);
|
||||
steppers[1].setSpeed(maxSpeed);
|
||||
}else if(port==M1){
|
||||
steppers[2] = MeStepper(M1);
|
||||
steppers[2].moveTo(distance);
|
||||
steppers[2].setMaxSpeed(maxSpeed);
|
||||
steppers[2].setSpeed(maxSpeed);
|
||||
}else if(port==M2){
|
||||
steppers[3] = MeStepper(M2);
|
||||
steppers[3].moveTo(distance);
|
||||
steppers[3].setMaxSpeed(maxSpeed);
|
||||
steppers[3].setSpeed(maxSpeed);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case ENCODER:{
|
||||
int slot = readBuffer(7);
|
||||
int maxSpeed = readShort(8);
|
||||
float distance = readFloat(10);
|
||||
#if defined(__AVR_ATmega328P__)
|
||||
if(slot==SLOT_1){
|
||||
encoders[0].move(distance,maxSpeed);
|
||||
}else if(slot==SLOT_2){
|
||||
encoders[1].move(distance,maxSpeed);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
case RGBLED:{
|
||||
int slot = readBuffer(7);
|
||||
int idx = readBuffer(8);
|
||||
int r = readBuffer(9);
|
||||
int g = readBuffer(10);
|
||||
int b = readBuffer(11);
|
||||
led.reset(port,slot);
|
||||
if(idx>0){
|
||||
led.setColorAt(idx-1,r,g,b);
|
||||
}else{
|
||||
led.setColor(r,g,b);
|
||||
}
|
||||
led.show();
|
||||
}
|
||||
break;
|
||||
case SERVO:{
|
||||
int slot = readBuffer(7);
|
||||
pin = slot==1?mePort[port].s1:mePort[port].s2;
|
||||
int v = readBuffer(8);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v>=0&&v<=180){
|
||||
if(port>0){
|
||||
sv.attach(pin);
|
||||
}else{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SEVSEG:{
|
||||
if(seg.getPort()!=port){
|
||||
seg.reset(port);
|
||||
}
|
||||
float v = readFloat(7);
|
||||
seg.display(v);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
generalDevice.dWrite1(v);
|
||||
}
|
||||
break;
|
||||
case SHUTTER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
if(v<2){
|
||||
generalDevice.dWrite1(v);
|
||||
}else{
|
||||
generalDevice.dWrite2(v-2);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
digitalWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case PWM:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
analogWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case TONE:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int hz = readShort(7);
|
||||
int ms = readShort(9);
|
||||
if(ms>0){
|
||||
buzzer.tone(pin, hz, ms);
|
||||
}else{
|
||||
buzzer.noTone(pin);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SERVO_PIN:{
|
||||
int v = readBuffer(7);
|
||||
if(v>=0&&v<=180){
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
sv.attach(pin);
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
lastTime = millis()/1000.0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int searchServoPin(int pin){
|
||||
for(int i=0;i<8;i++){
|
||||
if(servo_pins[i] == pin){
|
||||
return i;
|
||||
}
|
||||
if(servo_pins[i]==0){
|
||||
servo_pins[i] = pin;
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
void readSensor(int device){
|
||||
/**************************************************
|
||||
ff 55 len idx action device port slot data a
|
||||
0 1 2 3 4 5 6 7 8
|
||||
***************************************************/
|
||||
float value=0.0;
|
||||
int port,slot,pin;
|
||||
port = readBuffer(6);
|
||||
pin = port;
|
||||
switch(device){
|
||||
case ULTRASONIC_SENSOR:{
|
||||
if(us.getPort()!=port){
|
||||
us.reset(port);
|
||||
}
|
||||
value = us.distanceCm();
|
||||
writeHead();
|
||||
writeSerial(command_index);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case TEMPERATURE_SENSOR:{
|
||||
slot = readBuffer(7);
|
||||
if(ts.getPort()!=port||ts.getSlot()!=slot){
|
||||
ts.reset(port,slot);
|
||||
}
|
||||
value = ts.temperature();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:
|
||||
case SOUND_SENSOR:
|
||||
case POTENTIONMETER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.aRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
slot = readBuffer(7);
|
||||
if(joystick.getPort() != port){
|
||||
joystick.reset(port);
|
||||
}
|
||||
value = joystick.read(slot);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case INFRARED:
|
||||
{
|
||||
if(ir == NULL)
|
||||
{
|
||||
ir = new MeInfraredReceiver(port);
|
||||
ir->begin();
|
||||
}
|
||||
else if(ir->getPort() != port)
|
||||
{
|
||||
delete ir;
|
||||
ir = new MeInfraredReceiver(port);
|
||||
ir->begin();
|
||||
}
|
||||
irRead = ir->getCode();
|
||||
if((irRead < 255) && (irRead > 0))
|
||||
{
|
||||
sendFloat((float)irRead);
|
||||
}
|
||||
else
|
||||
{
|
||||
sendFloat(0);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case PIRMOTION:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LINEFOLLOWER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin1(),INPUT);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead1()*2+generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIMITSWITCH:{
|
||||
slot = readBuffer(7);
|
||||
if(generalDevice.getPort()!=port||generalDevice.getSlot()!=slot){
|
||||
generalDevice.reset(port,slot);
|
||||
}
|
||||
if(slot==1){
|
||||
pinMode(generalDevice.pin1(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead1();
|
||||
}else{
|
||||
pinMode(generalDevice.pin2(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead2();
|
||||
}
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
// case COMPASS:{
|
||||
// if(Compass.getPort()!=port){
|
||||
// Compass.reset(port);
|
||||
// Compass.setpin(Compass.pin1(),Compass.pin2());
|
||||
// }
|
||||
// double CompassAngle;
|
||||
// CompassAngle = Compass.getAngle();
|
||||
// sendDouble(CompassAngle);
|
||||
// }
|
||||
// break;
|
||||
case HUMITURE:{
|
||||
uint8_t index = readBuffer(7);
|
||||
if(humiture.getPort()!=port){
|
||||
humiture.reset(port);
|
||||
}
|
||||
uint8_t HumitureData;
|
||||
humiture.update();
|
||||
HumitureData = humiture.getValue(index);
|
||||
sendByte(HumitureData);
|
||||
}
|
||||
break;
|
||||
case FLAMESENSOR:{
|
||||
if(FlameSensor.getPort()!=port){
|
||||
FlameSensor.reset(port);
|
||||
FlameSensor.setpin(FlameSensor.pin2(),FlameSensor.pin1());
|
||||
}
|
||||
int16_t FlameData;
|
||||
FlameData = FlameSensor.readAnalog();
|
||||
sendShort(FlameData);
|
||||
}
|
||||
break;
|
||||
case GASSENSOR:{
|
||||
if(GasSensor.getPort()!=port){
|
||||
GasSensor.reset(port);
|
||||
GasSensor.setpin(GasSensor.pin2(),GasSensor.pin1());
|
||||
}
|
||||
int16_t GasData;
|
||||
GasData = GasSensor.readAnalog();
|
||||
sendShort(GasData);
|
||||
}
|
||||
break;
|
||||
case GYRO:{
|
||||
int axis = readBuffer(7);
|
||||
gyro.update();
|
||||
if(axis == 1){
|
||||
value = gyro.getAngleX();
|
||||
sendFloat(value);
|
||||
}else if(axis == 2){
|
||||
value = gyro.getAngleY();
|
||||
sendFloat(value);
|
||||
}else if(axis == 3){
|
||||
value = gyro.getAngleZ();
|
||||
sendFloat(value);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case VERSION:{
|
||||
sendString(mVersion);
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(digitalRead(pin));
|
||||
}
|
||||
break;
|
||||
case ANALOG:{
|
||||
pin = analogs[pin];
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(analogRead(pin));
|
||||
}
|
||||
break;
|
||||
case PULSEIN:{
|
||||
int pw = readShort(7);
|
||||
pinMode(pin, INPUT);
|
||||
sendShort(pulseIn(pin,HIGH,pw));
|
||||
}
|
||||
break;
|
||||
case ULTRASONIC_ARDUINO:{
|
||||
int trig = readBuffer(6);
|
||||
int echo = readBuffer(7);
|
||||
pinMode(trig,OUTPUT);
|
||||
digitalWrite(trig,LOW);
|
||||
delayMicroseconds(2);
|
||||
digitalWrite(trig,HIGH);
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(trig,LOW);
|
||||
pinMode(echo, INPUT);
|
||||
sendFloat(pulseIn(echo,HIGH,30000)/58.0);
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
sendFloat((float)currentTime);
|
||||
}
|
||||
break;
|
||||
case TOUCH_SENSOR:
|
||||
{
|
||||
if(touchSensor.getPort() != port){
|
||||
touchSensor.reset(port);
|
||||
}
|
||||
sendByte(touchSensor.touched());
|
||||
}
|
||||
break;
|
||||
case BUTTON:
|
||||
{
|
||||
if(buttonSensor.getPort() != port){
|
||||
buttonSensor.reset(port);
|
||||
}
|
||||
sendByte(keyPressed == readBuffer(7));
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
|
@ -0,0 +1,908 @@
|
|||
/*************************************************************************
|
||||
* File Name :starter_factory_firmware.ino
|
||||
* Author : Ander, Mark Yan
|
||||
* Updated : Ander, Mark Yan
|
||||
* Version : V0a.01.007
|
||||
* Date : 21/06/2017
|
||||
* Description : Firmware for Makeblock Electronic modules with Scratch.
|
||||
* License : CC-BY-SA 3.0
|
||||
* Copyright (C) 2013 - 2016 Maker Works Technology Co., Ltd. All right reserved.
|
||||
* http://www.makeblock.cc/
|
||||
**************************************************************************/
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
#include <Arduino.h>
|
||||
#include <MeOrion.h>
|
||||
|
||||
Servo servos[8];
|
||||
MeInfraredReceiver infraredReceiverDecode(PORT_6);
|
||||
MeDCMotor dc;
|
||||
MeTemperature ts;
|
||||
MeRGBLed led;
|
||||
MeUltrasonicSensor us(PORT_3);
|
||||
Me7SegmentDisplay seg;
|
||||
MePort generalDevice;
|
||||
MeJoystick joystick;
|
||||
MeStepper steppers[2];
|
||||
MeBuzzer buzzer;
|
||||
MeHumiture humiture;
|
||||
MeFlameSensor FlameSensor;
|
||||
MeGasSensor GasSensor;
|
||||
MeTouchSensor touchSensor;
|
||||
Me4Button buttonSensor;
|
||||
|
||||
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;
|
||||
MeModule modules[12];
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
int analogs[12]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11};
|
||||
#endif
|
||||
#if defined(__AVR_ATmega328P__) or defined(__AVR_ATmega168__)
|
||||
int analogs[8]={A0,A1,A2,A3,A4,A5,A6,A7};
|
||||
#endif
|
||||
#if defined(__AVR_ATmega1280__)|| defined(__AVR_ATmega2560__)
|
||||
int analogs[16]={A0,A1,A2,A3,A4,A5,A6,A7,A8,A9,A10,A11,A12,A13,A14,A15};
|
||||
#endif
|
||||
|
||||
#define BLUE_TOOTH 0
|
||||
#define IR_CONTROLER 1
|
||||
|
||||
boolean isStart = false;
|
||||
boolean isAvailable = false;
|
||||
boolean leftflag = false;
|
||||
boolean rightflag = false;
|
||||
|
||||
char buffer[52];
|
||||
char serialRead;
|
||||
byte index = 0;
|
||||
byte dataLen;
|
||||
byte modulesLen=0;
|
||||
uint8_t keyPressed = 0;
|
||||
uint8_t command_index = 0;
|
||||
uint8_t irRead = 0;
|
||||
uint8_t prevc=0;
|
||||
uint8_t controlflag = IR_CONTROLER;
|
||||
|
||||
int len = 52;
|
||||
int moveSpeed = 190;
|
||||
int turnSpeed = 200;
|
||||
int minSpeed = 45;
|
||||
int factor = 23;
|
||||
int distance=0;
|
||||
int randnum = 0;
|
||||
int starter_mode = 0;
|
||||
int servo_pins[8]={0,0,0,0,0,0,0,0};
|
||||
|
||||
double lastTime = 0.0;
|
||||
double currentTime = 0.0;
|
||||
float angleServo = 90.0;
|
||||
|
||||
String mVersion = "0a.01.007";
|
||||
|
||||
#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 PIRMOTION 15
|
||||
#define INFRARED 16
|
||||
#define LINEFOLLOWER 17
|
||||
#define SHUTTER 20
|
||||
#define LIMITSWITCH 21
|
||||
#define BUTTON 22
|
||||
#define HUMITURE 23
|
||||
#define FLAMESENSOR 24
|
||||
#define GASSENSOR 25
|
||||
#define COMPASS 26
|
||||
#define TEMPERATURE_SENSOR_1 27
|
||||
#define DIGITAL 30
|
||||
#define ANALOG 31
|
||||
#define PWM 32
|
||||
#define SERVO_PIN 33
|
||||
#define TONE 34
|
||||
#define BUTTON_INNER 35
|
||||
#define ULTRASONIC_ARDUINO 36
|
||||
#define PULSEIN 37
|
||||
#define STEPPER 40
|
||||
#define LEDMATRIX 41
|
||||
#define TIMER 50
|
||||
#define TOUCH_SENSOR 51
|
||||
#define JOYSTICK_MOVE 52
|
||||
#define COMMON_COMMONCMD 60
|
||||
//Secondary command
|
||||
#define SET_STARTER_MODE 0x10
|
||||
#define SET_AURIGA_MODE 0x11
|
||||
#define SET_MEGAPI_MODE 0x12
|
||||
#define GET_BATTERY_POWER 0x70
|
||||
#define GET_AURIGA_MODE 0x71
|
||||
#define GET_MEGAPI_MODE 0x72
|
||||
#define ENCODER_BOARD 61
|
||||
//Read type
|
||||
#define ENCODER_BOARD_POS 0x01
|
||||
#define ENCODER_BOARD_SPEED 0x02
|
||||
|
||||
#define ENCODER_PID_MOTION 62
|
||||
//Secondary command
|
||||
#define ENCODER_BOARD_POS_MOTION 0x01
|
||||
#define ENCODER_BOARD_SPEED_MOTION 0x02
|
||||
#define ENCODER_BOARD_PWM_MOTION 0x03
|
||||
#define ENCODER_BOARD_SET_CUR_POS_ZERO 0x04
|
||||
#define ENCODER_BOARD_CAR_POS_MOTION 0x05
|
||||
|
||||
#define GET 1
|
||||
#define RUN 2
|
||||
#define RESET 4
|
||||
#define START 5
|
||||
|
||||
void Forward()
|
||||
{
|
||||
dc.reset(M1);
|
||||
dc.run(-moveSpeed);
|
||||
dc.reset(M2);
|
||||
dc.run(moveSpeed);
|
||||
}
|
||||
|
||||
void Backward()
|
||||
{
|
||||
dc.reset(M1);
|
||||
dc.run(moveSpeed);
|
||||
dc.reset(M2);
|
||||
dc.run(-moveSpeed);
|
||||
}
|
||||
|
||||
void BackwardAndTurnLeft()
|
||||
{
|
||||
dc.reset(M1);
|
||||
dc.run(moveSpeed/2);
|
||||
dc.reset(M2);
|
||||
dc.run(-moveSpeed);
|
||||
}
|
||||
|
||||
void BackwardAndTurnRight()
|
||||
{
|
||||
dc.reset(M1);
|
||||
dc.run(moveSpeed);
|
||||
dc.reset(M2);
|
||||
dc.run(-moveSpeed/2);
|
||||
}
|
||||
|
||||
void TurnLeft()
|
||||
{
|
||||
dc.reset(M1);
|
||||
dc.run(moveSpeed);
|
||||
dc.reset(M2);
|
||||
dc.run(moveSpeed);
|
||||
}
|
||||
|
||||
void TurnRight()
|
||||
{
|
||||
dc.reset(M1);
|
||||
dc.run(-moveSpeed);
|
||||
dc.reset(M2);
|
||||
dc.run(-moveSpeed);
|
||||
}
|
||||
|
||||
void Stop()
|
||||
{
|
||||
dc.reset(M1);
|
||||
dc.run(0);
|
||||
dc.reset(M2);
|
||||
dc.run(0);
|
||||
}
|
||||
void ChangeSpeed(int spd)
|
||||
{
|
||||
moveSpeed = spd;
|
||||
}
|
||||
|
||||
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();
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
Serial1.println();
|
||||
#endif
|
||||
}
|
||||
|
||||
void writeSerial(unsigned char c){
|
||||
Serial.write(c);
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
Serial1.write(c);
|
||||
#endif
|
||||
}
|
||||
|
||||
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);
|
||||
command_index = (uint8_t)idx;
|
||||
int action = readBuffer(4);
|
||||
int device = readBuffer(5);
|
||||
switch(action){
|
||||
case GET:{
|
||||
if(device != ULTRASONIC_SENSOR){
|
||||
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);
|
||||
dc.reset(PORT_1);
|
||||
dc.run(0);
|
||||
dc.reset(PORT_2);
|
||||
dc.run(0);
|
||||
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<l;i++){
|
||||
writeSerial(s.charAt(i));
|
||||
}
|
||||
}
|
||||
|
||||
void sendFloat(float value){
|
||||
writeSerial(0x2);
|
||||
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]);
|
||||
}
|
||||
|
||||
void sendDouble(double value){
|
||||
writeSerial(2);
|
||||
valDouble.doubleVal = value;
|
||||
writeSerial(valDouble.byteVal[0]);
|
||||
writeSerial(valDouble.byteVal[1]);
|
||||
writeSerial(valDouble.byteVal[2]);
|
||||
writeSerial(valDouble.byteVal[3]);
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
long readLong(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.longVal;
|
||||
}
|
||||
|
||||
void runModule(int device){
|
||||
//0xff 0x55 0x6 0x0 0x1 0xa 0x9 0x0 0x0 0xa
|
||||
int port = readBuffer(6);
|
||||
int pin = port;
|
||||
switch(device){
|
||||
case MOTOR:{
|
||||
controlflag = BLUE_TOOTH;
|
||||
int speed = readShort(7);
|
||||
dc.reset(port);
|
||||
dc.run(speed);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
controlflag = BLUE_TOOTH;
|
||||
int leftSpeed = readShort(6);
|
||||
dc.reset(M1);
|
||||
dc.run(leftSpeed);
|
||||
int rightSpeed = readShort(8);
|
||||
dc.reset(M2);
|
||||
dc.run(rightSpeed);
|
||||
}
|
||||
break;
|
||||
case STEPPER:{
|
||||
int maxSpeed = readShort(7);
|
||||
long distance = readLong(9);
|
||||
if(port==PORT_1){
|
||||
steppers[0] = MeStepper(PORT_1);
|
||||
steppers[0].moveTo(distance);
|
||||
steppers[0].setMaxSpeed(maxSpeed);
|
||||
steppers[0].setSpeed(maxSpeed);
|
||||
}else if(port==PORT_2){
|
||||
steppers[1] = MeStepper(PORT_2);
|
||||
steppers[1].moveTo(distance);
|
||||
steppers[1].setMaxSpeed(maxSpeed);
|
||||
steppers[1].setSpeed(maxSpeed);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case RGBLED:{
|
||||
int slot = readBuffer(7);
|
||||
int idx = readBuffer(8);
|
||||
int r = readBuffer(9);
|
||||
int g = readBuffer(10);
|
||||
int b = readBuffer(11);
|
||||
if((led.getPort() != port) || led.getSlot() != slot)
|
||||
{
|
||||
led.reset(port,slot);
|
||||
}
|
||||
if(idx>0){
|
||||
led.setColorAt(idx-1,r,g,b);
|
||||
}else{
|
||||
led.setColor(r,g,b);
|
||||
}
|
||||
led.show();
|
||||
}
|
||||
break;
|
||||
case COMMON_COMMONCMD:{
|
||||
int slot = readBuffer(7);
|
||||
int subcmd = readBuffer(8);
|
||||
int cmd = readBuffer(9);
|
||||
if(SET_STARTER_MODE == subcmd)
|
||||
{
|
||||
Stop();
|
||||
if((cmd == 0x01) || (cmd == 0x00))
|
||||
{
|
||||
starter_mode = cmd;
|
||||
}
|
||||
else
|
||||
{
|
||||
starter_mode = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SERVO:{
|
||||
int slot = readBuffer(7);
|
||||
pin = slot==1?mePort[port].s1:mePort[port].s2;
|
||||
int v = readBuffer(8);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(!sv.attached())
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SEVSEG:{
|
||||
if(seg.getPort()!=port){
|
||||
seg.reset(port);
|
||||
}
|
||||
float v = readFloat(7);
|
||||
seg.display(v);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
generalDevice.dWrite1(v);
|
||||
}
|
||||
break;
|
||||
case SHUTTER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
}
|
||||
int v = readBuffer(7);
|
||||
if(v<2){
|
||||
generalDevice.dWrite1(v);
|
||||
}else{
|
||||
generalDevice.dWrite2(v-2);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
digitalWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case PWM:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int v = readBuffer(7);
|
||||
analogWrite(pin,v);
|
||||
}
|
||||
break;
|
||||
case TONE:{
|
||||
pinMode(pin,OUTPUT);
|
||||
int hz = readShort(7);
|
||||
int ms = readShort(9);
|
||||
if(ms>0){
|
||||
buzzer.tone(pin, hz, ms);
|
||||
}else{
|
||||
buzzer.noTone(pin);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case SERVO_PIN:{
|
||||
int v = readBuffer(7);
|
||||
Servo sv = servos[searchServoPin(pin)];
|
||||
if(v >= 0 && v <= 180)
|
||||
{
|
||||
if(!sv.attached())
|
||||
{
|
||||
sv.attach(pin);
|
||||
}
|
||||
sv.write(v);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
lastTime = millis()/1000.0;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
int searchServoPin(int pin){
|
||||
for(int i=0;i<8;i++){
|
||||
if(servo_pins[i] == pin){
|
||||
return i;
|
||||
}
|
||||
if(servo_pins[i]==0){
|
||||
servo_pins[i] = pin;
|
||||
return i;
|
||||
}
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
void readSensor(int device){
|
||||
/**************************************************
|
||||
ff 55 len idx action device port slot data a
|
||||
0 1 2 3 4 5 6 7 8
|
||||
***************************************************/
|
||||
float value=0.0;
|
||||
int port,slot,pin;
|
||||
port = readBuffer(6);
|
||||
pin = port;
|
||||
switch(device){
|
||||
case ULTRASONIC_SENSOR:{
|
||||
if(us.getPort()!=port){
|
||||
us.reset(port);
|
||||
}
|
||||
value = us.distanceCm();
|
||||
writeHead();
|
||||
writeSerial(command_index);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case TEMPERATURE_SENSOR:{
|
||||
slot = readBuffer(7);
|
||||
if(ts.getPort()!=port||ts.getSlot()!=slot){
|
||||
ts.reset(port,slot);
|
||||
}
|
||||
value = ts.temperature();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIGHT_SENSOR:
|
||||
case SOUND_SENSOR:
|
||||
case POTENTIONMETER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.aRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case JOYSTICK:{
|
||||
slot = readBuffer(7);
|
||||
if(joystick.getPort() != port){
|
||||
joystick.reset(port);
|
||||
}
|
||||
value = joystick.read(slot);
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case PIRMOTION:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LINEFOLLOWER:{
|
||||
if(generalDevice.getPort()!=port){
|
||||
generalDevice.reset(port);
|
||||
pinMode(generalDevice.pin1(),INPUT);
|
||||
pinMode(generalDevice.pin2(),INPUT);
|
||||
}
|
||||
value = generalDevice.dRead1()*2+generalDevice.dRead2();
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case LIMITSWITCH:{
|
||||
slot = readBuffer(7);
|
||||
if(generalDevice.getPort()!=port||generalDevice.getSlot()!=slot){
|
||||
generalDevice.reset(port,slot);
|
||||
}
|
||||
if(slot==1){
|
||||
pinMode(generalDevice.pin1(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead1();
|
||||
}else{
|
||||
pinMode(generalDevice.pin2(),INPUT_PULLUP);
|
||||
value = !generalDevice.dRead2();
|
||||
}
|
||||
sendFloat(value);
|
||||
}
|
||||
break;
|
||||
case HUMITURE:{
|
||||
uint8_t index = readBuffer(7);
|
||||
if(humiture.getPort()!=port){
|
||||
humiture.reset(port);
|
||||
}
|
||||
uint8_t HumitureData;
|
||||
humiture.update();
|
||||
HumitureData = humiture.getValue(index);
|
||||
sendByte(HumitureData);
|
||||
}
|
||||
break;
|
||||
case FLAMESENSOR:{
|
||||
if(FlameSensor.getPort()!=port){
|
||||
FlameSensor.reset(port);
|
||||
FlameSensor.setpin(FlameSensor.pin2(),FlameSensor.pin1());
|
||||
}
|
||||
int16_t FlameData;
|
||||
FlameData = FlameSensor.readAnalog();
|
||||
sendShort(FlameData);
|
||||
}
|
||||
break;
|
||||
case GASSENSOR:{
|
||||
if(GasSensor.getPort()!=port){
|
||||
GasSensor.reset(port);
|
||||
GasSensor.setpin(GasSensor.pin2(),GasSensor.pin1());
|
||||
}
|
||||
int16_t GasData;
|
||||
GasData = GasSensor.readAnalog();
|
||||
sendShort(GasData);
|
||||
}
|
||||
break;
|
||||
case VERSION:{
|
||||
sendString(mVersion);
|
||||
}
|
||||
break;
|
||||
case DIGITAL:{
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(digitalRead(pin));
|
||||
}
|
||||
break;
|
||||
case ANALOG:{
|
||||
pin = analogs[pin];
|
||||
pinMode(pin,INPUT);
|
||||
sendFloat(analogRead(pin));
|
||||
}
|
||||
break;
|
||||
case PULSEIN:{
|
||||
int pw = readShort(7);
|
||||
pinMode(pin, INPUT);
|
||||
sendShort(pulseIn(pin,HIGH,pw));
|
||||
}
|
||||
break;
|
||||
case ULTRASONIC_ARDUINO:{
|
||||
int trig = readBuffer(6);
|
||||
int echo = readBuffer(7);
|
||||
pinMode(trig,OUTPUT);
|
||||
digitalWrite(trig,LOW);
|
||||
delayMicroseconds(2);
|
||||
digitalWrite(trig,HIGH);
|
||||
delayMicroseconds(10);
|
||||
digitalWrite(trig,LOW);
|
||||
pinMode(echo, INPUT);
|
||||
sendFloat(pulseIn(echo,HIGH,30000)/58.0);
|
||||
}
|
||||
break;
|
||||
case TIMER:{
|
||||
sendFloat((float)currentTime);
|
||||
}
|
||||
break;
|
||||
case TOUCH_SENSOR:
|
||||
{
|
||||
if(touchSensor.getPort() != port){
|
||||
touchSensor.reset(port);
|
||||
}
|
||||
sendByte(touchSensor.touched());
|
||||
}
|
||||
break;
|
||||
case BUTTON:
|
||||
{
|
||||
if(buttonSensor.getPort() != port){
|
||||
buttonSensor.reset(port);
|
||||
}
|
||||
sendByte(keyPressed == readBuffer(7));
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ultrCarProcess()
|
||||
{
|
||||
distance = us.distanceCm();
|
||||
randomSeed(analogRead(A4));
|
||||
if((distance > 10) && (distance < 40))
|
||||
{
|
||||
randnum=random(300);
|
||||
if((randnum > 190) && (!rightflag))
|
||||
{
|
||||
leftflag=true;
|
||||
TurnLeft();
|
||||
}
|
||||
else
|
||||
{
|
||||
rightflag=true;
|
||||
TurnRight();
|
||||
}
|
||||
}
|
||||
else if(distance < 10)
|
||||
{
|
||||
randnum=random(300);
|
||||
if(randnum > 190)
|
||||
{
|
||||
BackwardAndTurnLeft();
|
||||
}
|
||||
else
|
||||
{
|
||||
BackwardAndTurnRight();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
leftflag=false;
|
||||
rightflag=false;
|
||||
Forward();
|
||||
}
|
||||
}
|
||||
|
||||
void IrProcess()
|
||||
{
|
||||
infraredReceiverDecode.loop();
|
||||
irRead = infraredReceiverDecode.getCode();
|
||||
if((irRead != IR_BUTTON_TEST) && (starter_mode != 0))
|
||||
{
|
||||
return;
|
||||
}
|
||||
switch(irRead)
|
||||
{
|
||||
case IR_BUTTON_PLUS:
|
||||
controlflag = IR_CONTROLER;
|
||||
Forward();
|
||||
break;
|
||||
case IR_BUTTON_MINUS:
|
||||
controlflag = IR_CONTROLER;
|
||||
Backward();
|
||||
break;
|
||||
case IR_BUTTON_NEXT:
|
||||
controlflag = IR_CONTROLER;
|
||||
TurnRight();
|
||||
break;
|
||||
case IR_BUTTON_PREVIOUS:
|
||||
controlflag = IR_CONTROLER;
|
||||
TurnLeft();
|
||||
break;
|
||||
case IR_BUTTON_9:
|
||||
controlflag = IR_CONTROLER;
|
||||
ChangeSpeed(factor*9+minSpeed);
|
||||
break;
|
||||
case IR_BUTTON_8:
|
||||
controlflag = IR_CONTROLER;
|
||||
ChangeSpeed(factor*8+minSpeed);
|
||||
break;
|
||||
case IR_BUTTON_7:
|
||||
controlflag = IR_CONTROLER;
|
||||
ChangeSpeed(factor*7+minSpeed);
|
||||
break;
|
||||
case IR_BUTTON_6:
|
||||
controlflag = IR_CONTROLER;
|
||||
ChangeSpeed(factor*6+minSpeed);
|
||||
break;
|
||||
case IR_BUTTON_5:
|
||||
controlflag = IR_CONTROLER;
|
||||
ChangeSpeed(factor*5+minSpeed);
|
||||
break;
|
||||
case IR_BUTTON_4:
|
||||
controlflag = IR_CONTROLER;
|
||||
ChangeSpeed(factor*4+minSpeed);
|
||||
break;
|
||||
case IR_BUTTON_3:
|
||||
controlflag = IR_CONTROLER;
|
||||
ChangeSpeed(factor*3+minSpeed);
|
||||
break;
|
||||
case IR_BUTTON_2:
|
||||
controlflag = IR_CONTROLER;
|
||||
ChangeSpeed(factor*2+minSpeed);
|
||||
break;
|
||||
case IR_BUTTON_1:
|
||||
controlflag = IR_CONTROLER;
|
||||
ChangeSpeed(factor*1+minSpeed);
|
||||
break;
|
||||
case IR_BUTTON_TEST:
|
||||
Stop();
|
||||
while(infraredReceiverDecode.buttonState() != 0)
|
||||
{
|
||||
infraredReceiverDecode.loop();
|
||||
}
|
||||
starter_mode = starter_mode + 1;
|
||||
if(starter_mode == 2)
|
||||
{
|
||||
starter_mode = 0;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
if(controlflag == IR_CONTROLER)
|
||||
{
|
||||
Stop();
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void setup(){
|
||||
pinMode(13,OUTPUT);
|
||||
digitalWrite(13,HIGH);
|
||||
delay(300);
|
||||
digitalWrite(13,LOW);
|
||||
Serial.begin(115200);
|
||||
delay(500);
|
||||
buzzerOn();
|
||||
delay(100);
|
||||
buzzerOff();
|
||||
delay(500);
|
||||
randomSeed(analogRead(0));
|
||||
Stop();
|
||||
infraredReceiverDecode.begin();
|
||||
Serial.print("Version: ");
|
||||
Serial.println(mVersion);
|
||||
}
|
||||
void loop(){
|
||||
keyPressed = buttonSensor.pressed();
|
||||
currentTime = millis()/1000.0-lastTime;
|
||||
readSerial();
|
||||
steppers[0].runSpeedToPosition();
|
||||
steppers[1].runSpeedToPosition();
|
||||
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;
|
||||
}
|
||||
}
|
||||
IrProcess();
|
||||
if(starter_mode == 1)
|
||||
{
|
||||
ultrCarProcess();
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,67 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me4ButtonTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.1
|
||||
* @date 2015/09/02
|
||||
* @brief Description: this file is sample program for 4 Button module.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t Me4Button::pressed()
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* Rafael Lee 2015/09/02 1.0.1 Added some comments and macros.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include <MeOrion.h>
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* Me4Button module can only be connected to PORT_6, PORT_7, PORT_8 on base
|
||||
* shield and Orion board.
|
||||
*/
|
||||
Me4Button btn(PORT_8);
|
||||
// Me4Button module can only be connected to PORT_6,
|
||||
// PORT_7, PORT_8 on base shield and Orion board.
|
||||
uint8_t keyPressed = KEY_NULL;
|
||||
uint8_t keyPressedPrevious = KEY_NULL;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
keyPressedPrevious = keyPressed;
|
||||
keyPressed = btn.pressed();
|
||||
if (keyPressedPrevious != keyPressed)
|
||||
{
|
||||
if (keyPressed == KEY_1)
|
||||
{
|
||||
Serial.println("KEY1 pressed");
|
||||
}
|
||||
if (keyPressed == KEY_2)
|
||||
{
|
||||
Serial.println("KEY2 pressed");
|
||||
}
|
||||
if (keyPressed == KEY_3)
|
||||
{
|
||||
Serial.println("KEY3 pressed");
|
||||
}
|
||||
if (keyPressed == KEY_4)
|
||||
{
|
||||
Serial.println("KEY4 pressed");
|
||||
}
|
||||
if (keyPressed == KEY_NULL)
|
||||
{
|
||||
Serial.println("KEY NULL");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,37 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file NumberDisplay.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.1
|
||||
* @date 2015/09/10
|
||||
* @brief Description: this file is sample code for Seven-Segment Display device.
|
||||
* It displays number from 0 to 100.
|
||||
* Function List:
|
||||
* 1. void Me7SegmentDisplay::display(int16_t value)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* Rafael Lee 2015/09/10 1.0.1 Added some comments and macros.
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
Me7SegmentDisplay disp(PORT_6);
|
||||
|
||||
int i = 0;
|
||||
void setup()
|
||||
{
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(i > 100)
|
||||
{
|
||||
i = 0;
|
||||
}
|
||||
disp.display(i++);
|
||||
delay(100);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,67 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file NumberFlow.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.1
|
||||
* @date 2015/09/02
|
||||
* @brief Description: this file is sample code for Seven-Segment LED device.
|
||||
* It test the number flow display
|
||||
* Function List:
|
||||
* 1. void Me7SegmentDisplay::init(void)
|
||||
* 2. void Me7SegmentDisplay::set(uint8_t = BRIGHT_2, uint8_t = ADDR_AUTO, \
|
||||
uint8_t = STARTADDR)
|
||||
* 3. void Me7SegmentDisplay::display(uint8_t BitAddr, uint8_t DispData);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* Rafael Lee 2015/09/02 1.0.1 Added some comments and macros.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
Me7SegmentDisplay disp(PORT_6);
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
void setup()
|
||||
{
|
||||
disp.init();
|
||||
disp.set(BRIGHTNESS_2);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
int8_t NumTab[] = { 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 }; // 0~9,A,b,C,d,E,F
|
||||
uint8_t ListDisp[4];
|
||||
unsigned char i = 0;
|
||||
unsigned char count = 0;
|
||||
delay(150);
|
||||
while(1)
|
||||
{
|
||||
i = count;
|
||||
count++;
|
||||
if(count == sizeof(NumTab) )
|
||||
{
|
||||
count = 0;
|
||||
}
|
||||
for(unsigned char BitSelect = 0; BitSelect < 4; BitSelect++)
|
||||
{
|
||||
ListDisp[BitSelect] = NumTab[i];
|
||||
i++;
|
||||
if(i == sizeof(NumTab) )
|
||||
{
|
||||
i = 0;
|
||||
}
|
||||
}
|
||||
disp.display( (uint8_t)0, ListDisp[0]);
|
||||
disp.display( (uint8_t)1, ListDisp[1]);
|
||||
disp.display( (uint8_t)2, ListDisp[2]);
|
||||
disp.display( (uint8_t)3, ListDisp[3]);
|
||||
delay(300);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,78 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file TimeDisplay.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.1
|
||||
* @date 2015/09/11
|
||||
* @brief Description: this file is sample code for Seven-Segment LED device.
|
||||
* It acts as a timer.
|
||||
* Function List:
|
||||
* 1. void Me7SegmentDisplay::init(void)
|
||||
* 2. void Me7SegmentDisplay::set(uint8_t = BRIGHT_2, uint8_t = ADDR_AUTO, \
|
||||
uint8_t = STARTADDR)
|
||||
* 3. void Me7SegmentDisplay::display(uint8_t DispData[]);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* Rafael Lee 2015/09/11 1.0.1 Added some comments and macros.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
|
||||
uint8_t TimeDisp[] = { 0x00, 0x00, 0x00, 0x00 };
|
||||
unsigned char second;
|
||||
unsigned char minute = 0;
|
||||
unsigned char hour = 12;
|
||||
long lastTime = 0;
|
||||
|
||||
Me7SegmentDisplay disp(PORT_6);
|
||||
|
||||
void setup()
|
||||
{
|
||||
disp.set();
|
||||
disp.init();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(millis() - lastTime >= 1000)
|
||||
{
|
||||
TimingISR();
|
||||
|
||||
TimeUpdate();
|
||||
disp.display(TimeDisp);
|
||||
|
||||
lastTime = millis();
|
||||
}
|
||||
}
|
||||
|
||||
void TimingISR()
|
||||
{
|
||||
second++;
|
||||
if(second == 60)
|
||||
{
|
||||
minute++;
|
||||
if(minute == 60)
|
||||
{
|
||||
hour++;
|
||||
if(hour == 24)
|
||||
{
|
||||
hour = 0;
|
||||
}
|
||||
minute = 0;
|
||||
}
|
||||
second = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void TimeUpdate(void)
|
||||
{
|
||||
TimeDisp[0] = minute / 10;
|
||||
TimeDisp[1] = minute % 10;
|
||||
TimeDisp[2] = second / 10;
|
||||
TimeDisp[3] = second % 10;
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,65 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file SlaveBluetoothBySoftSerialTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/09
|
||||
* @brief Description: this file is sample code for Me bluetooth device.
|
||||
* The bluetooth inherited the MeSerial class from SoftwareSerial.
|
||||
* You also can use this sample code to reset the bluetooth. The
|
||||
* AT command for the Me bluetooth can see 0n page 7 of
|
||||
* doc\Me_Bluetooth\Datasheet\ELET114A_Datasheet_v1.5.5_CH.pdf
|
||||
* You can use the command "AT+URATE=<baudrate> <CR> <LF>" to re-set
|
||||
* the baud rate.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeBluetooth::begin()
|
||||
* 2. int16_t MeBluetooth::available()
|
||||
* 3. size_t MeSerial::write(uint8_t byte)
|
||||
* 4. int16_t MeSerial::read(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/09 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeBluetooth bluetooth(PORT_3);
|
||||
|
||||
unsigned char table[128] = {0};
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
bluetooth.begin(115200); //The factory default baud rate is 115200
|
||||
Serial.println("Bluetooth Start!");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
int readdata = 0,i = 0,count = 0;
|
||||
char outDat;
|
||||
if (bluetooth.available())
|
||||
{
|
||||
while((readdata = bluetooth.read()) != (int)-1)
|
||||
{
|
||||
table[count] = readdata;
|
||||
count++;
|
||||
delay(1);
|
||||
}
|
||||
for(i = 0;i<count;i++)
|
||||
{
|
||||
Serial.write(table[i]);
|
||||
}
|
||||
}
|
||||
if(Serial.available() )
|
||||
{
|
||||
outDat = Serial.read();
|
||||
bluetooth.write(outDat);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,32 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file BuzzerTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/07/24
|
||||
* @brief Description: this file is sample code for buzzer
|
||||
*
|
||||
* Function List:
|
||||
* 1. void buzzerOn()
|
||||
* 2. void buzzerOff()
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
void setup()
|
||||
{
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
buzzerOn();
|
||||
delay(1000);
|
||||
buzzerOff();
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,183 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MbotBuzzerTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/19
|
||||
* @brief Description: this file is sample code for buzzer
|
||||
*
|
||||
* Function List:
|
||||
* 1. void buzzerOn()
|
||||
* 2. void buzzerOff()
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
* Public Constants
|
||||
*************************************************/
|
||||
|
||||
#define NOTE_B0 31
|
||||
#define NOTE_C1 33
|
||||
#define NOTE_CS1 35
|
||||
#define NOTE_D1 37
|
||||
#define NOTE_DS1 39
|
||||
#define NOTE_E1 41
|
||||
#define NOTE_F1 44
|
||||
#define NOTE_FS1 46
|
||||
#define NOTE_G1 49
|
||||
#define NOTE_GS1 52
|
||||
#define NOTE_A1 55
|
||||
#define NOTE_AS1 58
|
||||
#define NOTE_B1 62
|
||||
#define NOTE_C2 65
|
||||
#define NOTE_CS2 69
|
||||
#define NOTE_D2 73
|
||||
#define NOTE_DS2 78
|
||||
#define NOTE_E2 82
|
||||
#define NOTE_F2 87
|
||||
#define NOTE_FS2 93
|
||||
#define NOTE_G2 98
|
||||
#define NOTE_GS2 104
|
||||
#define NOTE_A2 110
|
||||
#define NOTE_AS2 117
|
||||
#define NOTE_B2 123
|
||||
#define NOTE_C3 131
|
||||
#define NOTE_CS3 139
|
||||
#define NOTE_D3 147
|
||||
#define NOTE_DS3 156
|
||||
#define NOTE_E3 165
|
||||
#define NOTE_F3 175
|
||||
#define NOTE_FS3 185
|
||||
#define NOTE_G3 196
|
||||
#define NOTE_GS3 208
|
||||
#define NOTE_A3 220
|
||||
#define NOTE_AS3 233
|
||||
#define NOTE_B3 247
|
||||
#define NOTE_C4 262
|
||||
#define NOTE_CS4 277
|
||||
#define NOTE_D4 294
|
||||
#define NOTE_DS4 311
|
||||
#define NOTE_E4 330
|
||||
#define NOTE_F4 349
|
||||
#define NOTE_FS4 370
|
||||
#define NOTE_G4 392
|
||||
#define NOTE_GS4 415
|
||||
#define NOTE_A4 440
|
||||
#define NOTE_AS4 466
|
||||
#define NOTE_B4 494
|
||||
#define NOTE_C5 523
|
||||
#define NOTE_CS5 554
|
||||
#define NOTE_D5 587
|
||||
#define NOTE_DS5 622
|
||||
#define NOTE_E5 659
|
||||
#define NOTE_F5 698
|
||||
#define NOTE_FS5 740
|
||||
#define NOTE_G5 784
|
||||
#define NOTE_GS5 831
|
||||
#define NOTE_A5 880
|
||||
#define NOTE_AS5 932
|
||||
#define NOTE_B5 988
|
||||
#define NOTE_C6 1047
|
||||
#define NOTE_CS6 1109
|
||||
#define NOTE_D6 1175
|
||||
#define NOTE_DS6 1245
|
||||
#define NOTE_E6 1319
|
||||
#define NOTE_F6 1397
|
||||
#define NOTE_FS6 1480
|
||||
#define NOTE_G6 1568
|
||||
#define NOTE_GS6 1661
|
||||
#define NOTE_A6 1760
|
||||
#define NOTE_AS6 1865
|
||||
#define NOTE_B6 1976
|
||||
#define NOTE_C7 2093
|
||||
#define NOTE_CS7 2217
|
||||
#define NOTE_D7 2349
|
||||
#define NOTE_DS7 2489
|
||||
#define NOTE_E7 2637
|
||||
#define NOTE_F7 2794
|
||||
#define NOTE_FS7 2960
|
||||
#define NOTE_G7 3136
|
||||
#define NOTE_GS7 3322
|
||||
#define NOTE_A7 3520
|
||||
#define NOTE_AS7 3729
|
||||
#define NOTE_B7 3951
|
||||
#define NOTE_C8 4186
|
||||
#define NOTE_CS8 4435
|
||||
#define NOTE_D8 4699
|
||||
#define NOTE_DS8 4978
|
||||
|
||||
void setup() {
|
||||
}
|
||||
|
||||
void loop() {
|
||||
play();//Play the music.
|
||||
delay(300);//Pause for a while.
|
||||
}
|
||||
|
||||
// notes in the melody:
|
||||
int melody[] = {
|
||||
NOTE_G4,//5
|
||||
NOTE_G4,//5
|
||||
NOTE_A4,//6
|
||||
NOTE_G4,//5
|
||||
NOTE_C5,//1.
|
||||
NOTE_B4,//7
|
||||
0,
|
||||
NOTE_G4,//5
|
||||
NOTE_G4,//5
|
||||
NOTE_A4,//6
|
||||
NOTE_G4,//5
|
||||
NOTE_D5,//2.
|
||||
NOTE_C5,//1.
|
||||
0,
|
||||
NOTE_G4,//5
|
||||
NOTE_G4,//5
|
||||
NOTE_G5,//5.
|
||||
NOTE_E5,//3.
|
||||
NOTE_C5,//1.
|
||||
NOTE_B4,//7
|
||||
NOTE_A4,//6
|
||||
0,
|
||||
NOTE_F5,//4.
|
||||
NOTE_F5,//4.
|
||||
NOTE_E5,//3.
|
||||
NOTE_C5,//1.
|
||||
NOTE_D5,//2.
|
||||
NOTE_C5,//1.
|
||||
0,
|
||||
};
|
||||
|
||||
int noteDurations[] = {
|
||||
8,8,4,4,4,4,
|
||||
4,
|
||||
8,8,4,4,4,4,
|
||||
4,
|
||||
8,8,4,4,4,4,2,
|
||||
8,
|
||||
8,8,4,4,4,2,
|
||||
4,
|
||||
};
|
||||
|
||||
void play()
|
||||
{
|
||||
for (int thisNote = 0; thisNote < 29; thisNote++) {
|
||||
|
||||
// to calculate the note duration, take one second
|
||||
// divided by the note type.
|
||||
//e.g. quarter note = 1000 / 4, eighth note = 1000/8, etc.
|
||||
int noteDuration = 1000/noteDurations[thisNote];
|
||||
tone(8, melody[thisNote],noteDuration);
|
||||
|
||||
// to distinguish the notes, set a minimum time between them.
|
||||
// the note's duration + 30% seems to work well:
|
||||
int pauseBetweenNotes = noteDuration * 1.30;
|
||||
delay(pauseBetweenNotes);
|
||||
// stop the tone playing:
|
||||
noTone(8);
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,187 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MbotBuzzerTest2.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/19
|
||||
* @brief Description: this file is sample code for buzzer
|
||||
*
|
||||
* Function List:
|
||||
* 1. void buzzerOn()
|
||||
* 2. void buzzerOff()
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
* Public Constants
|
||||
*************************************************/
|
||||
#include <MeMCore.h>
|
||||
|
||||
#define NOTE_B0 31
|
||||
#define NOTE_C1 33
|
||||
#define NOTE_CS1 35
|
||||
#define NOTE_D1 37
|
||||
#define NOTE_DS1 39
|
||||
#define NOTE_E1 41
|
||||
#define NOTE_F1 44
|
||||
#define NOTE_FS1 46
|
||||
#define NOTE_G1 49
|
||||
#define NOTE_GS1 52
|
||||
#define NOTE_A1 55
|
||||
#define NOTE_AS1 58
|
||||
#define NOTE_B1 62
|
||||
#define NOTE_C2 65
|
||||
#define NOTE_CS2 69
|
||||
#define NOTE_D2 73
|
||||
#define NOTE_DS2 78
|
||||
#define NOTE_E2 82
|
||||
#define NOTE_F2 87
|
||||
#define NOTE_FS2 93
|
||||
#define NOTE_G2 98
|
||||
#define NOTE_GS2 104
|
||||
#define NOTE_A2 110
|
||||
#define NOTE_AS2 117
|
||||
#define NOTE_B2 123
|
||||
#define NOTE_C3 131
|
||||
#define NOTE_CS3 139
|
||||
#define NOTE_D3 147
|
||||
#define NOTE_DS3 156
|
||||
#define NOTE_E3 165
|
||||
#define NOTE_F3 175
|
||||
#define NOTE_FS3 185
|
||||
#define NOTE_G3 196
|
||||
#define NOTE_GS3 208
|
||||
#define NOTE_A3 220
|
||||
#define NOTE_AS3 233
|
||||
#define NOTE_B3 247
|
||||
#define NOTE_C4 262
|
||||
#define NOTE_CS4 277
|
||||
#define NOTE_D4 294
|
||||
#define NOTE_DS4 311
|
||||
#define NOTE_E4 330
|
||||
#define NOTE_F4 349
|
||||
#define NOTE_FS4 370
|
||||
#define NOTE_G4 392
|
||||
#define NOTE_GS4 415
|
||||
#define NOTE_A4 440
|
||||
#define NOTE_AS4 466
|
||||
#define NOTE_B4 494
|
||||
#define NOTE_C5 523
|
||||
#define NOTE_CS5 554
|
||||
#define NOTE_D5 587
|
||||
#define NOTE_DS5 622
|
||||
#define NOTE_E5 659
|
||||
#define NOTE_F5 698
|
||||
#define NOTE_FS5 740
|
||||
#define NOTE_G5 784
|
||||
#define NOTE_GS5 831
|
||||
#define NOTE_A5 880
|
||||
#define NOTE_AS5 932
|
||||
#define NOTE_B5 988
|
||||
#define NOTE_C6 1047
|
||||
#define NOTE_CS6 1109
|
||||
#define NOTE_D6 1175
|
||||
#define NOTE_DS6 1245
|
||||
#define NOTE_E6 1319
|
||||
#define NOTE_F6 1397
|
||||
#define NOTE_FS6 1480
|
||||
#define NOTE_G6 1568
|
||||
#define NOTE_GS6 1661
|
||||
#define NOTE_A6 1760
|
||||
#define NOTE_AS6 1865
|
||||
#define NOTE_B6 1976
|
||||
#define NOTE_C7 2093
|
||||
#define NOTE_CS7 2217
|
||||
#define NOTE_D7 2349
|
||||
#define NOTE_DS7 2489
|
||||
#define NOTE_E7 2637
|
||||
#define NOTE_F7 2794
|
||||
#define NOTE_FS7 2960
|
||||
#define NOTE_G7 3136
|
||||
#define NOTE_GS7 3322
|
||||
#define NOTE_A7 3520
|
||||
#define NOTE_AS7 3729
|
||||
#define NOTE_B7 3951
|
||||
#define NOTE_C8 4186
|
||||
#define NOTE_CS8 4435
|
||||
#define NOTE_D8 4699
|
||||
#define NOTE_DS8 4978
|
||||
|
||||
MeBuzzer buzzer;
|
||||
|
||||
void setup() {
|
||||
|
||||
}
|
||||
|
||||
void loop() {
|
||||
play();//Play the music.
|
||||
delay(300);//Pause for a while.
|
||||
}
|
||||
|
||||
// notes in the melody:
|
||||
int melody[] = {
|
||||
NOTE_G4,//5
|
||||
NOTE_G4,//5
|
||||
NOTE_A4,//6
|
||||
NOTE_G4,//5
|
||||
NOTE_C5,//1.
|
||||
NOTE_B4,//7
|
||||
0,
|
||||
NOTE_G4,//5
|
||||
NOTE_G4,//5
|
||||
NOTE_A4,//6
|
||||
NOTE_G4,//5
|
||||
NOTE_D5,//2.
|
||||
NOTE_C5,//1.
|
||||
0,
|
||||
NOTE_G4,//5
|
||||
NOTE_G4,//5
|
||||
NOTE_G5,//5.
|
||||
NOTE_E5,//3.
|
||||
NOTE_C5,//1.
|
||||
NOTE_B4,//7
|
||||
NOTE_A4,//6
|
||||
0,
|
||||
NOTE_F5,//4.
|
||||
NOTE_F5,//4.
|
||||
NOTE_E5,//3.
|
||||
NOTE_C5,//1.
|
||||
NOTE_D5,//2.
|
||||
NOTE_C5,//1.
|
||||
0,
|
||||
};
|
||||
|
||||
int noteDurations[] = {
|
||||
8,8,4,4,4,4,
|
||||
4,
|
||||
8,8,4,4,4,4,
|
||||
4,
|
||||
8,8,4,4,4,4,2,
|
||||
8,
|
||||
8,8,4,4,4,2,
|
||||
4,
|
||||
};
|
||||
|
||||
void play()
|
||||
{
|
||||
for (int thisNote = 0; thisNote < 29; thisNote++) {
|
||||
|
||||
// to calculate the note duration, take one second
|
||||
// divided by the note type.
|
||||
//e.g. quarter note = 1000 / 4, eighth note = 1000/8, etc.
|
||||
int noteDuration = 1000/noteDurations[thisNote];
|
||||
buzzer.tone(melody[thisNote],noteDuration);
|
||||
|
||||
// to distinguish the notes, set a minimum time between them.
|
||||
// the note's duration + 30% seems to work well:
|
||||
int pauseBetweenNotes = noteDuration * 1.30;
|
||||
delay(pauseBetweenNotes);
|
||||
// stop the tone playing:
|
||||
buzzer.noTone();
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,96 @@
|
|||
#include "MeAuriga.h"
|
||||
#include "Wire.h"
|
||||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* \class MeColorSensor
|
||||
* \brief Driver for MeColorSensor module.
|
||||
* @file MeColorSensor.h
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/01/17
|
||||
* @brief Header for MeColorSensor.cpp module.
|
||||
* \par Description
|
||||
* This file is a drive for MeColorSensor module, It supports MeColorSensor V1.0 device provided
|
||||
* by MakeBlock.
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* zzipeng 2017/04/12 1.0.0 complete the driver code.
|
||||
* </pre>
|
||||
* Attention please!
|
||||
* 8mm~24mm detection distance.
|
||||
* auriga board only support PORT 6 7 8 9 ,as for this module!!
|
||||
*/
|
||||
//本例程示例单个颜色传感器模块工作,获取颜色识别值。单个模块工作数据返回率每秒6次。
|
||||
|
||||
MeColorSensor colorsensor(PORT_6);
|
||||
|
||||
uint8_t colorresult;
|
||||
uint16_t redvalue=0,greenvalue=0,bluevalue=0,colorvalue=0;
|
||||
uint8_t grayscale = 0;
|
||||
long systime = 0,colorcode=0;
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
Serial.begin(115200);
|
||||
colorsensor.SensorInit();//
|
||||
systime = millis();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
if(millis()-systime>200)
|
||||
{
|
||||
systime = millis();
|
||||
colorresult = colorsensor.Returnresult();
|
||||
redvalue = colorsensor.ReturnRedData();
|
||||
greenvalue = colorsensor.ReturnGreenData();
|
||||
bluevalue = colorsensor.ReturnBlueData();
|
||||
colorvalue = colorsensor.ReturnColorData();
|
||||
colorcode = colorsensor.ReturnColorCode();//RGB24code
|
||||
grayscale = colorsensor.ReturnGrayscale();
|
||||
|
||||
Serial.print("R:");
|
||||
Serial.print(redvalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("G:");
|
||||
Serial.print(greenvalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("B:");
|
||||
Serial.print(bluevalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("C:");
|
||||
Serial.print(colorvalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("color:");
|
||||
|
||||
switch(colorresult)
|
||||
{
|
||||
case BLACK:
|
||||
Serial.print("BLACK");
|
||||
break;
|
||||
case BLUE:
|
||||
Serial.print("BLUE");
|
||||
break;
|
||||
case YELLOW:
|
||||
Serial.print("YELLOW");
|
||||
break;
|
||||
case GREEN:
|
||||
Serial.print("GREEN");
|
||||
break;
|
||||
case RED:
|
||||
Serial.print("RED");
|
||||
break;
|
||||
case WHITE:
|
||||
Serial.print("WHITE");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
Serial.print("\t");
|
||||
Serial.print("code:");
|
||||
Serial.print(colorcode,HEX);
|
||||
Serial.print("\t");
|
||||
Serial.print("grayscale:");
|
||||
Serial.println(grayscale);
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,94 @@
|
|||
#include "MeMCore.h"
|
||||
#include "Wire.h"
|
||||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* \class MeGyro
|
||||
* \brief Driver for MeColorSensor module.
|
||||
* @file MeColorSensor.h
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/01/17
|
||||
* @brief Header for MeColorSensor.cpp module.
|
||||
* \par Description
|
||||
* This file is a drive for MeColorSensor module, It supports MeColorSensor V1.0 device provided
|
||||
* by MakeBlock.
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* zzipeng 2017/04/12 1.0.0 complete the driver code.
|
||||
* </pre>
|
||||
* Attention please!
|
||||
* 8mm~24mm detection distance.
|
||||
* Mcore board only support PORT 1 2 3 4,as for this module!!
|
||||
*/
|
||||
//本例程示例单个颜色传感器模块工作,获取颜色识别值。单个模块工作数据返回率每秒6次。
|
||||
|
||||
MeColorSensor colorsensor(PORT_1);
|
||||
|
||||
uint8_t colorresult;
|
||||
uint16_t redvalue=0,greenvalue=0,bluevalue=0,colorvalue=0;
|
||||
uint8_t grayscale = 0;
|
||||
long systime = 0,colorcode=0;
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
Serial.begin(115200);
|
||||
colorsensor.SensorInit();
|
||||
systime = millis();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
while(1)
|
||||
{
|
||||
colorresult = colorsensor.Returnresult();
|
||||
redvalue = colorsensor.ReturnRedData();
|
||||
greenvalue = colorsensor.ReturnGreenData();
|
||||
bluevalue = colorsensor.ReturnBlueData();
|
||||
colorvalue = colorsensor.ReturnColorData();
|
||||
colorcode = colorsensor.ReturnColorCode();//RGB24code
|
||||
grayscale = colorsensor.ReturnGrayscale();
|
||||
|
||||
Serial.print("R:");
|
||||
Serial.print(redvalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("G:");
|
||||
Serial.print(greenvalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("B:");
|
||||
Serial.print(bluevalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("C:");
|
||||
Serial.print(colorvalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("color:");
|
||||
switch(colorresult)
|
||||
{
|
||||
case BLACK:
|
||||
Serial.print("BLACK");
|
||||
break;
|
||||
case BLUE:
|
||||
Serial.print("BLUE");
|
||||
break;
|
||||
case YELLOW:
|
||||
Serial.print("YELLOW");
|
||||
break;
|
||||
case GREEN:
|
||||
Serial.print("GREEN");
|
||||
break;
|
||||
case RED:
|
||||
Serial.print("RED");
|
||||
break;
|
||||
case WHITE:
|
||||
Serial.print("WHITE");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
Serial.print("\t");
|
||||
Serial.print("code:");
|
||||
Serial.print(colorcode,HEX);
|
||||
Serial.print("\t");
|
||||
Serial.print("grayscale:");
|
||||
Serial.println(grayscale);
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,69 @@
|
|||
#include "MeMegaPi.h"
|
||||
#include "Wire.h"
|
||||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* \class MeGyro
|
||||
* \brief Driver for MeColorSensor module.
|
||||
* @file MeColorSensor.h
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/01/17
|
||||
* @brief Header for MeColorSensor.cpp module.
|
||||
* \par Description
|
||||
* This file is a drive for MeColorSensor module, It supports MeColorSensor V1.0 device provided
|
||||
* by MakeBlock.
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* zzipeng 2017/04/12 1.0.0 complete the driver code.
|
||||
* </pre>
|
||||
* Attention please!
|
||||
* 8mm~24mm detection distance.
|
||||
* megapi board only support PORT 5 6 7 8,as for this module!!
|
||||
*/
|
||||
//本例程示例单个颜色传感器模块工作,获取颜色识别值。单个模块工作数据返回率每秒6次。
|
||||
|
||||
#define NUM 1
|
||||
MeColorSensor colorsensor0(PORT_6);
|
||||
uint8_t colorresult[NUM]={0};
|
||||
long systime = 0,colorcode=0;
|
||||
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
Serial.begin(115200);
|
||||
colorsensor0.SensorInit();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
colorresult[0] = colorsensor0.ColorIdentify();
|
||||
|
||||
for(uint8_t i = 0;i<NUM;i++)
|
||||
{
|
||||
switch(colorresult[i])
|
||||
{
|
||||
case BLACK:
|
||||
Serial.print("BLACK");
|
||||
break;
|
||||
case BLUE:
|
||||
Serial.print("BLUE");
|
||||
break;
|
||||
case YELLOW:
|
||||
Serial.print("YELLOW");
|
||||
break;
|
||||
case GREEN:
|
||||
Serial.print("GREEN");
|
||||
break;
|
||||
case RED:
|
||||
Serial.print("RED");
|
||||
break;
|
||||
case WHITE:
|
||||
Serial.print("WHITE");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
Serial.print("\t");
|
||||
}
|
||||
Serial.print("\r\n");
|
||||
}
|
||||
|
|
@ -0,0 +1,139 @@
|
|||
#include "MeMegaPiPro.h"
|
||||
#include "Wire.h"
|
||||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* \class MeColorsensor
|
||||
* \brief Driver for MeColorSensor module.
|
||||
* @file MeColorSensor.h
|
||||
* @author MakeBlock
|
||||
* @version V1.0.1
|
||||
* @date 2017/05/23
|
||||
* @brief Header for MeColorSensor.cpp module.
|
||||
* \par Description
|
||||
* This file is a drive for MeColorSensor module, It supports MeColorSensor V1.0 device provided
|
||||
* by MakeBlock.
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* zzipeng 2017/05/23 1.0.1 complete the driver code.
|
||||
* </pre>
|
||||
* megapipro board only support PORT 6 7 8 9 10 11 12,as for this module!!
|
||||
*/
|
||||
|
||||
MeColorSensor colorsensor1(PORT_6);
|
||||
MeColorSensor colorsensor2(PORT_7);
|
||||
|
||||
uint16_t r1=0,g1=0,b1=0,c1=0;
|
||||
uint8_t colorresult1 = 0;
|
||||
uint16_t r2=0,g2=0,b2=0,c2=0;
|
||||
uint8_t colorresult2 = 0;
|
||||
long colorcode1=0,colorcode2=0;
|
||||
|
||||
void setup()
|
||||
{
|
||||
// put your setup code here, to run once:
|
||||
Serial.begin(115200);
|
||||
colorsensor1.SensorInit();
|
||||
colorsensor2.SensorInit();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
// put your main code here, to run repeatedly:
|
||||
colorresult1 = colorsensor1.ColorIdentify();
|
||||
colorcode1 = colorsensor1.ReturnColorCode();
|
||||
|
||||
r1 = (uint8_t)(colorcode1>>16);
|
||||
g1 = (uint8_t)(colorcode1>>8);
|
||||
b1 = (uint8_t)(colorcode1);
|
||||
|
||||
Serial.print("R:");
|
||||
Serial.print(r1);
|
||||
Serial.print("\t");
|
||||
Serial.print("G:");
|
||||
Serial.print(g1);
|
||||
Serial.print("\t");
|
||||
Serial.print("B:");
|
||||
Serial.print(b1);
|
||||
Serial.print("\t");
|
||||
Serial.print("color:");
|
||||
|
||||
switch(colorresult1)
|
||||
{
|
||||
case BLACK:
|
||||
Serial.print("BLACK");
|
||||
break;
|
||||
case BLUE:
|
||||
Serial.print("BLUE");
|
||||
break;
|
||||
case YELLOW:
|
||||
Serial.print("YELLOW");
|
||||
break;
|
||||
case GREEN:
|
||||
Serial.print("GREEN");
|
||||
break;
|
||||
case RED:
|
||||
Serial.print("RED");
|
||||
break;
|
||||
case WHITE:
|
||||
Serial.print("WHITE");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
Serial.print("\t");
|
||||
Serial.print("code:");
|
||||
Serial.print(colorcode1,HEX);
|
||||
Serial.print("\t");
|
||||
|
||||
colorresult2 = colorsensor2.ColorIdentify();
|
||||
colorcode2 = colorsensor2.ReturnColorCode();
|
||||
r2 = (uint8_t)(colorcode2>>16);
|
||||
g2 = (uint8_t)(colorcode2>>8);
|
||||
b2 = (uint8_t)(colorcode2);
|
||||
|
||||
Serial.print("R:");
|
||||
Serial.print(r2);
|
||||
Serial.print("\t");
|
||||
Serial.print("G:");
|
||||
Serial.print(g2);
|
||||
Serial.print("\t");
|
||||
Serial.print("B:");
|
||||
Serial.print(b2);
|
||||
Serial.print("\t");
|
||||
Serial.print("color:");
|
||||
|
||||
switch(colorresult2)
|
||||
{
|
||||
case BLACK:
|
||||
Serial.print("BLACK");
|
||||
break;
|
||||
case BLUE:
|
||||
Serial.print("BLUE");
|
||||
break;
|
||||
case YELLOW:
|
||||
Serial.print("YELLOW");
|
||||
break;
|
||||
case ORANGE:
|
||||
Serial.print("ORANGE");
|
||||
break;
|
||||
case GREEN:
|
||||
Serial.print("GREEN");
|
||||
break;
|
||||
case RED:
|
||||
Serial.print("RED");
|
||||
break;
|
||||
case PINKE:
|
||||
Serial.print("PINKE");
|
||||
break;
|
||||
case WHITE:
|
||||
Serial.print("WHITE");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
Serial.print("\t");
|
||||
Serial.print("code:");
|
||||
Serial.println(colorcode2,HEX);
|
||||
}
|
||||
|
|
@ -0,0 +1,96 @@
|
|||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* \class MeGyro
|
||||
* \brief Driver for MeColorSensor module.
|
||||
* @file MeColorSensor.h
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/01/17
|
||||
* @brief Header for MeColorSensor.cpp module.
|
||||
* \par Description
|
||||
* This file is a drive for MeColorSensor module, It supports MeColorSensor V1.0 device provided
|
||||
* by MakeBlock.
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* zzipeng 2017/04/12 1.0.0 complete the driver code.
|
||||
* </pre>
|
||||
* Attention please!
|
||||
* 8mm~24mm detection distance.
|
||||
* orion board only support PORT 1 2 3 4,as for this module!!
|
||||
*/
|
||||
//本例程示例单个颜色传感器模块工作,获取颜色识别值。单个模块工作数据返回率每秒6次。
|
||||
|
||||
MeColorSensor colorsensor(PORT_4);
|
||||
|
||||
uint8_t colorresult;
|
||||
uint16_t redvalue=0,greenvalue=0,bluevalue=0,colorvalue=0,hue;
|
||||
uint8_t grayscale = 0;
|
||||
long systime = 0,colorcode=0;
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
Serial.begin(115200);
|
||||
colorsensor.SensorInit();//
|
||||
systime = millis();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
if(millis()-systime>100)
|
||||
{
|
||||
systime = millis();
|
||||
colorresult = colorsensor.Returnresult();
|
||||
redvalue = colorsensor.ReturnRedData();
|
||||
greenvalue = colorsensor.ReturnGreenData();
|
||||
bluevalue = colorsensor.ReturnBlueData();
|
||||
colorvalue = colorsensor.ReturnColorData();
|
||||
colorcode = colorsensor.ReturnColorCode();//RGB24code
|
||||
grayscale = colorsensor.ReturnGrayscale();
|
||||
|
||||
Serial.print("R:");
|
||||
Serial.print(redvalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("G:");
|
||||
Serial.print(greenvalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("B:");
|
||||
Serial.print(bluevalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("C:");
|
||||
Serial.print(colorvalue);
|
||||
Serial.print("\t");
|
||||
Serial.print("color:");
|
||||
switch(colorresult)
|
||||
{
|
||||
case BLACK:
|
||||
Serial.print("BLACK");
|
||||
break;
|
||||
case BLUE:
|
||||
Serial.print("BLUE");
|
||||
break;
|
||||
case YELLOW:
|
||||
Serial.print("YELLOW");
|
||||
break;
|
||||
case GREEN:
|
||||
Serial.print("GREEN");
|
||||
break;
|
||||
case RED:
|
||||
Serial.print("RED");
|
||||
break;
|
||||
case WHITE:
|
||||
Serial.print("WHITE");
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
Serial.print("\t");
|
||||
Serial.print("code:");
|
||||
Serial.print(colorcode,HEX);
|
||||
Serial.print("\t");
|
||||
Serial.print("grayscale:");
|
||||
Serial.println(grayscale);
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,146 @@
|
|||
//#include "MeOrion.h"
|
||||
//#include "MeUnoShield.h"
|
||||
#include "MeMCore.h"
|
||||
#include "Wire.h"
|
||||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* \class MeGyro
|
||||
* \brief Driver for MeColorSensor module.
|
||||
* @file MeColorSensor.h
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/01/17
|
||||
* @brief Header for MeColorSensor.cpp module.
|
||||
* \par Description
|
||||
* This file is a drive for MeColorSensor module, It supports MeColorSensor V1.0 device provided
|
||||
* by MakeBlock.
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* zzipeng 2017/04/12 1.0.0 complete the driver code.
|
||||
* </pre>
|
||||
* Attention please!
|
||||
* 8mm~24mm detection distance.
|
||||
* Unoshield board only support PORT 1 2 3 4,as for this module!!
|
||||
*/
|
||||
//本例程示例两个颜色传感器模块分时轮流工作,获取颜色识别值。数据返回率每个每秒3~4次。
|
||||
|
||||
MeColorSensor colorsensor1(PORT_3);
|
||||
MeColorSensor colorsensor2(PORT_4);
|
||||
|
||||
uint8_t colorresult1,colorresult2;
|
||||
uint16_t redvalue1=0,greenvalue1=0,bluevalue1=0,colorvalue1=0;
|
||||
uint16_t redvalue2=0,greenvalue2=0,bluevalue2=0,colorvalue2=0;
|
||||
long systime = 0,colorcode1=0,colorcode2=0;
|
||||
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
Serial.begin(115200);
|
||||
colorsensor1.SensorInit();//
|
||||
colorsensor2.SensorInit();//
|
||||
systime = millis();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
if(millis()-systime>200)
|
||||
{
|
||||
systime = millis();
|
||||
colorresult1 = colorsensor1.ColorIdentify();
|
||||
redvalue1 = colorsensor1.ReturnRedData();
|
||||
greenvalue1 = colorsensor1.ReturnGreenData();
|
||||
bluevalue1 = colorsensor1.ReturnBlueData();
|
||||
colorvalue1 = colorsensor1.ReturnColorData();
|
||||
colorcode1 = colorsensor1.ReturnColorCode();//RGB24code
|
||||
|
||||
colorresult2 = colorsensor2.ColorIdentify();
|
||||
redvalue2 = colorsensor2.ReturnRedData();
|
||||
greenvalue2 = colorsensor2.ReturnGreenData();
|
||||
bluevalue2 = colorsensor2.ReturnBlueData();
|
||||
colorvalue2 = colorsensor2.ReturnColorData();
|
||||
colorcode2 = colorsensor2.ReturnColorCode();//RGB24code
|
||||
|
||||
Serial.print("R1:");
|
||||
Serial.print(redvalue1);
|
||||
Serial.print("\t");
|
||||
Serial.print("G:");
|
||||
Serial.print(greenvalue1);
|
||||
Serial.print("\t");
|
||||
Serial.print("B:");
|
||||
Serial.print(bluevalue1);
|
||||
Serial.print("\t");
|
||||
Serial.print("C:");
|
||||
Serial.print(colorvalue1);
|
||||
Serial.print("\t");
|
||||
Serial.print("color:");
|
||||
switch(colorresult1)
|
||||
{
|
||||
case BLACK:
|
||||
Serial.print("BLACK");
|
||||
break;
|
||||
case BLUE:
|
||||
Serial.print("BLUE");
|
||||
break;
|
||||
case YELLOW:
|
||||
Serial.print("YELLOW");
|
||||
break;
|
||||
case GREEN:
|
||||
Serial.print("GREEN");
|
||||
break;
|
||||
case RED:
|
||||
Serial.print("RED");
|
||||
break;
|
||||
case WHITE:
|
||||
Serial.print("WHITE");
|
||||
break;
|
||||
default:
|
||||
Serial.print("i don't know");
|
||||
break;
|
||||
}
|
||||
Serial.print("\t");
|
||||
Serial.print("code:");
|
||||
Serial.print(colorcode1,HEX);
|
||||
|
||||
Serial.print("\t\t");
|
||||
Serial.print("R2:");
|
||||
Serial.print(redvalue2);
|
||||
Serial.print("\t");
|
||||
Serial.print("G:");
|
||||
Serial.print(greenvalue2);
|
||||
Serial.print("\t");
|
||||
Serial.print("B:");
|
||||
Serial.print(bluevalue2);
|
||||
Serial.print("\t");
|
||||
Serial.print("C:");
|
||||
Serial.print(colorvalue2);
|
||||
Serial.print("\t");
|
||||
Serial.print("color:");
|
||||
switch(colorresult2)
|
||||
{
|
||||
case BLACK:
|
||||
Serial.print("BLACK");
|
||||
break;
|
||||
case BLUE:
|
||||
Serial.print("BLUE");
|
||||
break;
|
||||
case YELLOW:
|
||||
Serial.print("YELLOW");
|
||||
break;
|
||||
case GREEN:
|
||||
Serial.print("GREEN");
|
||||
break;
|
||||
case RED:
|
||||
Serial.print("RED");
|
||||
break;
|
||||
case WHITE:
|
||||
Serial.print("WHITE");
|
||||
break;
|
||||
default:
|
||||
Serial.print("i don't know");
|
||||
break;
|
||||
}
|
||||
Serial.print("\t");
|
||||
Serial.print("code:");
|
||||
Serial.println(colorcode2,HEX);
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,46 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeCompass.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/09
|
||||
* @brief Description: this file is sample code for Me MeCompass device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeCompass::init(void)
|
||||
* 2. double MeCompass::getAngle(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/09 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
|
||||
MeCompass Compass(PORT_4);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
Serial.println("Initializing I2C devices...");
|
||||
Compass.begin();
|
||||
Serial.println("Testing device connections...");
|
||||
Serial.println(Compass.testConnection() ? "HMC5883L connection successful" : "HMC5883L connection failed");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
int16_t head_X, head_Y, head_Z;
|
||||
double angle_number = 0;
|
||||
|
||||
head_X = Compass.getHeadingX();
|
||||
head_Y = Compass.getHeadingY();
|
||||
head_Z = Compass.getHeadingZ();
|
||||
|
||||
angle_number = Compass.getAngle();
|
||||
Serial.println(angle_number, 1);
|
||||
delay(500);
|
||||
}
|
||||
|
|
@ -0,0 +1,58 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file DCMotorDriverTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/09
|
||||
* @brief Description: this file is sample code for Me DC motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeDCMotor::run(int16_t speed)
|
||||
* 2. void MeDCMotor::stop(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/09 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeDCMotor motor1(PORT_1);
|
||||
|
||||
MeDCMotor motor2(PORT_2);
|
||||
|
||||
MeDCMotor motor3(M1);
|
||||
|
||||
MeDCMotor motor4(M2);
|
||||
|
||||
uint8_t motorSpeed = 100;
|
||||
|
||||
void setup()
|
||||
{
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor1.run(motorSpeed); /* value: between -255 and 255. */
|
||||
motor2.run(motorSpeed); /* value: between -255 and 255. */
|
||||
motor3.run(motorSpeed);
|
||||
motor4.run(motorSpeed);
|
||||
delay(2000);
|
||||
motor1.stop();
|
||||
motor2.stop();
|
||||
motor3.stop();
|
||||
motor4.stop();
|
||||
delay(100);
|
||||
motor1.run(-motorSpeed);
|
||||
motor2.run(-motorSpeed);
|
||||
motor3.run(-motorSpeed);
|
||||
motor4.run(-motorSpeed);
|
||||
delay(2000);
|
||||
motor1.stop();
|
||||
motor2.stop();
|
||||
motor3.stop();
|
||||
motor4.stop();
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,51 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file EncoderMotorChangeI2CDevID.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/03/19
|
||||
* @brief Description: this file is sample code for Encoder Motor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeEncoderMotor::begin();
|
||||
* 2. boolean MeEncoderMotor::setDevid(float turns, float speed);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* forfish 2016/03/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
//If you do not know the address of the current motor encoder, you can use
|
||||
//example code -> I2CScan -> Me_I2CScanTest to get the I2C address.
|
||||
|
||||
MeEncoderNew motor2(0x09, SLOT2); // motor at slot2
|
||||
|
||||
//This sample code is only used to modify the coding of the motor I2C address
|
||||
//Steps for usage:
|
||||
//1. programmed this code into the Orion Board.(parameter of setDevid is the address need to be set)
|
||||
//2. Linked to the encoder motor driver board through I2C bus (RJ25 cable)
|
||||
//3. Orion board must have an external power supply, and the switch is on.
|
||||
//4. reset the Orion Board.
|
||||
//5. When Orion board print OK, Unplug the I2C bus
|
||||
//6. reset the Encoder driver board.
|
||||
void setup()
|
||||
{
|
||||
delay(10);
|
||||
motor2.begin();
|
||||
Serial.begin(9600);
|
||||
delay(10);
|
||||
motor2.setDevid(0x0a);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Serial.println("OK");
|
||||
delay(9000);
|
||||
}
|
||||
|
|
@ -0,0 +1,51 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file EncoderMotorTestIsTarPosReaches.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/03/23
|
||||
* @brief Description: this file is sample code for Encoder Motor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeEncoderMotor::begin();
|
||||
* 2. boolean MeEncoderMotor::moveTo(float angle, float speed);
|
||||
* 3. void MeEncoderNew::setCurrentPosition(long pulse_counter);
|
||||
* 4. long MeEncoderNew::getCurrentPosition();
|
||||
* 5. boolean MeEncoderNew::isTarPosReached(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* forfish 2016/03/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeEncoderNew motor2(0x09, SLOT2); // motor at slot2
|
||||
|
||||
void setup()
|
||||
{
|
||||
motor2.begin();
|
||||
Serial.begin(9600);
|
||||
motor2.setCurrentPosition(0);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor2.moveTo(2000, 200);
|
||||
while(motor2.isTarPosReached() == false)
|
||||
{
|
||||
Serial.print("pos: ");
|
||||
Serial.println(motor2.getCurrentPosition());
|
||||
}
|
||||
motor2.moveTo(0, 200);
|
||||
while(motor2.isTarPosReached() == false)
|
||||
{
|
||||
Serial.print("pos: ");
|
||||
Serial.println(motor2.getCurrentPosition());
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,44 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file EncoderMotorTestMoveTo.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/19
|
||||
* @brief Description: this file is sample code for Encoder Motor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeEncoderMotor::begin();
|
||||
* 2. boolean MeEncoderMotor::moveTo(float angle, float speed);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeEncoderNew motor1(0x09, SLOT1); // Motor at slot1
|
||||
MeEncoderNew motor2(0x09, SLOT2); // motor at slot2
|
||||
|
||||
void setup()
|
||||
{
|
||||
motor1.begin();
|
||||
motor2.begin();
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor2.moveTo(360, 200);
|
||||
motor1.moveTo(360, 200);
|
||||
delay(2000);
|
||||
motor2.moveTo(0, 100);
|
||||
motor1.moveTo(0, 100);
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,40 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file EncoderMotorTestRunSpeed.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/19
|
||||
* @brief Description: this file is sample code for Encoder Motor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeEncoderMotor::begin();
|
||||
* 2. boolean MeEncoderMotor::runSpeed(float speed);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeEncoderNew motor2(0x09, SLOT2); // motor at slot2
|
||||
|
||||
void setup()
|
||||
{
|
||||
motor2.begin();
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor2.runSpeed(-150);
|
||||
delay(3000);
|
||||
motor2.runSpeed(0);
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,37 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file EncoderMotorTestRunSpeedAndTime.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/19
|
||||
* @brief Description: this file is sample code for Encoder Motor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeEncoderMotor::begin();
|
||||
* 2. boolean MeEncoderMotor::runSpeedAndTime(float speed, float time);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeEncoderNew motor2(0x09, SLOT2); // motor at slot2
|
||||
|
||||
void setup()
|
||||
{
|
||||
motor2.begin();
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor2.runSpeedAndTime(200,5);
|
||||
motor2.runSpeedAndTime(-100,5);
|
||||
}
|
||||
|
|
@ -0,0 +1,37 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file EncoderMotorTestRunTurns.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/19
|
||||
* @brief Description: this file is sample code for Encoder Motor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeEncoderMotor::begin();
|
||||
* 2. boolean MeEncoderMotor::runTurns(float turns, float speed);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeEncoderNew motor2(0x09, SLOT2); // motor at slot2
|
||||
|
||||
void setup()
|
||||
{
|
||||
motor2.begin();
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor2.runTurns(5,100);
|
||||
delay(9000);
|
||||
}
|
||||
|
|
@ -0,0 +1,44 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file EncoderMotorTestMoveTo.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/19
|
||||
* @brief Description: this file is sample code for Encoder Motor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeEncoderMotor::begin();
|
||||
* 2. boolean MeEncoderMotor::moveTo(float angle, float speed);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeEncoderMotor motor1(0x09, SLOT1); // Motor at slot1
|
||||
MeEncoderMotor motor2(0x09, SLOT2); // motor at slot2
|
||||
|
||||
void setup()
|
||||
{
|
||||
motor1.begin();
|
||||
motor2.begin();
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor2.moveTo(360, 200);
|
||||
motor1.moveTo(360, 200);
|
||||
delay(2000);
|
||||
motor2.moveTo(0, 100);
|
||||
motor1.moveTo(0, 100);
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,40 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file EncoderMotorTestRunSpeed.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/19
|
||||
* @brief Description: this file is sample code for Encoder Motor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeEncoderMotor::begin();
|
||||
* 2. boolean MeEncoderMotor::runSpeed(float speed);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeEncoderMotor motor2(0x09, SLOT2); // motor at slot2
|
||||
|
||||
void setup()
|
||||
{
|
||||
motor2.begin();
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor2.runSpeed(-150);
|
||||
delay(3000);
|
||||
motor2.runSpeed(0);
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,37 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file EncoderMotorTestRunSpeedAndTime.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/19
|
||||
* @brief Description: this file is sample code for Encoder Motor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeEncoderMotor::begin();
|
||||
* 2. boolean MeEncoderMotor::runSpeedAndTime(float speed, float time);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeEncoderMotor motor2(0x09, SLOT2); // motor at slot2
|
||||
|
||||
void setup()
|
||||
{
|
||||
motor2.begin();
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor2.runSpeedAndTime(100,5);
|
||||
delay(10000);
|
||||
}
|
||||
|
|
@ -0,0 +1,37 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2015, MakeBlock
|
||||
* @file EncoderMotorTestRunTurns.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/19
|
||||
* @brief Description: this file is sample code for Encoder Motor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeEncoderMotor::begin();
|
||||
* 2. boolean MeEncoderMotor::runTurns(float turns, float speed);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeEncoderMotor motor2(0x09, SLOT2); // motor at slot2
|
||||
|
||||
void setup()
|
||||
{
|
||||
motor2.begin();
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor2.runTurns(3,100);
|
||||
delay(9000);
|
||||
}
|
||||
|
|
@ -0,0 +1,44 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeFlameSensorTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/09
|
||||
* @brief Description: this file is sample code for Me flame snesor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeFlameSensor::readDigital(void)
|
||||
* 2. MeFlameSensor::readAnalog(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/09 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeFlameSensor FlameSensor1(PORT_8);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
// put your main code here, to run repeatedly:
|
||||
Serial.print("Analog Value is: ");
|
||||
Serial.print(FlameSensor1.readAnalog());
|
||||
Serial.print("----Status: ");
|
||||
if(FlameSensor1.readDigital() == Fire)
|
||||
{
|
||||
Serial.println("Fire");
|
||||
}
|
||||
else if(FlameSensor1.readDigital() == NoFire)
|
||||
{
|
||||
Serial.println("NoFire");
|
||||
}
|
||||
delay(200);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,42 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeGasSensorTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/09
|
||||
* @brief Description: this file is sample code for Me gas snesor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeGasSensor::readDigital(void)
|
||||
* 2. MeGasSensor::readAnalog(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/09 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeGasSensor GasSensor1(PORT_8);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Serial.print("Analog Value is: ");
|
||||
Serial.print(GasSensor1.readAnalog());
|
||||
Serial.print("----Status: ");
|
||||
if(GasSensor1.readDigital() == Gas_Exceeded)
|
||||
{
|
||||
Serial.println("The concentration exceeds");
|
||||
}
|
||||
else if(GasSensor1.readDigital() == Gas_not_Exceeded)
|
||||
{
|
||||
Serial.println("The concentration of the gas in the range");
|
||||
}
|
||||
delay(200);
|
||||
}
|
||||
|
|
@ -0,0 +1,45 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file GyroRotation.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/09
|
||||
* @brief Description: this file is sample code for MeGyro device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeGyro::begin(void)
|
||||
* 2. void MeGyro::update(void)
|
||||
* 3. double MeGyro::angleX(void)
|
||||
* 4. double MeGyro::angleY(void)
|
||||
* 5. double MeGyro::angleZ(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/09 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
#include <Wire.h>
|
||||
|
||||
MeGyro gyro;
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
gyro.begin();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
gyro.update();
|
||||
Serial.read();
|
||||
Serial.print("X:");
|
||||
Serial.print(gyro.getAngleX() );
|
||||
Serial.print(" Y:");
|
||||
Serial.print(gyro.getAngleY() );
|
||||
Serial.print(" Z:");
|
||||
Serial.println(gyro.getAngleZ() );
|
||||
delay(10);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,38 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeHumitureSensorTest1.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/07
|
||||
* @brief Description: this file is sample code for humiture sensor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeHumiture::update(void)
|
||||
* 2. uint8_t MeHumiture::getHumidity(void)
|
||||
* 3. uint8_t MeHumiture::getTemperature(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/07 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeHumiture humiture(PORT_6);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
humiture.update();
|
||||
Serial.print("Humidity (%) =");
|
||||
Serial.print( humiture.getHumidity() );
|
||||
Serial.print(", Temperature (oC) =");
|
||||
Serial.println( humiture.getTemperature() );
|
||||
Serial.println("###########################");
|
||||
delay(1000);
|
||||
}
|
||||
|
|
@ -0,0 +1,51 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeHumitureSensorTest2.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/11/18
|
||||
* @brief Description: this file is sample code for humiture sensor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeHumiture::update(void)
|
||||
* 2. uint8_t MeHumiture::getHumidity(void)
|
||||
* 3. uint8_t MeHumiture::getTemperature(void)
|
||||
* 6. double MeHumiture::getFahrenheit(void)
|
||||
* 7. double MeHumiture::getKelvin(void)
|
||||
* 8. double MeHumiture::getdewPoint(void)
|
||||
* 9. double MeHumiture::getPointFast()
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/07 1.0.0 rebuild the old lib
|
||||
* forfish 2015/11/18 1.0.1 Add some functions.
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeHumiture humiture(PORT_6);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
humiture.update();
|
||||
Serial.print("Humidity (%) =");
|
||||
Serial.println( humiture.getHumidity() );
|
||||
Serial.print("Temperature (oC) =");
|
||||
Serial.println( humiture.getTemperature() );
|
||||
Serial.print("Fahrenheit (oF) =");
|
||||
Serial.println( humiture.getFahrenheit() );
|
||||
Serial.print("Kelvin (K) =");
|
||||
Serial.println( humiture.getKelvin() );
|
||||
Serial.print("dewPoint (oC) =");
|
||||
Serial.println( humiture.getdewPoint() );
|
||||
//Serial.print("dewPointFast=");
|
||||
//Serial.println( humiture.getPointFast() );
|
||||
Serial.println("###########################");
|
||||
delay(1000);
|
||||
}
|
||||
|
|
@ -0,0 +1,79 @@
|
|||
// --------------------------------------
|
||||
// i2c_scanner
|
||||
//
|
||||
// Version 1
|
||||
// This program (or code that looks like it)
|
||||
// can be found in many places.
|
||||
// For example on the Arduino.cc forum.
|
||||
// The original author is not known.
|
||||
// Version 2, Juni 2012, Using Arduino 1.0.1
|
||||
// Adapted to be as simple as possible by Arduino.cc user Krodal
|
||||
// Version 3, Feb 26 2013
|
||||
// V3 by louarnold
|
||||
// Version 4, March 3, 2013, Using Arduino 1.0.3
|
||||
// by Arduino.cc user Krodal.
|
||||
// Changes by louarnold removed.
|
||||
// Scanning addresses changed from 0...127 to 1...119,
|
||||
// according to the i2c scanner by Nick Gammon
|
||||
// http://www.gammon.com.au/forum/?id=10896
|
||||
// Version 5, March 28, 2013
|
||||
// As version 4, but address scans now to 127.
|
||||
// A sensor seems to use address 120.
|
||||
//
|
||||
//
|
||||
// This sketch tests the standard 7-bit addresses
|
||||
// Devices with higher bit address might not be seen properly.
|
||||
//
|
||||
#include <Wire.h>
|
||||
|
||||
void setup()
|
||||
{
|
||||
Wire.begin();
|
||||
Serial.begin(9600);
|
||||
Serial.println("nI2C Scanner");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
byte error, address;
|
||||
int nDevices;
|
||||
|
||||
Serial.println("Scanning...");
|
||||
|
||||
nDevices = 0;
|
||||
for(address = 1; address < 127; address++ )
|
||||
{
|
||||
// The i2c_scanner uses the return value of
|
||||
// the Write.endTransmisstion to see if
|
||||
// a device did acknowledge to the address.
|
||||
Wire.beginTransmission(address);
|
||||
error = Wire.endTransmission();
|
||||
|
||||
if (error == 0)
|
||||
{
|
||||
Serial.print("I2C device found at address 0x");
|
||||
if (address<16)
|
||||
Serial.print("0");
|
||||
Serial.print(address,HEX);
|
||||
Serial.println(" !");
|
||||
|
||||
nDevices++;
|
||||
}
|
||||
else if (error==4)
|
||||
{
|
||||
Serial.print("Unknow error at address 0x");
|
||||
if (address<16)
|
||||
Serial.print("0");
|
||||
Serial.println(address,HEX);
|
||||
}
|
||||
}
|
||||
if (nDevices == 0)
|
||||
{
|
||||
Serial.println("No I2C devices foundn");
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.println("donen");
|
||||
}
|
||||
delay(5000); // wait 5 seconds for next scan
|
||||
}
|
||||
|
|
@ -0,0 +1,76 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file InfraredReceiverTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/01
|
||||
* @brief Description: this file is sample code for Me Infrared Receiver device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeInfraredReceiver::begin(void)
|
||||
* 2. int16_t MeInfraredReceiver::read(void)
|
||||
* 3. int16_t MeInfraredReceiver::available(void)
|
||||
* 4. bool MeInfraredReceiver::buttonState(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/01 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeInfraredReceiver infraredReceiverDecode(PORT_6);
|
||||
|
||||
void setup()
|
||||
{
|
||||
infraredReceiverDecode.begin();
|
||||
Serial.begin(9600);
|
||||
Serial.println("InfraredReceiverDecode Start!");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
uint8_t ReceiverCode;
|
||||
uint8_t buttonState;
|
||||
static uint8_t PrebuttonState = 0;
|
||||
|
||||
buttonState = infraredReceiverDecode.buttonState();
|
||||
if(PrebuttonState != buttonState)
|
||||
{
|
||||
PrebuttonState = buttonState;
|
||||
Serial.print("buttonState 0x");
|
||||
Serial.println(buttonState);
|
||||
}
|
||||
if(infraredReceiverDecode.available())
|
||||
{
|
||||
ReceiverCode = infraredReceiverDecode.read();
|
||||
switch(ReceiverCode)
|
||||
{
|
||||
case IR_BUTTON_A: Serial.println("Press A."); break;
|
||||
case IR_BUTTON_B: Serial.println("Press B."); break;
|
||||
case IR_BUTTON_C: Serial.println("Press C."); break;
|
||||
case IR_BUTTON_D: Serial.println("Press D."); break;
|
||||
case IR_BUTTON_E: Serial.println("Press E."); break;
|
||||
case IR_BUTTON_F: Serial.println("Press F."); break;
|
||||
case IR_BUTTON_SETTING: Serial.println("Press Setting."); break;
|
||||
case IR_BUTTON_UP: Serial.println("Press Up."); break;
|
||||
case IR_BUTTON_DOWN: Serial.println("Press Down."); break;
|
||||
case IR_BUTTON_LEFT: Serial.println("Press Left."); break;
|
||||
case IR_BUTTON_RIGHT: Serial.println("Press Right."); break;
|
||||
case IR_BUTTON_0: Serial.println("Press 0."); break;
|
||||
case IR_BUTTON_1: Serial.println("Press 1."); break;
|
||||
case IR_BUTTON_2: Serial.println("Press 2."); break;
|
||||
case IR_BUTTON_3: Serial.println("Press 3."); break;
|
||||
case IR_BUTTON_4: Serial.println("Press 4."); break;
|
||||
case IR_BUTTON_5: Serial.println("Press 5."); break;
|
||||
case IR_BUTTON_6: Serial.println("Press 6."); break;
|
||||
case IR_BUTTON_7: Serial.println("Press 7."); break;
|
||||
case IR_BUTTON_8: Serial.println("Press 8."); break;
|
||||
case IR_BUTTON_9: Serial.println("Press 9."); break;
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,57 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeJoystickTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/01
|
||||
* @brief Description: this file is sample code for Me Joystick device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. int16_t MeJoystick::readX()
|
||||
* 2. int16_t MeJoystick::readY()
|
||||
* 3. void CalCenterValue(int16_t x_offset,int16_t y_offset);
|
||||
* 4. float MeJoystick::angle()
|
||||
* 5. float MeJoystick::OffCenter()
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/01 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeJoystick joystick(PORT_6);
|
||||
|
||||
int16_t x = 0; /* a variable for the Joystick's x value */
|
||||
int16_t y = 0; /* a variable for the Joystick's y value */
|
||||
float angle = 0; /* The relative angle of XY */
|
||||
float OffCenter = 0; /* offset with the center */
|
||||
|
||||
void setup()
|
||||
{
|
||||
/* initialize serial communications at 9600 bps */
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
/* read the both joystick axis values: */
|
||||
x = joystick.readX();
|
||||
y = joystick.readY();
|
||||
angle = joystick.angle();
|
||||
OffCenter = joystick.OffCenter();
|
||||
|
||||
/* print the results to the serial monitor: */
|
||||
Serial.print("Joystick X = ");
|
||||
Serial.print(x);
|
||||
Serial.print(" Joystick Y = ");
|
||||
Serial.print(y);
|
||||
Serial.print(" angle =");
|
||||
Serial.print(angle);
|
||||
Serial.print(" OffCenter= ");
|
||||
Serial.println(OffCenter);
|
||||
/* wait 10 milliseconds before the next loop */
|
||||
delay(10);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,43 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_LEDMatrixTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/01/19
|
||||
* @brief Description: this file is sample code for Me LED Matrix device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeLEDMatrix::setBrightness(uint8_t Bright);
|
||||
* 2. void MeLEDMatrix::setColorIndex(bool Color_Number);
|
||||
* 3. void MeLEDMatrix::drawStr(int16_t X_position, int8_t Y_position, const char *str);
|
||||
* 4. void MeLEDMatrix::showClock(uint8_t hour, uint8_t minute, bool point_flag)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/01/19 1.0.0 build the new
|
||||
* Mark Yan 2016/01/27 1.0.1 add digital printing
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeLEDMatrix ledMx(PORT_4);
|
||||
|
||||
void setup()
|
||||
{
|
||||
ledMx.setBrightness(6);
|
||||
ledMx.setColorIndex(1);
|
||||
}
|
||||
|
||||
char *s = "AB";
|
||||
|
||||
void loop()
|
||||
{
|
||||
ledMx.showClock(12,03,1);
|
||||
delay(2000);
|
||||
ledMx.drawStr(0,7,s);
|
||||
delay(2000);
|
||||
ledMx.showNum(1.23);
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,73 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeLightSensorTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.1
|
||||
* @date 2015/09/10
|
||||
* @brief Description: this file is sample program for Me Light Sensor module.
|
||||
*
|
||||
* Function List:
|
||||
* 1. int16_t MeLightSensor::read();
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* Rafael Lee 2015/09/10 1.0.1 Added some comments and macros.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
MeLightSensor lightSensor(PORT_6);
|
||||
int value = 0; /* a variable for the lightSensor's value */
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
/**
|
||||
* \par Function
|
||||
* setup
|
||||
* \par Description
|
||||
* Run once, initialize serial port.
|
||||
* \param[in]
|
||||
* None
|
||||
* \par Output
|
||||
* None
|
||||
* \return
|
||||
* None.
|
||||
* \par Others
|
||||
* None
|
||||
*/
|
||||
void setup()
|
||||
{
|
||||
// initialize serial communications at 9600 bps
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
/**
|
||||
* \par Function
|
||||
* loop
|
||||
* \par Description
|
||||
* Run continuously, print if light sensor's DAC value.
|
||||
* \param[in]
|
||||
* None
|
||||
* \par Output
|
||||
* None
|
||||
* \return
|
||||
* None.
|
||||
* \par Others
|
||||
* None
|
||||
*/
|
||||
void loop()
|
||||
{
|
||||
// read the lightSensor value:
|
||||
value = lightSensor.read();
|
||||
|
||||
// print the results to the serial monitor
|
||||
Serial.print("value = ");
|
||||
Serial.println(value);
|
||||
// wait 100 milliseconds before the next loop
|
||||
delay(100);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,81 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* \brief Test
|
||||
* @file MeLightSensorTestResetPort.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.1
|
||||
* @date 2015/09/05
|
||||
* @brief Test Me Light Sensor module with port reconfiguration.
|
||||
*
|
||||
* Function List:
|
||||
* 1. int16_t MeLightSensor::read();
|
||||
* 2. void MeLightSensor::reset(uint8_t port);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 rebuild the old lib
|
||||
* Rafael Lee 2015/09/05 1.0.1 First Version.
|
||||
* </pre>
|
||||
*
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
//Instantiate class MeLightSensor
|
||||
MeLightSensor lightSensor(PORT_6);
|
||||
//Me Light Sensor can only be connected to PORT_6, PORT_7, PORT_8 on Orion Board of Makeblock.
|
||||
// lightSensor's value
|
||||
int value = 0;
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
/**
|
||||
* \par Function
|
||||
* setup
|
||||
* \par Description
|
||||
* Run once, initialize serial port and reset port.
|
||||
* \param[in]
|
||||
* None
|
||||
* \par Output
|
||||
* None
|
||||
* \return
|
||||
* None.
|
||||
* \par Others
|
||||
* None
|
||||
*/
|
||||
void setup()
|
||||
{
|
||||
// Initialize serial communication using 9600 bps
|
||||
Serial.begin(9600);
|
||||
// Reset the port of instance lightSensor to PORT_8
|
||||
lightSensor.reset(PORT_8);
|
||||
// Reset lightSensor's port to PORT_8.
|
||||
}
|
||||
|
||||
/**
|
||||
* \par Function
|
||||
* loop
|
||||
* \par Description
|
||||
* Run continuously, print light sensor's DAC value.
|
||||
* \param[in]
|
||||
* None
|
||||
* \par Output
|
||||
* None
|
||||
* \return
|
||||
* None.
|
||||
* \par Others
|
||||
* None
|
||||
*/
|
||||
void loop()
|
||||
{
|
||||
// Read the lightSensor's value
|
||||
value = lightSensor.read();
|
||||
|
||||
// Print results to serial monitor
|
||||
Serial.print("value = ");
|
||||
Serial.println(value);
|
||||
// Wait 100 milliseconds before next loop
|
||||
delay(100);
|
||||
}
|
||||
|
|
@ -0,0 +1,76 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeLightSensorTestWithLEDon.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.1
|
||||
* @date 2015/09/10
|
||||
* @brief Description: this file is sample program for Me Light Sensor module.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeLightSensor::lightOn();
|
||||
* 2. int16_t MeLightSensor::read();
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* Rafael Lee 2015/09/10 1.0.1 Added some comments and macros.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
MeLightSensor lightSensor(PORT_6);
|
||||
int value = 0; // a variable for the lightSensor's value
|
||||
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
/**
|
||||
* \par Function
|
||||
* setup
|
||||
* \par Description
|
||||
* Run once, initialize serial port.
|
||||
* \param[in]
|
||||
* None
|
||||
* \par Output
|
||||
* None
|
||||
* \return
|
||||
* None.
|
||||
* \par Others
|
||||
* None
|
||||
*/
|
||||
void setup()
|
||||
{
|
||||
// initialize serial communications at 9600 bps
|
||||
Serial.begin(9600);
|
||||
lightSensor.lightOn();
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* \par Function
|
||||
* loop
|
||||
* \par Description
|
||||
* Run continuously, print light sensor's DAC value .
|
||||
* \param[in]
|
||||
* None
|
||||
* \par Output
|
||||
* None
|
||||
* \return
|
||||
* None.
|
||||
* \par Others
|
||||
* None
|
||||
*/
|
||||
void loop()
|
||||
{
|
||||
// read the lightSensor value:
|
||||
value = lightSensor.read();
|
||||
|
||||
// print the results to the serial monitor:
|
||||
Serial.print("value = ");
|
||||
Serial.println(value);
|
||||
// wait 100 milliseconds before the next loop
|
||||
delay(100);
|
||||
}
|
||||
|
|
@ -0,0 +1,57 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file LimitSwitchTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/10
|
||||
* @brief Description: this file is sample program for Limit Switch module.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void bool MeLimitSwitch::touched();
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* Rafael Lee 2015/09/10 1.0.1 Added some comments and macros.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
// Me_LimitSwitch module can only be connected to PORT_3, PORT_4, PORT_6, PORT_7,
|
||||
// PORT_8 of base shield or from PORT_3 to PORT_8 of baseboard.
|
||||
MeLimitSwitch limitSwitch(PORT_6);
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
Serial.println("Start.");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(limitSwitch.touched() ) // If the limit switch is touched, the return value is true.
|
||||
{
|
||||
Serial.println("State: DOWN.");
|
||||
delay(1);
|
||||
while(limitSwitch.touched() )
|
||||
{
|
||||
;// Repeat check the switch state, until released.
|
||||
}
|
||||
delay(2);
|
||||
}
|
||||
if(!limitSwitch.touched() )
|
||||
{
|
||||
Serial.println("State: UP.");
|
||||
delay(1);
|
||||
while(!limitSwitch.touched() )
|
||||
{
|
||||
;
|
||||
}
|
||||
delay(2);
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,50 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MicroSwitchTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.1
|
||||
* @date 2015/09/10
|
||||
* @brief Description: this file is sample program for Limit Switch module.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void bool MeLimitSwitch::touched();
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* Rafael Lee 2015/09/10 1.0.1 Added some comments and macros.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
/* Me_LimitSwitch module can only be connected to PORT_3, PORT_4, PORT_6,
|
||||
// PORT_7,PORT_8 of base shield or from PORT_3 to PORT_8 of baseboard. */
|
||||
MeLimitSwitch limitSwitch1(PORT_3, SLOT1); // connecte to Me RJ25 Adapter SLOT1
|
||||
|
||||
|
||||
MeLimitSwitch limitSwitch2(PORT_3, SLOT2); // connecte to Me RJ25 Adapter SLOT2
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
Serial.println("Start.");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(limitSwitch1.touched() ) // If the limit switch is touched, the return value is true.
|
||||
{
|
||||
delay(10);
|
||||
Serial.println("limitSwitch1 DOWN.");
|
||||
}
|
||||
if(limitSwitch2.touched() ) // If the limit switch is touched, the return value is true.
|
||||
{
|
||||
delay(10);
|
||||
Serial.println("limitSwitch2 DOWN.");
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,40 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file LineFollowerTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/09
|
||||
* @brief Description: this file is sample code for Me line follower module.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeLineFollower::readSensors(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/09/09 1.0.0 Rebuild the old lib.
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeLineFollower lineFinder(PORT_3); /* Line Finder module can only be connected to PORT_3, PORT_4, PORT_5, PORT_6 of base shield. */
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
int sensorState = lineFinder.readSensors();
|
||||
switch(sensorState)
|
||||
{
|
||||
case S1_IN_S2_IN: Serial.println("Sensor 1 and 2 are inside of black line"); break;
|
||||
case S1_IN_S2_OUT: Serial.println("Sensor 2 is outside of black line"); break;
|
||||
case S1_OUT_S2_IN: Serial.println("Sensor 1 is outside of black line"); break;
|
||||
case S1_OUT_S2_OUT: Serial.println("Sensor 1 and 2 are outside of black line"); break;
|
||||
default: break;
|
||||
}
|
||||
delay(200);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,58 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeMegaPiDCMotorTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/05/17
|
||||
* @brief Description: this file is sample code for MegaPi DC motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeMegaPiDCMotorTest::run(int16_t speed)
|
||||
* 2. void MeMegaPiDCMotorTest::stop(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/05/17 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeMegaPi.h"
|
||||
|
||||
MeMegaPiDCMotor motor1(PORT1A);
|
||||
|
||||
MeMegaPiDCMotor motor2(PORT1B);
|
||||
|
||||
MeMegaPiDCMotor motor3(PORT2A);
|
||||
|
||||
MeMegaPiDCMotor motor4(PORT2B);
|
||||
|
||||
uint8_t motorSpeed = 100;
|
||||
|
||||
void setup()
|
||||
{
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor1.run(motorSpeed); /* value: between -255 and 255. */
|
||||
motor2.run(motorSpeed); /* value: between -255 and 255. */
|
||||
motor3.run(motorSpeed);
|
||||
motor4.run(motorSpeed);
|
||||
delay(2000);
|
||||
motor1.stop();
|
||||
motor2.stop();
|
||||
motor3.stop();
|
||||
motor4.stop();
|
||||
delay(100);
|
||||
motor1.run(-motorSpeed);
|
||||
motor2.run(-motorSpeed);
|
||||
motor3.run(-motorSpeed);
|
||||
motor4.run(-motorSpeed);
|
||||
delay(2000);
|
||||
motor1.stop();
|
||||
motor2.stop();
|
||||
motor3.stop();
|
||||
motor4.stop();
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,81 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MegaPiOnBoardStepperTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/05/06
|
||||
* @brief Description: this file is sample code for Stepper Driver device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* 1. void MeStepper::moveTo(long absolute);
|
||||
* 2. void MeStepper::move(long relative);
|
||||
* 3. boolean MeStepper::run();
|
||||
* 4. void MeStepper::setMaxSpeed(float speed);
|
||||
* 5. void MeStepper::setAcceleration(float acceleration);
|
||||
* 6. void MeStepper::setMicroStep(int8_t value);
|
||||
* 7. void MeStepper::enableOutputs(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/05/06 1.0.0 build the new.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeMegaPi.h"
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeStepperOnBoard stepper(SLOT_1);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
// Change these to suit your stepper if you want
|
||||
stepper.setMaxSpeed(1000);
|
||||
stepper.setAcceleration(20000);
|
||||
stepper.setMicroStep(16);
|
||||
stepper.enableOutputs();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
switch(a)
|
||||
{
|
||||
case '0':
|
||||
stepper.moveTo(0);
|
||||
break;
|
||||
case '1':
|
||||
stepper.moveTo(200);
|
||||
break;
|
||||
case '2':
|
||||
stepper.move(50);
|
||||
break;
|
||||
case '3':
|
||||
stepper.move(100);
|
||||
break;
|
||||
case '4':
|
||||
stepper.move(200);
|
||||
break;
|
||||
case '5':
|
||||
stepper.move(400);
|
||||
break;
|
||||
case '6':
|
||||
stepper.move(600);
|
||||
break;
|
||||
case '7':
|
||||
stepper.move(4000);
|
||||
break;
|
||||
case '8':
|
||||
stepper.move(8000);
|
||||
break;
|
||||
case '9':
|
||||
stepper.move(3200);
|
||||
break;
|
||||
}
|
||||
}
|
||||
stepper.run();
|
||||
}
|
||||
|
|
@ -0,0 +1,84 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2017, MakeBlock
|
||||
* @file MeMegaPiProDCMotorTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/05/10
|
||||
* @brief Description: this file is sample code for MegaPi Pro DC motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeMegaPiProDCMotorTest::run(int16_t speed)
|
||||
* 2. void MeMegaPiProDCMotorTest::stop(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Lan weiting 2017/05/10 1.0.0 build the new
|
||||
* Zzipeng 2017/05/14 1.0.1 complete the code.s
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeMegaPiPro.h"
|
||||
|
||||
MeMegaPiDCMotor motor1(PORT1A);
|
||||
|
||||
MeMegaPiDCMotor motor2(PORT1B);
|
||||
|
||||
MeMegaPiDCMotor motor3(PORT2A);
|
||||
|
||||
MeMegaPiDCMotor motor4(PORT2B);
|
||||
|
||||
MeMegaPiDCMotor motor5(PORT3A);
|
||||
|
||||
MeMegaPiDCMotor motor6(PORT3B);
|
||||
|
||||
MeMegaPiDCMotor motor7(PORT4A);
|
||||
|
||||
MeMegaPiDCMotor motor8(PORT4B);
|
||||
|
||||
uint8_t motorSpeed = 250;
|
||||
|
||||
void setup()
|
||||
{
|
||||
TCCR1A = _BV(WGM10);//timer1 will be set to 490hz in setup function
|
||||
TCCR1B = _BV(CS11) | _BV(CS10) | _BV(WGM12);//970hz
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor1.run(motorSpeed); /* value: between -255 and 255. */
|
||||
motor2.run(motorSpeed); /* value: between -255 and 255. */
|
||||
motor3.run(motorSpeed);
|
||||
motor4.run(motorSpeed);
|
||||
motor5.run(motorSpeed); /* value: between -255 and 255. */
|
||||
motor6.run(motorSpeed); /* value: between -255 and 255. */
|
||||
motor7.run(motorSpeed);
|
||||
motor8.run(motorSpeed);
|
||||
delay(2000);
|
||||
motor1.stop();
|
||||
motor2.stop();
|
||||
motor3.stop();
|
||||
motor4.stop();
|
||||
motor5.stop();
|
||||
motor6.stop();
|
||||
motor7.stop();
|
||||
motor8.stop();
|
||||
delay(1000);
|
||||
motor1.run(-motorSpeed);
|
||||
motor2.run(-motorSpeed);
|
||||
motor3.run(-motorSpeed);
|
||||
motor4.run(-motorSpeed);
|
||||
motor5.run(-motorSpeed); /* value: between -255 and 255. */
|
||||
motor6.run(-motorSpeed); /* value: between -255 and 255. */
|
||||
motor7.run(-motorSpeed);
|
||||
motor8.run(-motorSpeed);
|
||||
delay(2000);
|
||||
motor1.stop();
|
||||
motor2.stop();
|
||||
motor3.stop();
|
||||
motor4.stop();
|
||||
motor5.stop();
|
||||
motor6.stop();
|
||||
motor7.stop();
|
||||
motor8.stop();
|
||||
delay(1000);
|
||||
}
|
||||
|
|
@ -0,0 +1,69 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeMegaPiDCMotorTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/05/17
|
||||
* @brief Description: this file is sample code for MegaPi DC motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeMegaPiDCMotorTest::run(int16_t speed)
|
||||
* 2. void MeMegaPiDCMotorTest::stop(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Zzipeng 2017/05/17 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeMegaPiPro.h"
|
||||
|
||||
// MeStepperOnBoard stepper1(SLOT_1);
|
||||
// MeStepperOnBoard stepper2(SLOT_2);
|
||||
MeStepperOnBoard stepper3(SLOT_3);
|
||||
MeStepperOnBoard stepper4(SLOT_4);
|
||||
|
||||
int i=0;
|
||||
void setup()
|
||||
{
|
||||
// Change these to suit your stepper if you want
|
||||
// stepper1.setMaxSpeed(3000);
|
||||
// stepper1.setAcceleration(20000);
|
||||
// stepper1.setMicroStep(4);
|
||||
// stepper1.enableOutputs();
|
||||
|
||||
// stepper2.setMaxSpeed(3000);
|
||||
// stepper2.setAcceleration(20000);
|
||||
// stepper2.setMicroStep(4);
|
||||
// stepper2.enableOutputs();
|
||||
|
||||
stepper3.setMaxSpeed(3000);
|
||||
stepper3.setAcceleration(20000);
|
||||
stepper3.setMicroStep(4);
|
||||
stepper3.enableOutputs();
|
||||
|
||||
stepper4.setMaxSpeed(3000);
|
||||
stepper4.setAcceleration(20000);
|
||||
stepper4.setMicroStep(4);
|
||||
stepper4.enableOutputs();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
while(1)
|
||||
{
|
||||
// stepper1.move(2000);
|
||||
// stepper2.move(2000);
|
||||
stepper3.move(2000);
|
||||
stepper4.move(2000);
|
||||
for(i=1000;i>0;i--)
|
||||
{
|
||||
// stepper1.run();
|
||||
// stepper2.run();
|
||||
stepper3.run();
|
||||
stepper4.run();
|
||||
delay(1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,44 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2017, MakeBlock
|
||||
* @file MeMegaPiProESCMotor.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/05/016
|
||||
* @brief Description: this file is sample code for MegaPiPro ESC motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeMegaPiProESCMotorTest::init(void);
|
||||
* 2. void MeMegaPiProESCMotorTest::run(int16_t speed);
|
||||
* 3. void MeMegaPiProESCMotorTest::stop(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* lan Weiting 2017/05/09 1.0.0 build the new
|
||||
* Zzipeng 2017/05/09 1.0.1 build the new
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeMegaPiPro.h"
|
||||
|
||||
MeMegaPiProESCMotor bldcmotor1(PORT1);
|
||||
MeMegaPiProESCMotor bldcmotor2(PORT2);
|
||||
MeMegaPiProESCMotor bldcmotor3(PORT3);
|
||||
MeMegaPiProESCMotor bldcmotor4(PORT4);
|
||||
uint8_t motorSpeed = 40;//0~100
|
||||
void setup()
|
||||
{
|
||||
// put your setup code here, to run once:
|
||||
bldcmotor1.init();
|
||||
bldcmotor2.init();
|
||||
bldcmotor3.init();
|
||||
bldcmotor4.init();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
// put your main code here, to run repeatedly:
|
||||
bldcmotor1.run(motorSpeed);
|
||||
bldcmotor2.run(motorSpeed);
|
||||
bldcmotor3.run(motorSpeed);
|
||||
bldcmotor4.run(motorSpeed);
|
||||
}
|
||||
|
|
@ -0,0 +1,140 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Megapipro_encoder_pid_pos.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/05/11
|
||||
* @brief Description: this file is sample code for Megapi Pro encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 7. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPulse(int16_t pulseValue);
|
||||
* 9. void MeEncoderOnBoard::setRatio(int16_t RatioValue);
|
||||
* 10. void MeEncoderOnBoard::moveTo(long position,float speed,int16_t extId,cb callback);
|
||||
* 11. void MeEncoderOnBoard::loop(void);
|
||||
* 12. long MeEncoderOnBoard::getCurPos(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/07/14 1.0.0 build the new
|
||||
* Zzipeng 2017/05/18 1.0.1 set all timer frequency at 970hz
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeMegaPiPro.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//set pwm 1khz
|
||||
TCCR1A = _BV(WGM10);//PIN12
|
||||
TCCR1B = _BV(CS11) | _BV(CS10) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);//PIN8
|
||||
TCCR2B = _BV(CS22);
|
||||
|
||||
TCCR3A = _BV(WGM30);//PIN9
|
||||
TCCR3B = _BV(CS31) | _BV(CS30) | _BV(WGM32);
|
||||
|
||||
TCCR4A = _BV(WGM40);//PIN5
|
||||
TCCR4B = _BV(CS41) | _BV(CS40) | _BV(WGM42);
|
||||
|
||||
Encoder_1.setPulse(7);
|
||||
Encoder_2.setPulse(7);
|
||||
Encoder_1.setRatio(26.9);
|
||||
Encoder_2.setRatio(26.9);
|
||||
|
||||
Encoder_1.setPosPid(1.8,0,0.5);
|
||||
Encoder_2.setPosPid(1.8,0,0.5);
|
||||
Encoder_1.setSpeedPid(0.18,0,0);
|
||||
Encoder_2.setSpeedPid(0.18,0,0);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
switch(a)
|
||||
{
|
||||
case '0':
|
||||
Encoder_1.moveTo(0,300);
|
||||
Encoder_2.moveTo(0,300);
|
||||
break;
|
||||
case '1':
|
||||
Encoder_1.moveTo(360,300);
|
||||
Encoder_2.moveTo(-360,300);
|
||||
break;
|
||||
case '2':
|
||||
Encoder_1.moveTo(1800,300);
|
||||
Encoder_2.moveTo(-1800,300);
|
||||
break;
|
||||
case '3':
|
||||
Encoder_1.moveTo(3600,50);
|
||||
Encoder_2.moveTo(-3600,300);
|
||||
break;
|
||||
case '4':
|
||||
Encoder_1.moveTo(-360,50);
|
||||
Encoder_2.moveTo(360);
|
||||
break;
|
||||
case '5':
|
||||
Encoder_1.moveTo(-1800,50);
|
||||
Encoder_2.moveTo(1800,50);
|
||||
break;
|
||||
case '6':
|
||||
Encoder_1.moveTo(-3600,50);
|
||||
Encoder_2.moveTo(3600,50);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
Encoder_1.loop();
|
||||
Encoder_2.loop();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.print(" ,CurPos 1:");
|
||||
Serial.print(Encoder_1.getCurPos());
|
||||
Serial.print(" ,CurPos 2:");
|
||||
Serial.println(Encoder_2.getCurPos());
|
||||
}
|
||||
|
|
@ -0,0 +1,143 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Megapipro_encoder_pid_speed.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/05/11
|
||||
* @brief Description: this file is sample code for Megapi Pro encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 7. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPulse(int16_t pulseValue);
|
||||
* 9. void MeEncoderOnBoard::setRatio(int16_t RatioValue);
|
||||
* 10. void MeEncoderOnBoard::runSpeed(float speed);
|
||||
* 11. void MeEncoderOnBoard::loop(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Lan weiting 2017/05/11 1.0.0 build the new
|
||||
* Zzipeng 2017/05/18 1.0.1 set all timer frequency at 970hz
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeMegaPiPro.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//set pwm 1khz
|
||||
TCCR1A = _BV(WGM10);//PIN12
|
||||
TCCR1B = _BV(CS11) | _BV(CS10) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);//PIN8
|
||||
TCCR2B = _BV(CS22);
|
||||
|
||||
TCCR3A = _BV(WGM30);//PIN9
|
||||
TCCR3B = _BV(CS31) | _BV(CS30) | _BV(WGM32);
|
||||
|
||||
TCCR4A = _BV(WGM40);//PIN5
|
||||
TCCR4B = _BV(CS41) | _BV(CS40) | _BV(WGM42);
|
||||
|
||||
Encoder_1.setPulse(7);
|
||||
Encoder_2.setPulse(7);
|
||||
Encoder_1.setRatio(26.9);
|
||||
Encoder_2.setRatio(26.9);
|
||||
Encoder_1.setPosPid(1.8,0,1.2);
|
||||
Encoder_2.setPosPid(1.8,0,1.2);
|
||||
Encoder_1.setSpeedPid(0.18,0,0);
|
||||
Encoder_2.setSpeedPid(0.18,0,0);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
switch(a)
|
||||
{
|
||||
case '0':
|
||||
Encoder_1.runSpeed(0);
|
||||
Encoder_2.runSpeed(0);
|
||||
break;
|
||||
case '1':
|
||||
Encoder_1.runSpeed(100);
|
||||
Encoder_2.runSpeed(-100);
|
||||
break;
|
||||
case '2':
|
||||
Encoder_1.runSpeed(200);
|
||||
Encoder_2.runSpeed(-200);
|
||||
break;
|
||||
case '3':
|
||||
Encoder_1.runSpeed(255);
|
||||
Encoder_2.runSpeed(-255);
|
||||
break;
|
||||
case '4':
|
||||
Encoder_1.runSpeed(-100);
|
||||
Encoder_2.runSpeed(100);
|
||||
break;
|
||||
case '5':
|
||||
Encoder_1.runSpeed(-200);
|
||||
Encoder_2.runSpeed(200);
|
||||
break;
|
||||
case '6':
|
||||
Encoder_1.runSpeed(-255);
|
||||
Encoder_2.runSpeed(255);
|
||||
break;
|
||||
case '7':
|
||||
Encoder_1.runSpeed(-400);
|
||||
Encoder_2.runSpeed(400);
|
||||
break;
|
||||
case '8':
|
||||
Encoder_1.runSpeed(-800);
|
||||
Encoder_2.runSpeed(800);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
Encoder_1.loop();
|
||||
Encoder_2.loop();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.println(Encoder_2.getCurrentSpeed());
|
||||
}
|
||||
|
|
@ -0,0 +1,122 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Megapipro_encoder_pwm.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/05/11
|
||||
* @brief Description: this file is sample code for Megapi Pro encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::loop(void);
|
||||
* 8. void MeEncoderOnBoard::setTarPWM(int16_t pwm_value);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Lan weiting 2017/05/11 1.0.0 build the new
|
||||
* Zzipeng 2017/05/18 1.0.1 set all timer frequency at 970hz
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeMegaPiPro.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//set pwm 1khz
|
||||
TCCR1A = _BV(WGM10);//PIN12
|
||||
TCCR1B = _BV(CS11) | _BV(CS10) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);//PIN8
|
||||
TCCR2B = _BV(CS22);
|
||||
|
||||
TCCR3A = _BV(WGM30);//PIN9
|
||||
TCCR3B = _BV(CS31) | _BV(CS30) | _BV(WGM32);
|
||||
|
||||
TCCR4A = _BV(WGM40);//PIN5
|
||||
TCCR4B = _BV(CS41) | _BV(CS40) | _BV(WGM42);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
switch(a)
|
||||
{
|
||||
case '0':
|
||||
Encoder_1.setTarPWM(0);
|
||||
Encoder_2.setTarPWM(0);
|
||||
break;
|
||||
case '1':
|
||||
Encoder_1.setTarPWM(100);
|
||||
Encoder_2.setTarPWM(-100);
|
||||
break;
|
||||
case '2':
|
||||
Encoder_1.setTarPWM(200);
|
||||
Encoder_2.setTarPWM(-200);
|
||||
break;
|
||||
case '3':
|
||||
Encoder_1.setTarPWM(255);
|
||||
Encoder_2.setTarPWM(-255);
|
||||
break;
|
||||
case '4':
|
||||
Encoder_1.setTarPWM(-100);
|
||||
Encoder_2.setTarPWM(100);
|
||||
break;
|
||||
case '5':
|
||||
Encoder_1.setTarPWM(-200);
|
||||
Encoder_2.setTarPWM(200);
|
||||
break;
|
||||
case '6':
|
||||
Encoder_1.setTarPWM(-255);
|
||||
Encoder_2.setTarPWM(255);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
Encoder_1.loop();
|
||||
Encoder_2.loop();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.println(Encoder_2.getCurrentSpeed());
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,58 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2017, MakeBlock
|
||||
* @file MeMegaPiProDCMotorTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/05/10
|
||||
* @brief Description: this file is sample code for MegaPi Pro DC motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeMegaPiProDCMotorTest::run(int16_t speed)
|
||||
* 2. void MeMegaPiProDCMotorTest::stop(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Lan weiting 2017/05/10 1.0.0 build the new
|
||||
* Zzipeng 2017/05/12 1.0.1 build the new
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeMegaPiPro.h"
|
||||
|
||||
MeDCMotor motor1(M9);
|
||||
|
||||
MeDCMotor motor2(M10);
|
||||
|
||||
MeDCMotor motor3(M11);
|
||||
|
||||
MeDCMotor motor4(M12);
|
||||
|
||||
uint8_t motorSpeed = 250;
|
||||
|
||||
void setup()
|
||||
{
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
motor1.run(motorSpeed); /* value: between -255 and 255. */
|
||||
motor2.run(motorSpeed); /* value: between -255 and 255. */
|
||||
motor3.run(motorSpeed);
|
||||
motor4.run(motorSpeed);
|
||||
delay(2000);
|
||||
motor1.stop();
|
||||
motor2.stop();
|
||||
motor3.stop();
|
||||
motor4.stop();
|
||||
delay(1000);
|
||||
motor1.run(-motorSpeed);
|
||||
motor2.run(-motorSpeed);
|
||||
motor3.run(-motorSpeed);
|
||||
motor4.run(-motorSpeed);
|
||||
delay(2000);
|
||||
motor1.stop();
|
||||
motor2.stop();
|
||||
motor3.stop();
|
||||
motor4.stop();
|
||||
delay(1000);
|
||||
}
|
||||
|
|
@ -0,0 +1,35 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeOnBoardTempTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/04/01
|
||||
* @brief Description: this file is sample code for On Board Temperature device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint16_t MeOnBoardTemp::readAnalog(void);
|
||||
* 2. float MeOnBoardTemp::readValue(void)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/04/01 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeAuriga.h"
|
||||
|
||||
MeOnBoardTemp OnBoardTemp(PORT_13);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Serial.print("Analog Value is: ");
|
||||
Serial.println(OnBoardTemp.readAnalog());
|
||||
Serial.print("Temp Value is: ");
|
||||
Serial.println(OnBoardTemp.readValue());
|
||||
delay(200);
|
||||
}
|
||||
|
|
@ -0,0 +1,96 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Auriga_encoder.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/07/14
|
||||
* @brief Description: this file is sample code for auriga encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 7. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPulse(int16_t pulseValue);
|
||||
* 9. void MeEncoderOnBoard::setRatio(int16_t RatioValue);
|
||||
* 10. void MeEncoderOnBoard::moveTo(long position,float speed,int16_t extId,cb callback);
|
||||
* 11. void MeEncoderOnBoard::loop(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/07/14 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeAuriga.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//Set PWM 8KHz
|
||||
TCCR1A = _BV(WGM10);
|
||||
TCCR1B = _BV(CS11) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);
|
||||
TCCR2B = _BV(CS21);
|
||||
|
||||
Encoder_1.setPulse(9);
|
||||
Encoder_2.setPulse(9);
|
||||
Encoder_1.setRatio(39.267);
|
||||
Encoder_2.setRatio(39.267);
|
||||
Encoder_1.setPosPid(1.8,0,1.2);
|
||||
Encoder_2.setPosPid(1.8,0,1.2);
|
||||
Encoder_1.setSpeedPid(0.18,0,0);
|
||||
Encoder_2.setSpeedPid(0.18,0,0);
|
||||
Encoder_1.moveTo(3600,200,NULL,callback_test);
|
||||
Encoder_2.moveTo(3600,200,NULL,callback_test);
|
||||
}
|
||||
|
||||
void callback_test(int16_t slot,int16_t extID)
|
||||
{
|
||||
Serial.print("Encoder_");
|
||||
Serial.print(slot);
|
||||
Serial.println(" reached the position!");
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Encoder_1.loop();
|
||||
Encoder_2.loop();
|
||||
}
|
||||
|
|
@ -0,0 +1,78 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Auriga_encoder_direct.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/07/14
|
||||
* @brief Description: this file is sample code for auriga encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::updateSpeed(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/07/14 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeAuriga.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//Set PWM 8KHz
|
||||
TCCR1A = _BV(WGM10);
|
||||
TCCR1B = _BV(CS11) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);
|
||||
TCCR2B = _BV(CS21);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Encoder_1.setMotorPwm(100);
|
||||
Encoder_2.setMotorPwm(100);
|
||||
Encoder_1.updateSpeed();
|
||||
Encoder_2.updateSpeed();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.println(Encoder_2.getCurrentSpeed());
|
||||
}
|
||||
|
|
@ -0,0 +1,132 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Auriga_encoder.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/07/14
|
||||
* @brief Description: this file is sample code for auriga encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 7. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPulse(int16_t pulseValue);
|
||||
* 9. void MeEncoderOnBoard::setRatio(int16_t RatioValue);
|
||||
* 10. void MeEncoderOnBoard::moveTo(long position,float speed,int16_t extId,cb callback);
|
||||
* 11. void MeEncoderOnBoard::loop(void);
|
||||
* 12. long MeEncoderOnBoard::getCurPos(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/07/14 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeAuriga.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//Set PWM 8KHz
|
||||
TCCR1A = _BV(WGM10);
|
||||
TCCR1B = _BV(CS11) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);
|
||||
TCCR2B = _BV(CS21);
|
||||
|
||||
Encoder_1.setPulse(9);
|
||||
Encoder_2.setPulse(9);
|
||||
Encoder_1.setRatio(39.267);
|
||||
Encoder_2.setRatio(39.267);
|
||||
Encoder_1.setPosPid(1.8,0,1.2);
|
||||
Encoder_2.setPosPid(1.8,0,1.2);
|
||||
Encoder_1.setSpeedPid(0.18,0,0);
|
||||
Encoder_2.setSpeedPid(0.18,0,0);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
switch(a)
|
||||
{
|
||||
case '0':
|
||||
Encoder_1.moveTo(0,50);
|
||||
Encoder_2.moveTo(0,50);
|
||||
break;
|
||||
case '1':
|
||||
Encoder_1.moveTo(360);
|
||||
Encoder_2.moveTo(-360);
|
||||
break;
|
||||
case '2':
|
||||
Encoder_1.moveTo(1800);
|
||||
Encoder_2.moveTo(-1800);
|
||||
break;
|
||||
case '3':
|
||||
Encoder_1.moveTo(3600);
|
||||
Encoder_2.moveTo(-3600);
|
||||
break;
|
||||
case '4':
|
||||
Encoder_1.moveTo(-360);
|
||||
Encoder_2.moveTo(360);
|
||||
break;
|
||||
case '5':
|
||||
Encoder_1.moveTo(-1800);
|
||||
Encoder_2.moveTo(1800);
|
||||
break;
|
||||
case '6':
|
||||
Encoder_1.moveTo(-3600);
|
||||
Encoder_2.moveTo(3600);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
Encoder_1.loop();
|
||||
Encoder_2.loop();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.print(" ,CurPos 1:");
|
||||
Serial.print(Encoder_1.getCurPos());
|
||||
Serial.print(" ,CurPos 2:");
|
||||
Serial.println(Encoder_2.getCurPos());
|
||||
}
|
||||
|
|
@ -0,0 +1,128 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Auriga_encoder.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/07/14
|
||||
* @brief Description: this file is sample code for auriga encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 7. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPulse(int16_t pulseValue);
|
||||
* 9. void MeEncoderOnBoard::setRatio(int16_t RatioValue);
|
||||
* 10. void MeEncoderOnBoard::runSpeed(float speed);
|
||||
* 11. void MeEncoderOnBoard::loop(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/07/14 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeAuriga.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//Set PWM 8KHz
|
||||
TCCR1A = _BV(WGM10);
|
||||
TCCR1B = _BV(CS11) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);
|
||||
TCCR2B = _BV(CS21);
|
||||
|
||||
Encoder_1.setPulse(9);
|
||||
Encoder_2.setPulse(9);
|
||||
Encoder_1.setRatio(39.267);
|
||||
Encoder_2.setRatio(39.267);
|
||||
Encoder_1.setPosPid(0.18,0,0);
|
||||
Encoder_2.setPosPid(0.18,0,0);
|
||||
Encoder_1.setSpeedPid(0.18,0,0);
|
||||
Encoder_2.setSpeedPid(0.18,0,0);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
switch(a)
|
||||
{
|
||||
case '0':
|
||||
Encoder_1.runSpeed(0);
|
||||
Encoder_2.runSpeed(0);
|
||||
break;
|
||||
case '1':
|
||||
Encoder_1.runSpeed(100);
|
||||
Encoder_2.runSpeed(-100);
|
||||
break;
|
||||
case '2':
|
||||
Encoder_1.runSpeed(200);
|
||||
Encoder_2.runSpeed(-200);
|
||||
break;
|
||||
case '3':
|
||||
Encoder_1.runSpeed(255);
|
||||
Encoder_2.runSpeed(-255);
|
||||
break;
|
||||
case '4':
|
||||
Encoder_1.runSpeed(-100);
|
||||
Encoder_2.runSpeed(100);
|
||||
break;
|
||||
case '5':
|
||||
Encoder_1.runSpeed(-200);
|
||||
Encoder_2.runSpeed(200);
|
||||
break;
|
||||
case '6':
|
||||
Encoder_1.runSpeed(-255);
|
||||
Encoder_2.runSpeed(255);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
Encoder_1.loop();
|
||||
Encoder_2.loop();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.println(Encoder_2.getCurrentSpeed());
|
||||
}
|
||||
|
|
@ -0,0 +1,115 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Auriga_encoder_pwm.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/07/14
|
||||
* @brief Description: this file is sample code for auriga encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::loop(void);
|
||||
* 8. void MeEncoderOnBoard::setTarPWM(int16_t pwm_value);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/07/14 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeAuriga.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//Set PWM 8KHz
|
||||
TCCR1A = _BV(WGM10);
|
||||
TCCR1B = _BV(CS11) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);
|
||||
TCCR2B = _BV(CS21);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
switch(a)
|
||||
{
|
||||
case '0':
|
||||
Encoder_1.setTarPWM(0);
|
||||
Encoder_2.setTarPWM(0);
|
||||
break;
|
||||
case '1':
|
||||
Encoder_1.setTarPWM(100);
|
||||
Encoder_2.setTarPWM(-100);
|
||||
break;
|
||||
case '2':
|
||||
Encoder_1.setTarPWM(200);
|
||||
Encoder_2.setTarPWM(-200);
|
||||
break;
|
||||
case '3':
|
||||
Encoder_1.setTarPWM(255);
|
||||
Encoder_2.setTarPWM(-255);
|
||||
break;
|
||||
case '4':
|
||||
Encoder_1.setTarPWM(-100);
|
||||
Encoder_2.setTarPWM(100);
|
||||
break;
|
||||
case '5':
|
||||
Encoder_1.setTarPWM(-200);
|
||||
Encoder_2.setTarPWM(200);
|
||||
break;
|
||||
case '6':
|
||||
Encoder_1.setTarPWM(-255);
|
||||
Encoder_2.setTarPWM(255);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
Encoder_1.loop();
|
||||
Encoder_2.loop();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.println(Encoder_2.getCurrentSpeed());
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,78 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Auriga_encoder_direct.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/07/14
|
||||
* @brief Description: this file is sample code for auriga encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::updateSpeed(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/07/14 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeMegaPi.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//Set PWM 8KHz
|
||||
TCCR1A = _BV(WGM10);
|
||||
TCCR1B = _BV(CS11) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);
|
||||
TCCR2B = _BV(CS21);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Encoder_1.setMotorPwm(100);
|
||||
Encoder_2.setMotorPwm(100);
|
||||
Encoder_1.updateSpeed();
|
||||
Encoder_2.updateSpeed();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.println(Encoder_2.getCurrentSpeed());
|
||||
}
|
||||
|
|
@ -0,0 +1,132 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Megapi_encoder_pid_pos.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/07/14
|
||||
* @brief Description: this file is sample code for Megapi encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 7. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPulse(int16_t pulseValue);
|
||||
* 9. void MeEncoderOnBoard::setRatio(int16_t RatioValue);
|
||||
* 10. void MeEncoderOnBoard::moveTo(long position,float speed,int16_t extId,cb callback);
|
||||
* 11. void MeEncoderOnBoard::loop(void);
|
||||
* 12. long MeEncoderOnBoard::getCurPos(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/07/14 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeMegaPi.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT4);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//Set PWM 8KHz
|
||||
TCCR1A = _BV(WGM10);
|
||||
TCCR1B = _BV(CS11) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);
|
||||
TCCR2B = _BV(CS21);
|
||||
|
||||
Encoder_1.setPulse(7);
|
||||
Encoder_2.setPulse(7);
|
||||
Encoder_1.setRatio(26.9);
|
||||
Encoder_2.setRatio(26.9);
|
||||
Encoder_1.setPosPid(1.8,0,1.2);
|
||||
Encoder_2.setPosPid(1.8,0,1.2);
|
||||
Encoder_1.setSpeedPid(0.18,0,0);
|
||||
Encoder_2.setSpeedPid(0.18,0,0);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
switch(a)
|
||||
{
|
||||
case '0':
|
||||
Encoder_1.moveTo(0,300);
|
||||
Encoder_2.moveTo(0,300);
|
||||
break;
|
||||
case '1':
|
||||
Encoder_1.moveTo(360,300);
|
||||
Encoder_2.moveTo(-360,300);
|
||||
break;
|
||||
case '2':
|
||||
Encoder_1.moveTo(1800,300);
|
||||
Encoder_2.moveTo(-1800,300);
|
||||
break;
|
||||
case '3':
|
||||
Encoder_1.moveTo(3600,50);
|
||||
Encoder_2.moveTo(-3600,300);
|
||||
break;
|
||||
case '4':
|
||||
Encoder_1.moveTo(-360,50);
|
||||
Encoder_2.moveTo(360);
|
||||
break;
|
||||
case '5':
|
||||
Encoder_1.moveTo(-1800,50);
|
||||
Encoder_2.moveTo(1800,50);
|
||||
break;
|
||||
case '6':
|
||||
Encoder_1.moveTo(-3600,50);
|
||||
Encoder_2.moveTo(3600,50);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
Encoder_1.loop();
|
||||
Encoder_2.loop();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.print(" ,CurPos 1:");
|
||||
Serial.print(Encoder_1.getCurPos());
|
||||
Serial.print(" ,CurPos 2:");
|
||||
Serial.println(Encoder_2.getCurPos());
|
||||
}
|
||||
|
|
@ -0,0 +1,128 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Megapi_encoder_pid_speed.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/07/14
|
||||
* @brief Description: this file is sample code for Megapi encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::setSpeedPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 7. void MeEncoderOnBoard::setPosPid(float p,float i,float d);
|
||||
* 8. void MeEncoderOnBoard::setPulse(int16_t pulseValue);
|
||||
* 9. void MeEncoderOnBoard::setRatio(int16_t RatioValue);
|
||||
* 10. void MeEncoderOnBoard::runSpeed(float speed);
|
||||
* 11. void MeEncoderOnBoard::loop(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/07/14 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeMegaPi.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//Set PWM 8KHz
|
||||
TCCR1A = _BV(WGM10);
|
||||
TCCR1B = _BV(CS11) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);
|
||||
TCCR2B = _BV(CS21);
|
||||
|
||||
Encoder_1.setPulse(7);
|
||||
Encoder_2.setPulse(7);
|
||||
Encoder_1.setRatio(26.9);
|
||||
Encoder_2.setRatio(26.9);
|
||||
Encoder_1.setPosPid(1.8,0,1.2);
|
||||
Encoder_2.setPosPid(1.8,0,1.2);
|
||||
Encoder_1.setSpeedPid(0.18,0,0);
|
||||
Encoder_2.setSpeedPid(0.18,0,0);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
switch(a)
|
||||
{
|
||||
case '0':
|
||||
Encoder_1.runSpeed(0);
|
||||
Encoder_2.runSpeed(0);
|
||||
break;
|
||||
case '1':
|
||||
Encoder_1.runSpeed(100);
|
||||
Encoder_2.runSpeed(-100);
|
||||
break;
|
||||
case '2':
|
||||
Encoder_1.runSpeed(200);
|
||||
Encoder_2.runSpeed(-200);
|
||||
break;
|
||||
case '3':
|
||||
Encoder_1.runSpeed(255);
|
||||
Encoder_2.runSpeed(-255);
|
||||
break;
|
||||
case '4':
|
||||
Encoder_1.runSpeed(-100);
|
||||
Encoder_2.runSpeed(100);
|
||||
break;
|
||||
case '5':
|
||||
Encoder_1.runSpeed(-200);
|
||||
Encoder_2.runSpeed(200);
|
||||
break;
|
||||
case '6':
|
||||
Encoder_1.runSpeed(-255);
|
||||
Encoder_2.runSpeed(255);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
Encoder_1.loop();
|
||||
Encoder_2.loop();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.println(Encoder_2.getCurrentSpeed());
|
||||
}
|
||||
|
|
@ -0,0 +1,115 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Me_Megapi_encoder_pwm.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/07/14
|
||||
* @brief Description: this file is sample code for Megapi encoder motor device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t MeEncoderOnBoard::getPortB(void);
|
||||
* 2. uint8_t MeEncoderOnBoard::getIntNum(void);
|
||||
* 3. void MeEncoderOnBoard::pulsePosPlus(void);
|
||||
* 4. void MeEncoderOnBoard::pulsePosMinus(void);
|
||||
* 5. void MeEncoderOnBoard::setMotorPwm(int pwm);
|
||||
* 6. double MeEncoderOnBoard::getCurrentSpeed(void);
|
||||
* 7. void MeEncoderOnBoard::loop(void);
|
||||
* 8. void MeEncoderOnBoard::setTarPWM(int16_t pwm_value);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/07/14 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include <MeMegaPi.h>
|
||||
|
||||
MeEncoderOnBoard Encoder_1(SLOT1);
|
||||
MeEncoderOnBoard Encoder_2(SLOT2);
|
||||
|
||||
void isr_process_encoder1(void)
|
||||
{
|
||||
if(digitalRead(Encoder_1.getPortB()) == 0)
|
||||
{
|
||||
Encoder_1.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_1.pulsePosPlus();;
|
||||
}
|
||||
}
|
||||
|
||||
void isr_process_encoder2(void)
|
||||
{
|
||||
if(digitalRead(Encoder_2.getPortB()) == 0)
|
||||
{
|
||||
Encoder_2.pulsePosMinus();
|
||||
}
|
||||
else
|
||||
{
|
||||
Encoder_2.pulsePosPlus();
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
attachInterrupt(Encoder_1.getIntNum(), isr_process_encoder1, RISING);
|
||||
attachInterrupt(Encoder_2.getIntNum(), isr_process_encoder2, RISING);
|
||||
Serial.begin(115200);
|
||||
|
||||
//Set PWM 8KHz
|
||||
TCCR1A = _BV(WGM10);
|
||||
TCCR1B = _BV(CS11) | _BV(WGM12);
|
||||
|
||||
TCCR2A = _BV(WGM21) | _BV(WGM20);
|
||||
TCCR2B = _BV(CS21);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
switch(a)
|
||||
{
|
||||
case '0':
|
||||
Encoder_1.setTarPWM(0);
|
||||
Encoder_2.setTarPWM(0);
|
||||
break;
|
||||
case '1':
|
||||
Encoder_1.setTarPWM(100);
|
||||
Encoder_2.setTarPWM(-100);
|
||||
break;
|
||||
case '2':
|
||||
Encoder_1.setTarPWM(200);
|
||||
Encoder_2.setTarPWM(-200);
|
||||
break;
|
||||
case '3':
|
||||
Encoder_1.setTarPWM(255);
|
||||
Encoder_2.setTarPWM(-255);
|
||||
break;
|
||||
case '4':
|
||||
Encoder_1.setTarPWM(-100);
|
||||
Encoder_2.setTarPWM(100);
|
||||
break;
|
||||
case '5':
|
||||
Encoder_1.setTarPWM(-200);
|
||||
Encoder_2.setTarPWM(200);
|
||||
break;
|
||||
case '6':
|
||||
Encoder_1.setTarPWM(-255);
|
||||
Encoder_2.setTarPWM(255);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
Encoder_1.loop();
|
||||
Encoder_2.loop();
|
||||
Serial.print("Spped 1:");
|
||||
Serial.print(Encoder_1.getCurrentSpeed());
|
||||
Serial.print(" ,Spped 2:");
|
||||
Serial.println(Encoder_2.getCurrentSpeed());
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,41 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file PIRMotionSensorTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/10
|
||||
* @brief Description: this file is sample program for PIR Motion module.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MePIRMotionSensor::SetPirMotionMode(uint8_t ModePin)
|
||||
* 2. bool MePIRMotionSensor::isHumanDetected();
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* Rafael Lee 2015/09/10 1.0.1 Added some comments and macros.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
MePIRMotionSensor myPIRsensor(PORT_3);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
myPIRsensor.SetPirMotionMode(1); //Continuous Trigger mode
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(myPIRsensor.isHumanDetected() )
|
||||
{
|
||||
Serial.println("People Motion Detected");
|
||||
}
|
||||
delay(20);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,123 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MePS2Test.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.2
|
||||
* @date 2016/09/23
|
||||
* @brief Description: this file is sample code for MePS2.
|
||||
*
|
||||
* Function List:
|
||||
* 1. int16_t MePS2::MeAnalog(uint8_t button);
|
||||
* 2. boolean MePS2::ButtonPressed(uint8_t button);
|
||||
* 3. void MePS2::loop(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Scott wang 2016/09/18 1.0.0 Build the lib.
|
||||
* Scott wang 2016/09/19 1.0.1 Revise the rocker.
|
||||
* Scott 2016/09/23 1.0.2 Add BUTTON_L and BUTTON_R.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeMegaPi.h"
|
||||
#include "Arduino.h"
|
||||
#include "SoftwareSerial.h"
|
||||
MePS2 MePS2(PORT_15);
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
MePS2.begin(115200);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
MePS2.loop();
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_UP))
|
||||
{
|
||||
Serial.println("UP is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_DOWN))
|
||||
{
|
||||
Serial.println("DOWN is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_LEFT))
|
||||
{
|
||||
Serial.println("LEFT is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_RIGHT))
|
||||
{
|
||||
Serial.println("RIGHT is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_L1))
|
||||
{
|
||||
Serial.println("L1 is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_L2))
|
||||
{
|
||||
Serial.println("L2 is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_R1))
|
||||
{
|
||||
Serial.println("R1 is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_R2))
|
||||
{
|
||||
Serial.println("R2 is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_TRIANGLE))
|
||||
{
|
||||
Serial.println("TRIANGLE is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_XSHAPED))
|
||||
{
|
||||
Serial.println("XSHAPED is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_SQUARE))
|
||||
{
|
||||
Serial.println("SQUARE is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_ROUND))
|
||||
{
|
||||
Serial.println("ROUND is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_START))
|
||||
{
|
||||
Serial.println("START is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_SELECT))
|
||||
{
|
||||
Serial.println("SELECT is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_MODE))
|
||||
{
|
||||
Serial.println("MODE is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_BUTTON_L))
|
||||
{
|
||||
Serial.println("BUTTON_L is pressed!");
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_BUTTON_R))
|
||||
{
|
||||
Serial.println("BUTTON_R is pressed!");
|
||||
}
|
||||
|
||||
if(MePS2.MeAnalog(MeJOYSTICK_RX))
|
||||
{
|
||||
Serial.print("MePS2_RX value is: ");
|
||||
Serial.println(MePS2.MeAnalog(MeJOYSTICK_RX),DEC);
|
||||
}
|
||||
if( MePS2.MeAnalog(MeJOYSTICK_RY))
|
||||
{
|
||||
Serial.print("MePS2_RY value is: ");
|
||||
Serial.println(MePS2.MeAnalog(MeJOYSTICK_RY),DEC);
|
||||
}
|
||||
if(MePS2.MeAnalog(MeJOYSTICK_LX))
|
||||
{
|
||||
Serial.print("MePS2_LX value is: ");
|
||||
Serial.println(MePS2.MeAnalog(MeJOYSTICK_LX),DEC);
|
||||
}
|
||||
if(MePS2.MeAnalog(MeJOYSTICK_LY))
|
||||
{
|
||||
Serial.print("MePS2_LY value is: ");
|
||||
Serial.println(MePS2.MeAnalog(MeJOYSTICK_LY),DEC);
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,50 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MePS2Test2.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.2
|
||||
* @date 2016/09/23
|
||||
* @brief Description: this file is sample code for MePS2.
|
||||
*
|
||||
* Function List:
|
||||
* 1. int16_t MePS2::MeAnalog(uint8_t button);
|
||||
* 2. boolean MePS2::ButtonPressed(uint8_t button);
|
||||
* 3. void MePS2::loop(void);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Scott wang 2016/09/18 1.0.0 Build the lib.
|
||||
* Scott wang 2016/09/19 1.0.1 Revise the rocker.
|
||||
* Scott 2016/09/23 1.0.2 Add BUTTON_L and BUTTON_R.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeAuriga.h"
|
||||
#include "Arduino.h"
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MePS2 MePS2(PORT_16); //Auriga should set to PORT_16
|
||||
|
||||
MeRGBLed led;
|
||||
|
||||
void setup() {
|
||||
MePS2.begin(115200);
|
||||
led.setpin(44); //Auriga on board RGB LED is on pin 44.
|
||||
led.setColor(0,0,0,0); //When power on, clear the led.
|
||||
led.show();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
MePS2.loop();
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_L1))
|
||||
{
|
||||
led.setColor(0,60,0,0);
|
||||
led.show();
|
||||
}
|
||||
if (MePS2.ButtonPressed(MeJOYSTICK_L2))
|
||||
{
|
||||
led.setColor(0,0,0,0);
|
||||
led.show();
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,63 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeCompass.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/12/23
|
||||
* @brief Description: this file is sample code for Me MePm25Sensor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Zzipeng 2016/12/23 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
#include "MePm25Sensor.h"
|
||||
#include <SoftwareSerial.h>
|
||||
MePm25Sensor myMePm25Sensor(PORT3);
|
||||
uint16_t pm1_0=0,pm2_5=0,pm10=0,len=0,checksum=0;
|
||||
int cmdTimeOutValue = 0;
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
Serial.begin(9600);
|
||||
myMePm25Sensor.begin(9600);
|
||||
delay(50);
|
||||
Serial.println("setup...!");
|
||||
cmdTimeOutValue = millis();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
myMePm25Sensor.rxloop();//loop
|
||||
pm1_0 = myMePm25Sensor.readPm1_0Concentration();
|
||||
pm2_5 = myMePm25Sensor.readPm2_5Concentration();
|
||||
pm10 = myMePm25Sensor.readPm10Concentration();
|
||||
len = myMePm25Sensor.returnlen();
|
||||
checksum = myMePm25Sensor.returnchecksum();
|
||||
|
||||
if(millis() - cmdTimeOutValue > 500)
|
||||
{
|
||||
cmdTimeOutValue = millis();
|
||||
Serial.print("len=");
|
||||
Serial.print(len);
|
||||
Serial.print("\t");
|
||||
Serial.print("Pm1.0=");
|
||||
Serial.print(pm1_0);
|
||||
Serial.print("ug/m^3\t");
|
||||
Serial.print("Pm2.5=");
|
||||
Serial.print(pm2_5);
|
||||
Serial.print("ug/m^3\t");
|
||||
Serial.print("Pm10=");
|
||||
Serial.print(pm10);
|
||||
Serial.print("ug/m^3");
|
||||
Serial.print("\t");
|
||||
Serial.print("check=");
|
||||
Serial.print(checksum);
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
}
|
||||
|
|
@ -0,0 +1,63 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeCompass.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/12/23
|
||||
* @brief Description: this file is sample code for Me MePm25Sensor device.
|
||||
*
|
||||
* Function List:
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Zzipeng 2016/12/13 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*
|
||||
*/
|
||||
#include "MeAuriga.h"
|
||||
//#include "MePm25Sensor.h"
|
||||
#include <SoftwareSerial.h>
|
||||
MePm25Sensor myMePm25Sensor(PORT3);
|
||||
uint16_t pm1_0=0,pm2_5=0,pm10=0,len=0,checksum=0;
|
||||
int cmdTimeOutValue = 0;
|
||||
void setup() {
|
||||
// put your setup code here, to run once:
|
||||
Serial.begin(9600);
|
||||
myMePm25Sensor.begin(9600);
|
||||
delay(50);
|
||||
Serial.println("setup...!");
|
||||
cmdTimeOutValue = millis();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// put your main code here, to run repeatedly:
|
||||
myMePm25Sensor.rxloop();//loop
|
||||
pm1_0 = myMePm25Sensor.readPm1_0Concentration();
|
||||
pm2_5 = myMePm25Sensor.readPm2_5Concentration();
|
||||
pm10 = myMePm25Sensor.readPm10Concentration();
|
||||
len = myMePm25Sensor.returnlen();
|
||||
checksum = myMePm25Sensor.returnchecksum();
|
||||
|
||||
if(millis() - cmdTimeOutValue > 500)
|
||||
{
|
||||
cmdTimeOutValue = millis();
|
||||
Serial.print("len=");
|
||||
Serial.print(len);
|
||||
Serial.print("\t");
|
||||
Serial.print("Pm1.0=");
|
||||
Serial.print(pm1_0);
|
||||
Serial.print("ug/m^3\t");
|
||||
Serial.print("Pm2.5=");
|
||||
Serial.print(pm2_5);
|
||||
Serial.print("ug/m^3\t");
|
||||
Serial.print("Pm10=");
|
||||
Serial.print(pm10);
|
||||
Serial.print("ug/m^3");
|
||||
Serial.print("\t");
|
||||
Serial.print("check=");
|
||||
Serial.print(checksum);
|
||||
Serial.println();
|
||||
}
|
||||
|
||||
}
|
||||
|
|
@ -0,0 +1,37 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file PotentiometerTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.1
|
||||
* @date 2015/09/10
|
||||
* @brief Description: this file is sample program for Potentiometer module.
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint16_t MePotentiometer::read();
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* `<Author>` `<Time>` `<Version>` `<Descr>`
|
||||
* Mark Yan 2015/07/24 1.0.0 Rebuild the old lib.
|
||||
* Rafael Lee 2015/09/10 1.0.1 Added some comments and macros.
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
MePotentiometer myPotentiometer(PORT_6);
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
Serial.print("value=");
|
||||
Serial.println(myPotentiometer.read() );
|
||||
delay(100);
|
||||
}
|
||||
|
|
@ -0,0 +1,37 @@
|
|||
#include <Wire.h>
|
||||
#include <MeMegaPi.h>
|
||||
|
||||
MePressureSensor bmp;
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
if (!bmp.begin()) {
|
||||
Serial.println("Could not find a valid BMP180 or BMP085 sensor, check I2C wiring!");
|
||||
while (1) {}
|
||||
}
|
||||
}
|
||||
|
||||
void loop() {
|
||||
Serial.print("Temperature = ");
|
||||
Serial.print(bmp.readTemperature());
|
||||
Serial.println(" ℃");
|
||||
|
||||
Serial.print("Pressure = ");
|
||||
Serial.print(bmp.readPressure());
|
||||
Serial.println(" Pa");
|
||||
|
||||
Serial.print("Altitude = ");
|
||||
Serial.print(bmp.readAltitude());
|
||||
Serial.println(" meters");
|
||||
|
||||
Serial.print("Pressure at sealevel (calculated) = ");
|
||||
Serial.print(bmp.readSealevelPressure());
|
||||
Serial.println(" Pa");
|
||||
|
||||
Serial.print("Real altitude = ");
|
||||
Serial.print(bmp.readAltitude(101500));
|
||||
Serial.println(" meters");
|
||||
|
||||
Serial.println();
|
||||
delay(2000);
|
||||
}
|
||||
|
|
@ -0,0 +1,48 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file ColorLoopTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/02
|
||||
* @brief Description: this file is sample code for RGB LED, It used for random color change
|
||||
*
|
||||
* Function List:
|
||||
* 1. bool MeRGBLed::setColorAt(uint8_t index, uint8_t red, uint8_t green, uint8_t blue)
|
||||
* 2. void MeRGBLed::show()
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/02 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeRGBLed led(PORT_3);
|
||||
|
||||
float j, f, k;
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
color_loop();
|
||||
}
|
||||
|
||||
void color_loop()
|
||||
{
|
||||
for(uint8_t t = 1; t < 15; t++)
|
||||
{
|
||||
uint8_t red = 64 * (1 + sin(t / 2.0 + j / 4.0) );
|
||||
uint8_t green = 64 * (1 + sin(t / 1.0 + f / 9.0 + 2.1) );
|
||||
uint8_t blue = 64 * (1 + sin(t / 3.0 + k / 14.0 + 4.2) );
|
||||
led.setColorAt(t, red, green, blue);
|
||||
}
|
||||
led.show();
|
||||
j += random(1, 6) / 6.0;
|
||||
f += random(1, 6) / 6.0;
|
||||
k += random(1, 6) / 6.0;
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,74 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file ColorLoopTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/02
|
||||
* @brief Description: this file is sample code for RGB LED, It used for random color change
|
||||
*
|
||||
* Function List:
|
||||
* 1. bool MeRGBLed::setColorAt(uint8_t index, uint8_t red, uint8_t green, uint8_t blue)
|
||||
* 2. void MeRGBLed::show()
|
||||
* 3. void MeRGBLed::setpin(uint8_t port)
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/02 1.0.0 rebuild the old lib
|
||||
* Gregory Toto 2017/03/01 1.0.1 added Auriga support
|
||||
</pre>
|
||||
*/
|
||||
|
||||
#include <MeAuriga.h>
|
||||
|
||||
|
||||
#define ALLLEDS 0
|
||||
|
||||
#ifdef MeAuriga_H
|
||||
|
||||
// Auriga on-board light ring has 12 LEDs
|
||||
#define LEDNUM 12
|
||||
|
||||
// on-board LED ring, at PORT0 (onboard)
|
||||
MeRGBLed led( 0, LEDNUM );
|
||||
|
||||
#else
|
||||
|
||||
#define LEDNUM 14
|
||||
|
||||
// external device
|
||||
MeRGBLed led( PORT_3 );
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
float j, f, k;
|
||||
|
||||
void setup()
|
||||
{
|
||||
#ifdef MeAuriga_H
|
||||
// LED Ring controller is on Auriga D44/PWM
|
||||
led.setpin( 44 );
|
||||
#endif
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
color_loop();
|
||||
}
|
||||
|
||||
void color_loop()
|
||||
{
|
||||
for (uint8_t t = 0; t < LEDNUM; t++ )
|
||||
{
|
||||
uint8_t red = 64 * (1 + sin(t / 2.0 + j / 4.0) );
|
||||
uint8_t green = 64 * (1 + sin(t / 1.0 + f / 9.0 + 2.1) );
|
||||
uint8_t blue = 64 * (1 + sin(t / 3.0 + k / 14.0 + 4.2) );
|
||||
led.setColorAt( t, red, green, blue );
|
||||
}
|
||||
led.show();
|
||||
|
||||
j += random(1, 6) / 6.0;
|
||||
f += random(1, 6) / 6.0;
|
||||
k += random(1, 6) / 6.0;
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,60 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file IndicatorsTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/02
|
||||
* @brief Description: this file is sample code for RGB LED, It used for random length display
|
||||
*
|
||||
* Function List:
|
||||
* 1. bool MeRGBLed::setColorAt(uint8_t index, uint8_t red, uint8_t green, uint8_t blue)
|
||||
* 2. void MeRGBLed::show()
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/02 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeRGBLed led(PORT_3);
|
||||
|
||||
int lastNum = 0;
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
uint8_t count = random(1, 15);
|
||||
/* generates random numbers */
|
||||
indicators(count, 20, 30, 40);
|
||||
delay(150);
|
||||
}
|
||||
|
||||
void indicators(uint8_t count, uint8_t r, uint8_t g, uint8_t b)
|
||||
{
|
||||
uint8_t inSpeed = 10;
|
||||
if(lastNum <= count)
|
||||
{
|
||||
for(int16_t x = lastNum; x <= count; ++x)
|
||||
{
|
||||
led.setColorAt(x, r, g, b);
|
||||
led.show();
|
||||
delay(inSpeed);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
for(int16_t x = lastNum; x > count; --x)
|
||||
{
|
||||
led.setColorAt(x, 0, 0, 0);
|
||||
led.show();
|
||||
delay(inSpeed);
|
||||
}
|
||||
}
|
||||
lastNum = count;
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,86 @@
|
|||
|
||||
/**
|
||||
* \par Copyright (C), 2017, MakeBlock
|
||||
* @file MeAurigaOnBoardLEDRing.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/03/01
|
||||
* @brief Description: this file is sample code for the Auriga on-board 12 LED ring device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. bool MeRGBLed::setColor(uint8_t index, uint8_t red, uint8_t green, uint8_t blue)
|
||||
* 2. void MeRGBLed::show()
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Gregory Toto 2017/03/01 1.0.0 First version example code
|
||||
* </pre>
|
||||
*
|
||||
*/
|
||||
|
||||
#include <MeAuriga.h>
|
||||
|
||||
#define AURIGARINGLEDNUM 12
|
||||
#define RINGALLLEDS 0
|
||||
|
||||
|
||||
#ifdef MeAuriga_H
|
||||
// on-board LED ring, at PORT0 (onboard), with 12 LEDs
|
||||
MeRGBLed led_ring( 0, 12 );
|
||||
#endif
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin( 9600 );
|
||||
|
||||
#ifdef MeAuriga_H
|
||||
// 12 LED Ring controller is on Auriga D44/PWM
|
||||
led_ring.setpin( 44 );
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
int i;
|
||||
|
||||
// cycle the RING LEDS through RED/GREEN/BLUE at increasing brightnesses
|
||||
for ( i = 50; i <= 150; i+=50 )
|
||||
{
|
||||
|
||||
// led_ring.setColor( 0...12, 0...255, 0...255, 0...255 )
|
||||
// turn on all 12 leds, RED, incrementing brightness by 50 each
|
||||
// time through the loop
|
||||
Serial.print("RED ");
|
||||
led_ring.setColor( RINGALLLEDS, i, 0, 0 ) ;
|
||||
led_ring.show();
|
||||
delay( 500 );
|
||||
|
||||
Serial.print("GREEN ");
|
||||
led_ring.setColor( RINGALLLEDS, 0, i, 0 );
|
||||
led_ring.show();
|
||||
delay( 500 );
|
||||
|
||||
Serial.println("BLUE ");
|
||||
led_ring.setColor( RINGALLLEDS, 0, 0, i );
|
||||
led_ring.show();
|
||||
delay( 500 );
|
||||
}
|
||||
|
||||
// all LEDs off
|
||||
led_ring.setColor( RINGALLLEDS, 0, 0, 0 );
|
||||
led_ring.show();
|
||||
delay( 500 );
|
||||
|
||||
for ( i = 1; i <= AURIGARINGLEDNUM; i++ )
|
||||
{
|
||||
// Turn on LEDs one at a time with some interesting color
|
||||
Serial.print(i);
|
||||
led_ring.setColor( i, 40, 10, 40);
|
||||
led_ring.show();
|
||||
delay( 200 );
|
||||
}
|
||||
Serial.println("");
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,59 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file WhiteBreathLightTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/02
|
||||
* @brief Description: this file is sample code for RGB LED, It used for white breathing light
|
||||
*
|
||||
* Function List:
|
||||
* 1. bool MeRGBLed::setColor(uint8_t index, uint8_t red, uint8_t green, uint8_t blue)
|
||||
* 2. void MeRGBLed::show()
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/02 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
|
||||
MeRGBLed led1(PORT_3, SLOT1, 15); /* parameter description: port, slot, led number */
|
||||
MeRGBLed led2(PORT_3, SLOT2, 15);
|
||||
|
||||
int16_t bri = 0, st = 0;
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(bri >= 100)
|
||||
{
|
||||
st = 1;
|
||||
}
|
||||
if(bri <= 0)
|
||||
{
|
||||
st = 0;
|
||||
}
|
||||
|
||||
if(st)
|
||||
{
|
||||
bri--;
|
||||
}
|
||||
else
|
||||
{
|
||||
bri++;
|
||||
}
|
||||
for(int16_t t = 0; t < 15; t++)
|
||||
{
|
||||
led1.setColorAt(t, bri, bri, bri); /* parameter description: led number, red, green, blue, flash mode */
|
||||
led2.setColorAt(t, bri, bri, bri);
|
||||
}
|
||||
led1.show();
|
||||
led2.show();
|
||||
delay(20);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,44 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file RJ25AdapterTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/02
|
||||
* @brief Description: this file is sample code for RJ25 adapter module
|
||||
*
|
||||
* Function List:
|
||||
* 1. bool MeRGBLed::dWrite1(bool value)
|
||||
* 2. bool MeRGBLed::dRead2()
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/02 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
|
||||
MePort output(PORT_4);
|
||||
|
||||
|
||||
MePort input(PORT_3);
|
||||
|
||||
|
||||
int val;
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
output.dWrite1(HIGH); /* SLOT1 HIGH */
|
||||
delay(500);
|
||||
output.dWrite1(LOW); /* SLOT1 LOW */
|
||||
delay(500);
|
||||
|
||||
val = input.dRead1(); /* read SLOT1 level */
|
||||
Serial.print("val=");
|
||||
Serial.println(val);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,59 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeSerialReceiveTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/09
|
||||
* @brief Description: this file is sample code for hardware/software Serial.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeSerial::begin(long baudrate)
|
||||
* 2. size_t MeSerial::write(uint8_t byte)
|
||||
* 3. int16_t MeSerial::read(void)
|
||||
* 4. int16_t MeSerial::available(void)
|
||||
* 5. int16_t MeSerial::poll(void)
|
||||
* 6. void MeSerial::print(char *fmt,...)
|
||||
* 7. void MeSerial::println(char *fmt,...)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/09 1.0.0 rebuild the old lib
|
||||
* forfish 2015/11/19 1.0.0 add some descriptions
|
||||
* </pre>
|
||||
*/
|
||||
|
||||
#include "MeOrion.h"
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
unsigned char table[128] = {0};
|
||||
SoftwareSerial softuart(13,12);
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(57600);
|
||||
softuart.begin(57600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
int readdata = 0,i = 0,count = 0;
|
||||
if (softuart.available())
|
||||
{
|
||||
Serial.print(" readdata:");
|
||||
while((readdata = softuart.read()) != (int)-1)
|
||||
{
|
||||
table[count] = readdata;
|
||||
count++;
|
||||
delay(1);
|
||||
}
|
||||
for(i = 0;i<count;i++)
|
||||
{
|
||||
Serial.print(" 0x");
|
||||
Serial.print( table[i],HEX);
|
||||
softuart.write(table[i]);
|
||||
}
|
||||
Serial.println(" stop rev");
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,35 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeSerialTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/09
|
||||
* @brief Description: this file is sample code for hardware/software Serial.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeSerial::begin(long baudrate)
|
||||
* 2. void MeSerial::printf(char *fmt,...)
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/09 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
MeSerial mySerial(PORT_8);
|
||||
|
||||
void setup()
|
||||
{
|
||||
mySerial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
mySerial.println("just for test");
|
||||
mySerial.printf("%d,0x%x \r\n",123,0x123);
|
||||
delay(100);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,40 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Knob.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/02
|
||||
* @brief Description: This file is sample code for servo. Servo.h should be
|
||||
* included before makeblock header file
|
||||
*
|
||||
* Function List:
|
||||
* 1. uint8_t Servo::attach()
|
||||
* 2. uint8_t Servo::write()
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/02 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
MePort port(PORT_3);
|
||||
Servo myservo; // create servo object to control a servo
|
||||
int16_t servopin = port.pin2();//attaches the servo on PORT_3 SLOT2 to the servo object
|
||||
int16_t potpin = A1;// // analog pin used to connect the potentiometer
|
||||
int16_t val; // variable to read the value from the analog pin
|
||||
|
||||
void setup()
|
||||
{
|
||||
myservo.attach(servopin); // attaches the servo on servopin
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
val = analogRead(potpin); // reads the value of the potentiometer (value between 0 and 1023)
|
||||
val = map(val, 0, 1023, 0, 179); // scale it to use it with the servo (value between 0 and 180)
|
||||
myservo.write(val); // sets the servo position according to the scaled value
|
||||
delay(15); // waits for the servo to get there
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,45 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file Knob.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/02
|
||||
* @brief Description: this file is sample code for servo. Servo.h should be
|
||||
* included before makeblock header file
|
||||
* Function List:
|
||||
* 1. uint8_t Servo::attach()
|
||||
* 2. uint8_t Servo::write()
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/02 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
//Parts required:Me RJ25 Adapter and two servo
|
||||
//Me RJ25 Adapter SLOT1 connect servo1,SLOT2 connect servo2,
|
||||
//The Me RJ25 Adapter module can connect to the port with yellow tag (PORT_3 to PROT_8).
|
||||
|
||||
MePort port(PORT_3);
|
||||
Servo myservo1; // create servo object to control a servo
|
||||
Servo myservo2; // create servo object to control another servo
|
||||
int16_t servo1pin = port.pin1();//attaches the servo on PORT_3 SLOT1 to the servo object
|
||||
int16_t servo2pin = port.pin2();//attaches the servo on PORT_3 SLOT2 to the servo object
|
||||
|
||||
void setup()
|
||||
{
|
||||
myservo1.attach(servo1pin); // attaches the servo on servopin1
|
||||
myservo2.attach(servo2pin); // attaches the servo on servopin2
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
myservo1.write(0); // sets the servo position according to the scaled value
|
||||
myservo2.write(0);
|
||||
delay(2000); // waits for the servo to get there
|
||||
myservo1.write(180);
|
||||
myservo2.write(180);
|
||||
delay(2000);
|
||||
}
|
||||
|
|
@ -0,0 +1,54 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file MeShutterTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2015/09/01
|
||||
* @brief Description: this file is sample code for Me Shutter device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. void MeShutter::shotOn()
|
||||
* 2. void MeShutter::shotOff()
|
||||
* 3. void MeShutter::focusOn()
|
||||
* 4. void MeShutter::focusOff()
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2015/09/01 1.0.0 rebuild the old lib
|
||||
* </pre>
|
||||
*/
|
||||
#include "MeOrion.h"
|
||||
|
||||
// MeShutter module can only be connected to the PORT_3, PORT_4, PORT_6 on Orion board
|
||||
MeShutter myshutter(PORT3);
|
||||
|
||||
void setup()
|
||||
{
|
||||
/* initialize serial communications at 9600 bps */
|
||||
Serial.begin(9600);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
if(Serial.available())
|
||||
{
|
||||
char a = Serial.read();
|
||||
if(a == 's')
|
||||
{
|
||||
myshutter.focusOn();
|
||||
delay(1000);
|
||||
myshutter.shotOn();
|
||||
delay(200);
|
||||
myshutter.shotOff();
|
||||
myshutter.focusOff();
|
||||
}
|
||||
if(a == 'f')
|
||||
{
|
||||
myshutter.focusOn();
|
||||
delay(1500);
|
||||
myshutter.focusOff();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,59 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file SmartServoCallback.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2017/07/10
|
||||
* @brief Description: this file is sample code for Smart servo device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. boolean MeSmartServo::assignDevIdRequest(void);
|
||||
* 2. boolean MeSmartServo::moveTo(uint8_t dev_id,long angle_value,float speed,smartServoCb callback);
|
||||
* 3. boolean MeSmartServo::move(uint8_t dev_id,long angle_value,float speed,smartServoCb callback);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2017/07/10 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
#include <SoftwareSerial.h>
|
||||
#include "MeAuriga.h"
|
||||
|
||||
MeSmartServo mysmartservo(PORT5); //UART2 is on port 5
|
||||
|
||||
long loopTime = 0;
|
||||
|
||||
void callback_test(uint8_t servoNum)
|
||||
{
|
||||
switch(servoNum)
|
||||
{
|
||||
case 1:
|
||||
Serial.println("servo 1 has been reached!");
|
||||
break;
|
||||
case 2:
|
||||
Serial.println("servo 2 has been reached!");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
mysmartservo.begin(115200);
|
||||
delay(5);
|
||||
mysmartservo.assignDevIdRequest();
|
||||
delay(50);
|
||||
Serial.println("setup!");
|
||||
loopTime = millis();
|
||||
mysmartservo.moveTo(1,0,50);
|
||||
mysmartservo.moveTo(2,0,50);
|
||||
delay(2000);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
mysmartservo.moveTo(1,360,50,callback_test); //device ID, angle, speed; relative angle move;
|
||||
mysmartservo.moveTo(2,360,50,callback_test); //device ID, angle, speed; relative angle move;
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,76 @@
|
|||
/**
|
||||
* \par Copyright (C), 2012-2016, MakeBlock
|
||||
* @file SmartServoTest.ino
|
||||
* @author MakeBlock
|
||||
* @version V1.0.0
|
||||
* @date 2016/08/31
|
||||
* @brief Description: this file is sample code for Smart servo device.
|
||||
*
|
||||
* Function List:
|
||||
* 1. boolean MeSmartServo::assignDevIdRequest(void);
|
||||
* 2. boolean MeSmartServo::moveTo(uint8_t dev_id,long angle_value,float speed);
|
||||
* 3. boolean MeSmartServo::move(uint8_t dev_id,long angle_value,float speed);
|
||||
* 4. long MeSmartServo::getAngleRequest(uint8_t devId);
|
||||
* 5. float MeSmartServo::getSpeedRequest(uint8_t devId);
|
||||
* 6. float MeSmartServo::getVoltageRequest(uint8_t devId);
|
||||
* 7. float MeSmartServo::getTempRequest(uint8_t devId);
|
||||
* 8. float MeSmartServo::getCurrentRequest(uint8_t devId);
|
||||
*
|
||||
* \par History:
|
||||
* <pre>
|
||||
* <Author> <Time> <Version> <Descr>
|
||||
* Mark Yan 2016/08/31 1.0.0 build the new
|
||||
* </pre>
|
||||
*/
|
||||
#include <SoftwareSerial.h>
|
||||
#include "MeAuriga.h"
|
||||
|
||||
MeSmartServo mysmartservo(PORT5); //UART2 is on port 5
|
||||
|
||||
long loopTime = 0;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200);
|
||||
mysmartservo.begin(115200);
|
||||
delay(5);
|
||||
mysmartservo.assignDevIdRequest();
|
||||
delay(50);
|
||||
Serial.println("setup!");
|
||||
loopTime = millis();
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
mysmartservo.moveTo(1,360,50); //device ID, angle, speed; absolute angle move;
|
||||
loopTime = millis();
|
||||
while(millis() - loopTime < 2000)
|
||||
{
|
||||
Serial.print("angle:");
|
||||
Serial.print(mysmartservo.getAngleRequest(1));
|
||||
Serial.print(" speed:");
|
||||
Serial.print(mysmartservo.getSpeedRequest(1));
|
||||
Serial.print(" voltage:");
|
||||
Serial.print(mysmartservo.getVoltageRequest(1));
|
||||
Serial.print(" temp:");
|
||||
Serial.print(mysmartservo.getTempRequest(1));
|
||||
Serial.print(" Current:");
|
||||
Serial.println(mysmartservo.getCurrentRequest(1));
|
||||
}
|
||||
mysmartservo.move(1,-360,50); //device ID, angle, speed; relative angle move;
|
||||
loopTime = millis();
|
||||
while(millis() - loopTime < 2000)
|
||||
{
|
||||
Serial.print("angle:");
|
||||
Serial.print(mysmartservo.getAngleRequest(1));
|
||||
Serial.print(" speed:");
|
||||
Serial.print(mysmartservo.getSpeedRequest(1));
|
||||
Serial.print(" voltage:");
|
||||
Serial.print(mysmartservo.getVoltageRequest(1));
|
||||
Serial.print(" temp:");
|
||||
Serial.print(mysmartservo.getTempRequest(1));
|
||||
Serial.print(" Current:");
|
||||
Serial.println(mysmartservo.getCurrentRequest(1));
|
||||
}
|
||||
}
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue