Commit 3af8c184 by satsob

Uuendused

parent a89f92d0
# 3.1 BLE ühenduse loomine RF24 ja nutitelefoni vahel
# 3.1 BLE ühenduse loomine RF24 ja nutitelefoni vahel
Ülesandeks oli luua BLE (Bluetooth Low Energy, edaspidi BLE) kommunikeerimine telefoniga, mitte ühenduse, vaid andmepakettide saatmise-vastuvõtmise teel. Kasutusel oli RF24 raadiosidemoodul, mille kaudu pidi suutma saata nutitelefonile (Android või iPhone) pakette ning neid ka vastu võtma.
/* Include libraries */
/* Include libraries */
#include <SPI.h>
#include <RF24.h>
#include <BTLE.h>
RF24 radio(9,10); // Create RF24 object to work with the RF24 library.
BTLE btle(&radio); // Create BTLE object to work with the BTLE library.
// Replace! "CustomName" to the name of your device. Password - maximum length (14)! characters
#define PASSWORD "Galaxy A70"
void setup() {
/* Start the Serial and btle. */
Serial.begin(9600);
// while (!Serial) { }
// Serial.println("BTLE advertisement receiver");
btle.begin("");
}
void loop() {
String str = ""; // For collecting a string of values ​​from different types of variables
/* Start listening. If data is received it is stored in the "buffer".
Then the received data is decoded and checked (CRC). */
if (btle.listen()) {
// Serial.print("Got payload: "); // If data is received, print "Got payload: "
// Store the received data into the buffer
for (uint8_t i = 2; i < (btle.buffer.pl_size)-6; i++) {
str += (char (btle.buffer.payload[i]));
// Serial.print(btle.buffer.payload[i],HEX); Serial.print(" "); // To receive data in HEX format
// Serial.print(char (btle.buffer.payload[i])); Serial.print(" "); // To receive data in char format
}
// (Spam protection) only if string starts with "CustomName"
if (str.startsWith(PASSWORD)) {
str.replace(PASSWORD, ""); // (remove / replace) PASSWORD
// According to what data was sent, print the direction
if ((char (str.charAt(2))) == 7) Serial.println("RIGHT");
else if ((char (str.charAt(2))) == 6) Serial.println("LEFT");
else if ((char (str.charAt(2))) == 5) Serial.println("FORWARD");
else if ((char (str.charAt(2))) == 4) Serial.println("BACKWARD");
}
}
btle.hopChannel();
}
#include <SPI.h>
#include <SPI.h>
#include <RF24.h>
#include <BTLE.h>
RF24 radio(9,10);
BTLE btle(&radio);
void setup() {
Serial.begin(9600);
while (!Serial) { }
Serial.println("BTLE advertisement sender");
btle.begin("foobar");
}
void loop() {
float temp = 0.5; // Send battery level
// float temp = 30; // Send temperature
nrf_service_data buf;
// buf.service_uuid = NRF_DEVICE_INFORMATION_SERVICE_UUID; // 0x180A
// buf.service_uuid = NRF_TEMPERATURE_SERVICE_UUID; // 0x1809
buf.service_uuid = NRF_BATTERY_SERVICE_UUID; // 0x180F
buf.value = BTLE::to_nRF_Float(temp);
btle.advertise(0x16, &buf, sizeof(buf));
// btle.advertise(0,0);
btle.hopChannel();
Serial.print(".");
}
# Roboti puldiga juhtimise ülesanne
# Roboti puldiga juhtimise ülesanne
Ülesande eesmärgiks on tekitada raadioside roboti ja kursorhoobi kilbi vahel.
# Roboti juhtimine BT ühenduse kaudu
# Roboti juhtimine BT ühenduse kaudu
Ülesandeks oli roboti juhtimine BT ühenduse kaudu. Kasutamiseks on HC-05, mis võimaldab ühenduse loomist kahe seadme vahel kasutades selleks BT ühendust. Roboti juhtimine toimub läbi nutitelefoni. Google Play poest, kui ka Apple Appstore-ist on saadaval erinevad robotite juhtimiseks aplikatsioonid, läbi mille on võimalik luua robotiga ühendus ning käske saata. Selle ülesande eesmärgiks on õpetada tudengitele, kuidas toimib BT side seadmete ja moodulite vahel.
# Labürindi läbimine liigutatava ultraheli sensoriga
# Labürindi läbimine liigutatava ultraheli sensoriga
Ülesande eesmärgiks on luua robotile ultraheli sensori süsteem, millega suudetakse takistustest mööda põigata. Robot hakkab sõitma ning takistuseni jõudes jääb robot seisma ning hakkab ultrahelisensoriga otsima, kumbalt poolelt saaks mööduda ning kas see üldse on võimalik.
#include <LiquidCrystal_I2C.h>
#include <LiquidCrystal_I2C.h>
#include <Servo.h>
LiquidCrystal_I2C lcd(0x3F, 16, 2); // Address found using lcd scanner, columns, rows
/*
TEST!
There are 16x2 segments on the LCD display. Each segment is 8x5 (width x length).
The points in the segment starts from left to right and from top to bottom.
"1" (ONE) represents filled box and "0" (ZERO) unfilled box in the segment.
For example, 00010 means that in the first line only the forth box in segment is filled.
Other boxes in the line are unfilled (not active).
*/
//byte test[8] = {B00001, B00010, B00100, B01000, B10000, B00101, B00110, B00111};
/*
Intialize for robot driving pathway.
Byte array to store the values for LCD. B or 0b. Equals one segment.
*/
byte liigun[8] = {B00000, B00000, B00000, B00000, B00000, B00000, B00000, B00000};
byte temp[8] = {0}; // To temporarily store liigun array
bool sameArray = false; // To check whether to save temp array or not
int sameCounter = 0; // To check whether to save temp array or not. 1 - Store array
// 2 - Store it back to liigun array and reset the counter
/* LCD coordinates. To create points on LCD screen segments. */
int pointx = 0; // Can only be 0 or 1; sets x position on lcd
int pointy = 0; // Can be max 7; sets y postion on lcd
/* To store the values for moving on LCD screen. To move in array. */
int counterb = 7 // Initialize counterb as array[counterb]. 7 to start from the bottom, 0 from top.
int cursorCounter = 0; // Initialize cursorCounter that sets cursor point on LCD
int pos = 4; // Initialize pos (position) to calculate the correct postion
int posx = 0; // Starting x position and the position of x-axis segment, max 79
int posy = 8; // Starting y position and the position of y-axis segment, max 15
/*
Robot movement stuff!
*/
/* Defines */
#define rightServo 5 // Define Servo right pin
#define leftServo 6 // Define Servo left pin
/* Global variables */
Servo rightWheel;
Servo leftWheel;
/* Define functions used to control the robot. */
/* Stop the robot */
void setWheelsStop() {
rightWheel.writeMicroseconds(1500);
leftWheel.writeMicroseconds(1500);
}
/* Drive forward */
void setWheelsForward() {
rightWheel.write(1300);
leftWheel.write(1700);
}
/* Drive right */
void setWheelsRight() {
rightWheel.write(1700);
leftWheel.write(1700);
}
/* Drive left */
void setWheelsLeft() {
rightWheel.write(1300);
leftWheel.write(1300);
}
void setup()
{
lcd.begin();
Serial.begin(9600);
/* Attach servos to digital pins defined earlier */
rightWheel.attach(rightServo);
leftWheel.attach(leftServo);
/* Put servos to standstill */
//setWheelsStop();
/***** Ignore the commented out code! These are FOR TESTING purposes! *****/
// lcd.backlight();
// lcd.clear();
// lcd.setCursor(4, 0);
// lcd.print("Write Something!");
// delay(500);
// lcd.clear();
// lcd.scrollDisplayLeft(); //moves sentence to the left by one character. Right to right.
// lcd.cursor(); //show visible cursor below next char that will be printed
// lcd.noCursor(); //turns cursor off
// lcd.blink(); //similar to lcd.cursor but creates blinking block cursor
// lcd.noBlink(); //turn blinking cursor off
/* TEST */
// lcd.createChar(6, test);
// lcd.setCursor(0, 0);
// lcd.write(6);
/***** Ignore the commented out code! These are FOR TESTING purposes! *****/
}
void loop()
{
/* Check if you can move forward. YOU CAN ONLY MOVE FORWARD EIGHTY (80) TIMES! */
if (posx >= 79) {
Serial.println("ERROR!");
exit(0);
}
if (otse) {
/* Check in which segment you are going to draw a point. */
if (posx % 5 == 0) {
changeSegment(2); // Two to move forward
}
/* DO NOT CHANGE counterb HERE! Change only when moving right or left! */
liigun[counterb] = liigun[counterb] | (1 << pos);
lcd.createChar(cursorCounter, liigun[counterb]);
lcd.setCursor(pointx, pointy);
lcd.write(cursorCounter);
posx++; // Increment posx to move on the segment to know were we at.
pos--; // Decrement pos to get the correct power of 2 to add to counterb.
}
else if (parem) {
/* Check if you can move right. */
if (pointy == 1 && posy == 0) {
Serial.println("ERROR! CANNOT MOVE RIGHT NO MORE!");
exit(0);
}
/* Check in which segment you are going to draw a point. */
if (posy == 8) {
changeSegment(1); // One to move down (right)
} else {
counterb++; // Increment counterb to "move right" in array.
}
liigun[counterb] = liigun[counterb] | (1 << pos);
lcd.createChar(cursorCounter, liigun[counterb]);
lcd.setCursor(pointx, pointy);
lcd.write(cursorCounter);
posx++; // Increment posx to move forward one step.
posy--; // Decrement posy to move down one step.
pos--; // Decrement pos to get the correct power of 2 to add to counterb.
}
else if (vasak) {
/* Check if you can move left. */
if (pointy == 0 && posy == 15) {
Serial.println("ERROR! CANNOT MOVE LEFT NO MORE!");
exit(0);
}
/* Check in which segment you are going to draw a point. */
if (posy == 7) {
changeSegment(0); // Zero to move up (left)
} else {
counterb--; // Decrement counterb to "move left" in array.
}
liigun[counterb] = liigun[counterb] | (1 << pos);
lcd.createChar(cursorCounter, liigun[counterb]);
lcd.setCursor(pointx, pointy);
lcd.write(cursorCounter);
posx++; // Increment posx to move forward one step.
posy++; // Increment posy to move up one step.
pos--; // Decrement pos to get the correct power of 2 to add to counterb.
}
}
void changeSegment(int a) {
/*
Here it is determined whether to increment or decrement the position on the LCD.
For moving forward a is 2, right a is 1 and left a is 0.
According to the int value it's determined whether to increment pointx or pointy.
Boolean sameArray and int sameCounter is used when we change the segment, but later
we need the old array back if we return to the previous segment so that
the path is not lost. If the counter is two then we restore the previous array.
cursorCounter is used to know in which segment to create the pathway.
*/
if (a == 2) {
pointx++;
pos = 4; // Reinitialize pos to 4.
sameArray = false; // Just in case sameArray is true but pointx and pointy have changed.
}
else if (a == 1) {
/* Fristly check if you're going to move one segment down and towards. */
if (posx % 5 == 0 && posy == 8) {
pointx++;
pointy++;
pos = 4; // Reinitialize pos to 4.
sameArray = false; // Just in case sameArray is true but pointx and pointy have changed.
}
else if (pointy == 0) {
sameArray = true;
sameCounter++;
//temp = liigun;
pointy = 1; // Move down one segment
}
counterb = 0;
}
else if (a == 0) {
/* Fristly check if you're going to move one segment up and towards. */
if (posx % 5 == 0 && posy == 7) {
pointx++;
pointy--;
pos = 4; // Reinitialize pos to 4.
sameArray = false; // Just in case sameArray is true but pointx and pointy have changed.
}
else if (pointy == 1) {
sameArray = true;
sameCounter++;
pointy = 0; // Move up one segment
}
counterb = 7;
}
if (sameArray) {
if (sameCounter == 1) {
/* Copy the contents of array liigun to array temp for later use. */
memcpy(temp, liigun, sizeof(liigun)); // OR sizeof(temp)
//resetArray();
/* Increment cursorCounter for next segment. */
cursorCounter++;
}
else if (sameCounter == 2) { // If you need to copy the contents of temp back to array.
memcpy(liigun, temp, sizeof(temp)); // OR sizeof(temp)
memset(temp, 0, sizeof(temp)); // Empty temp array
cursorCounter--;
sameCounter = 0;
sameArray = false;
}
} else {
//resetArray();
/* Increment cursorCounter for next segment. */
cursorCounter++;
}
}
/***** WORK IN PROGRESS *****/
//void resetArray() {
// // Reinitizialize robotMoving 2D array.
// memset(robotMoving,0,sizeof(robotMoving));
//
// // OR
//
// for(int i=0;i<5;i++)
// for(int j=0;j<8;j++)
// robotMoving[i][j] = 0b00000; // OR = 0 OR = 0b0
//
// memset(liigun, 0, sizeof(liigun));
//
// //OR
//
// for (int i=0; i<8; i++)
// liigun[i] = B00000; // 0b00000
//
//}
//
//void forward() {
//
//}
//
//void rightTurn() {
//
//}
//
//void leftTurn() {
//
//}
# Raja kaardistamine ekraanile
# Raja kaardistamine ekraanile
Esmalt tuleks saada robot sõitma, kas raadioside või BT ühenduse kaudu (erinevad ülesannete variandid) ning seejärel teekonna joonestamine ekraanile.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or sign in to comment