diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..a89bce8 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,9 @@ +[submodule "cxx_serial_support"] + path = code/c++/cxx-api/serial_support + url = https://github.com/wjwwood/serial.git +[submodule "cxx_gamepad_support"] + path = code/c++/cxx-gamepad-app/gamepad_support + url = https://github.com/AJIOB/libstem_gamepad.git +[submodule "cxx_libcrc"] + path = code/c++/cxx-api/libcrc + url = https://github.com/lammertb/libcrc.git diff --git a/README.md b/README.md index 9d4f767..a464d86 100644 --- a/README.md +++ b/README.md @@ -14,7 +14,9 @@ - Драйвер двигателя (L298N) - Поворотная платформа -Датчики расстояния объедены в модуль, который несложно снимается, что позволяет заменить датчики. В модуле 5 датчиков расстояния, расположенных под различными углами для улучшения ориентирования на местности. Так же углы поворота датчиков можно настраивать в небольшом диапазоне. Расположены спереди платформы. +Для отладки требуется небольная модификация исходников Arduino IDE в соответствии с [этой](https://playground.arduino.cc/Main/Printf) статьей. + +Датчики расстояния объеденены в модуль, который несложно снимается, что позволяет заменить датчики. В модуле 5 датчиков расстояния, расположенных под различными углами для улучшения ориентирования на местности. Так же углы поворота датчиков можно настраивать в небольшом диапазоне. Расположены спереди платформы. ![](https://pp.userapi.com/c626121/v626121114/60cc7/xe6EOab8Ysw.jpg) diff --git a/code/Arduino/Bluetooth.cpp b/code/Arduino/Bluetooth.cpp deleted file mode 100644 index 1dc2bed..0000000 --- a/code/Arduino/Bluetooth.cpp +++ /dev/null @@ -1,11 +0,0 @@ -#include "Bluetooth.h" - - -Bluetooth::Bluetooth(int rx, int tx, int speed) : ConnectingDevice(rx, tx, speed) -{ -} - - -Bluetooth::~Bluetooth() -{ -} diff --git a/code/Arduino/Bluetooth.h b/code/Arduino/Bluetooth.h deleted file mode 100644 index 38ff722..0000000 --- a/code/Arduino/Bluetooth.h +++ /dev/null @@ -1,10 +0,0 @@ -#pragma once -#include "ConnectingDevice.h" - -class Bluetooth : public ConnectingDevice -{ -public: - Bluetooth(int rx, int tx, int speed); - ~Bluetooth(); -}; - diff --git a/code/Arduino/CommandsController.cpp b/code/Arduino/CommandsController.cpp deleted file mode 100644 index 9c6e0f0..0000000 --- a/code/Arduino/CommandsController.cpp +++ /dev/null @@ -1,28 +0,0 @@ -#include "CommandsController.h" - - - -CommandsController::CommandsController() -{ -} - -void CommandsController::handle(ConnectingDevice *device, String command) -{ - switch (command[0]) { - case movementControllerID: - moveController.exec(device, command); - break; - case sensorsControllerID: - sensorsController.exec(device, command); - break; - case servoControllerID: - servoController.exec(device, command); - break; - default: - break; - } -} - -CommandsController::~CommandsController() -{ -} diff --git a/code/Arduino/CommandsController.h b/code/Arduino/CommandsController.h deleted file mode 100644 index 9507744..0000000 --- a/code/Arduino/CommandsController.h +++ /dev/null @@ -1,21 +0,0 @@ -#pragma once - -#include "ConnectingDevice.h" -#include "MovementController.h" -#include "SensorsController.h" -#include "ServoController.h" -#include "CommandsEnum.h" - -class CommandsController -{ -private: - MovementController moveController; - SensorsController sensorsController; - ServoController servoController; - -public: - CommandsController(); - void handle(ConnectingDevice *device, String command); - ~CommandsController(); -}; - diff --git a/code/Arduino/CommandsEnum.h b/code/Arduino/CommandsEnum.h deleted file mode 100644 index 4797d95..0000000 --- a/code/Arduino/CommandsEnum.h +++ /dev/null @@ -1,45 +0,0 @@ -#pragma once - - -enum ControllerEnum { - movementControllerID = '\001', - sensorsControllerID = '\002', - servoControllerID = '\003' -}; - -enum SensorsEnum { - distance_sensor = '\001', //get value from single distance senceor - distance_sensor_all = '\002', //get value from all distance senceors - line_sensor = '\003', //get value from single line senceor - line_sensor_all = '\004' //get value from all line senceors -}; - - -enum MoveEnum { - forward = '\001', //move forward - left = '\002', //move left - right = '\003', //move right - back = '\004', //move back - stop = '\005', //stop - forward_speed = '\006', //move forward with established speed - forward_time = '\007', //move forward while established time - back_speed = '\010', //move back with established speed - track_set_speed = '\011' //choose track and set passed speed -}; - -enum TrackDiraction { - forward_direction = true, //rotation of track in forward diration - back_direction = false //rotation of track in backword diration -}; - -enum TrackID { - left_track = 0, //left track id - right_track = 1 //right track id -}; - -enum ServoCommands { - set_horizontal_angle = '\001', //set horizontal angle of servo - set_vertical_angle = '\002', //set vertical angle of servo - set_horiz_vertical_angles = '\003', //set horizontal and verticalse angles of servo - get_coodrinates = '\004', //get current angels of horizontal and vertical servos -}; \ No newline at end of file diff --git a/code/Arduino/ConnectingDevice.cpp b/code/Arduino/ConnectingDevice.cpp deleted file mode 100644 index e52db5f..0000000 --- a/code/Arduino/ConnectingDevice.cpp +++ /dev/null @@ -1,38 +0,0 @@ -#include "ConnectingDevice.h" -#include "SoftwareSerial.h" - -ConnectingDevice::ConnectingDevice(int rx, int tx, int speed) -{ - device = new SoftwareSerial(rx, tx); - device->begin(speed); - device->listen(); -} - -void ConnectingDevice::send(String data) -{ - this->device->println(data); -} - -bool ConnectingDevice::isActive() -{ - if ((*device).available()) { - return true; - } - return false; -} - -String ConnectingDevice::read() -{ - String command = ""; - - while ((*device).available()) { - char code = (*device).read(); - command += code; - } - return command; -} - - -ConnectingDevice::~ConnectingDevice() -{ -} diff --git a/code/Arduino/ConnectingDevice.h b/code/Arduino/ConnectingDevice.h deleted file mode 100644 index 888b998..0000000 --- a/code/Arduino/ConnectingDevice.h +++ /dev/null @@ -1,16 +0,0 @@ -#pragma once -#include -#include "Arduino.h" -class ConnectingDevice -{ -protected: - SoftwareSerial *device; - -public: - ConnectingDevice(int, int, int); - bool isActive(); - String read(); - void send(String data); - virtual ~ConnectingDevice(); -}; - diff --git a/code/Arduino/Constants.cpp b/code/Arduino/Constants.cpp deleted file mode 100644 index 01c2e46..0000000 --- a/code/Arduino/Constants.cpp +++ /dev/null @@ -1,41 +0,0 @@ -#include "Constants.h" - -Constants::Constants() -{ - bluetooth_RX = 50; - bluetooth_TX = 51; - bluetooth_serial_speed = 9600; - - wifi_RX = 30; - wifi_TX = 31; - wifi_serial_speed = 9600; - - left_engine_enable = 7; - left_engine_straight_pin = 8; - left_engine_reverse_pin = 9; - right_engine_straight_pin = 10; - right_engine_reverse_pin = 11; - right_engine_enable = 12; - - /*distance_sensor_read_pin = A0;*/ - distance_sensor_a_pin = 4; - distance_sensor_b_pin = 5; - distance_sensor_c_pin = 6; - - //line_sensor_read_pin = A1; - line_sensor_a_pin = 15; - line_sensor_b_pin = 16; - line_sensor_c_pin = 17; - - servo_horizontal_pin = 34; - servo_vertical_pin = 35; - - commands_delimetr = ';'; -} - - -Constants::~Constants() -{ -} - - diff --git a/code/Arduino/Constants.h b/code/Arduino/Constants.h deleted file mode 100644 index 7bc6e8c..0000000 --- a/code/Arduino/Constants.h +++ /dev/null @@ -1,42 +0,0 @@ -#pragma once -#include - -class Constants -{ -public: - int bluetooth_RX; - int bluetooth_TX; - int bluetooth_serial_speed; - - int wifi_RX; - int wifi_TX; - int wifi_serial_speed; - - int left_engine_straight_pin; - int left_engine_reverse_pin; - int right_engine_straight_pin; - int right_engine_reverse_pin; - - int left_engine_enable; - int right_engine_enable; - - long distance_sensor_read_pin; - int distance_sensor_a_pin; - int distance_sensor_b_pin; - int distance_sensor_c_pin; - - - long line_sensor_read_pin; - int line_sensor_a_pin; - int line_sensor_b_pin; - int line_sensor_c_pin; - - int servo_horizontal_pin; - int servo_vertical_pin; - - char commands_delimetr; - - Constants(); - ~Constants(); -}; - diff --git a/code/Arduino/MainController.cpp b/code/Arduino/MainController.cpp deleted file mode 100644 index 15f4a5e..0000000 --- a/code/Arduino/MainController.cpp +++ /dev/null @@ -1,39 +0,0 @@ -#include "MainController.h" - -MainController::MainController() { - -} - - -int* MainController::parse_command(String command, int begin, char delimetr, int paramsLength) { - int* arr = new int[paramsLength]; - for (int i = 0; i < paramsLength; i++) { - int delimetrPos = command.indexOf(delimetr); - if (delimetrPos >= 0) { - arr[i] = command.substring(begin, delimetrPos).toInt(); - begin = delimetrPos + 1; - command = command.substring(begin, command.length()); - begin = 0; - } - } - return arr; -} - -int MainController::parse_command(String command, int begin, int end) { - return command.substring(begin, end).toInt(); -} - - -String MainController::intArrayToString(int* array, int size) { - String str = ""; - for (int i = 0; i < size; i++) { - str += String(array[i]); - str += ";"; - } - return str; -} - - -MainController::~MainController() { - -} \ No newline at end of file diff --git a/code/Arduino/MainController.h b/code/Arduino/MainController.h deleted file mode 100644 index a748f63..0000000 --- a/code/Arduino/MainController.h +++ /dev/null @@ -1,18 +0,0 @@ -#pragma once -#include "Arduino.h" -#include "Constants.h" -#include "CommandsEnum.h" -#include "HardwareSerial.h" -#include "ConnectingDevice.h" - -class MainController -{ -public: - Constants constants; - MainController(); - int* parse_command(String command, int begin, char delimetr, int paramsLength); - int parse_command(String command, int begin, int end); - - String intArrayToString(int*, int); - ~MainController(); -}; diff --git a/code/Arduino/MovementController.cpp b/code/Arduino/MovementController.cpp deleted file mode 100644 index 62e9bb7..0000000 --- a/code/Arduino/MovementController.cpp +++ /dev/null @@ -1,163 +0,0 @@ -#include "MovementController.h" - - - -MovementController::MovementController() -{ - MIN_SPEED = 0; - MAX_SPEED = 255; - - pinMode(constants.left_engine_enable, OUTPUT); - pinMode(constants.left_engine_straight_pin, OUTPUT); - pinMode(constants.left_engine_reverse_pin, OUTPUT); - pinMode(constants.right_engine_straight_pin, OUTPUT); - pinMode(constants.right_engine_reverse_pin, OUTPUT); - pinMode(constants.right_engine_enable, OUTPUT); - - stop_moving(); -} - -void MovementController::exec(ConnectingDevice *device, String command) { - switch (command[1]) - { - case forward: - move_forward(); - break; - case back: - move_back(); - break; - case left: - turn_left(); - break; - case right: - turn_right(); - break; - case stop: - stop_moving(); - break; - case forward_speed: - move_forward(parse_command(command, 2, command.length())); - break; - case forward_time: - move_forward(MAX_SPEED, parse_command(command, 2, command.length())); - break; - case back_speed: - move_back(parse_command(command, 2, command.length())); - break; - case track_set_speed: - choose_track_set_speed(parse_command(command, 2, constants.commands_delimetr, 2)); - break; - default: - break; - } - -} - - -void MovementController::move_forward() { - left_track_control(forward_direction, MAX_SPEED); - right_track_control(forward_direction, MAX_SPEED); -} - -void MovementController::move_forward(int speed) { - left_track_control(forward_direction, speed); - right_track_control(forward_direction, speed); -} - -void MovementController::move_forward(int speed, int time_ms) { - left_track_control(forward_direction, speed); - right_track_control(forward_direction, speed); - delay(time_ms); - stop_moving(); -} - -void MovementController::move_back() { - left_track_control(back_direction, MAX_SPEED); - right_track_control(back_direction, MAX_SPEED); -} - -void MovementController::move_back(int speed) { - left_track_control(back_direction, speed); - right_track_control(back_direction, speed); -} - -void MovementController::turn_left() { - left_track_control(forward_direction, MAX_SPEED); - right_track_control(back_direction, MAX_SPEED); -} - -void MovementController::turn_right() { - left_track_control(back_direction, MAX_SPEED); - right_track_control(forward_direction, MAX_SPEED); -} - -void MovementController::stop_moving() { - analogWrite(constants.left_engine_enable, MIN_SPEED); - analogWrite(constants.right_engine_enable, MIN_SPEED); - digitalWrite(constants.left_engine_straight_pin, LOW); - digitalWrite(constants.left_engine_reverse_pin, LOW); - digitalWrite(constants.right_engine_straight_pin, LOW); - digitalWrite(constants.right_engine_reverse_pin, LOW); -} - -void MovementController::choose_track_set_speed(int trackID, int speed) { - switch (trackID) - { - case left_track: - left_track_control(forward_direction, speed); - break; - case right_track: - right_track_control(forward_direction, speed); - break; - default: - break; - } -} - -void MovementController::choose_track_set_speed(int* arr) { - switch (arr[0]) - { - case left_track: - left_track_control(forward_direction, arr[1]); - break; - case right_track: - right_track_control(forward_direction, arr[1]); - break; - default: - break; - } -} - -void MovementController::left_track_control(bool direction, int speed) { - analogWrite(constants.left_engine_enable, speed); - switch (direction) { - case forward_direction: - digitalWrite(constants.left_engine_straight_pin, LOW); - digitalWrite(constants.left_engine_reverse_pin, HIGH); - break; - - case back_direction: - digitalWrite(constants.left_engine_straight_pin, HIGH); - digitalWrite(constants.left_engine_reverse_pin, LOW); - break; - } -} - -void MovementController::right_track_control(bool direction, int speed) { - analogWrite(constants.right_engine_enable, speed); - switch (direction) { - case forward_direction: - digitalWrite(constants.right_engine_straight_pin, LOW); - digitalWrite(constants.right_engine_reverse_pin, HIGH); - break; - - case back_direction: - digitalWrite(constants.right_engine_straight_pin, HIGH); - digitalWrite(constants.right_engine_reverse_pin, LOW); - break; - } -} - -MovementController::~MovementController() -{ -} diff --git a/code/Arduino/MovementController.h b/code/Arduino/MovementController.h deleted file mode 100644 index abaf91f..0000000 --- a/code/Arduino/MovementController.h +++ /dev/null @@ -1,31 +0,0 @@ -#pragma once - -#include "MainController.h" - - - -class MovementController : public MainController -{ -private: - Constants constants; - int MIN_SPEED; - int MAX_SPEED; - -public: - MovementController(); - void exec(ConnectingDevice *device, String); - void move_forward(); - void move_forward(int speed); - void move_forward(int speed, int time_ms); - void move_back(); - void move_back(int speed); - void turn_left(); - void turn_right(); - void left_track_control(bool direction, int speed); - void right_track_control(bool direction, int speed); - void choose_track_set_speed(int trackID, int speed); - void choose_track_set_speed(int* arr); - void stop_moving(); - ~MovementController(); -}; - diff --git a/code/Arduino/SensorsController.cpp b/code/Arduino/SensorsController.cpp deleted file mode 100644 index 2004874..0000000 --- a/code/Arduino/SensorsController.cpp +++ /dev/null @@ -1,158 +0,0 @@ -#include "SensorsController.h" - - - -SensorsController::SensorsController() -{ - countDistanceSensors = 5; - countLineSensors = 5; - minimalLineBound = 270; - - pinMode(constants.line_sensor_a_pin, OUTPUT); - pinMode(constants.line_sensor_b_pin, OUTPUT); - pinMode(constants.line_sensor_c_pin, OUTPUT); - - pinMode(constants.distance_sensor_a_pin, OUTPUT); - pinMode(constants.distance_sensor_b_pin, OUTPUT); - pinMode(constants.distance_sensor_c_pin, OUTPUT); - - digitalWrite(constants.line_sensor_a_pin, HIGH); - digitalWrite(constants.line_sensor_b_pin, LOW); - digitalWrite(constants.line_sensor_c_pin, HIGH); -} - - -void SensorsController::exec(ConnectingDevice *device, String command) { - switch (command[1]) - { - case distance_sensor: - device->send(String(getDistance(parse_command(command, 2, command.length())))); - break; - case distance_sensor_all: - device->send(intArrayToString(getDistanceAll(), countDistanceSensors)); - break; - case line_sensor: - device->send(String(getLine(parse_command(command, 2, command.length())))); - break; - case line_sensor_all: - device->send(intArrayToString(getLineAll(), countLineSensors)); - break; - default: - break; - } -} - -void SensorsController::chooseLineSensor(int number) { - switch (number) { - case 1: - digitalWrite(constants.line_sensor_a_pin, LOW); - digitalWrite(constants.line_sensor_b_pin, LOW); - digitalWrite(constants.line_sensor_c_pin, HIGH); - break; - case 2: - digitalWrite(constants.line_sensor_a_pin, HIGH); - digitalWrite(constants.line_sensor_b_pin, HIGH); - digitalWrite(constants.line_sensor_c_pin, HIGH); - break; - case 3: - digitalWrite(constants.line_sensor_a_pin, HIGH); - digitalWrite(constants.line_sensor_b_pin, LOW); - digitalWrite(constants.line_sensor_c_pin, HIGH); - break; - case 4: - digitalWrite(constants.line_sensor_a_pin, LOW); - digitalWrite(constants.line_sensor_b_pin, HIGH); - digitalWrite(constants.line_sensor_c_pin, HIGH); - break; - case 5: - digitalWrite(constants.line_sensor_a_pin, HIGH); - digitalWrite(constants.line_sensor_b_pin, LOW); - digitalWrite(constants.line_sensor_c_pin, LOW); - break; - default: - break; - } -} - -int SensorsController::getLine(int number) { - chooseLineSensor(number); - return analogRead(A1) > minimalLineBound ? 1 : 0; -} - -int* SensorsController::getLineAll() { - int* arr = new int[countLineSensors]; - for (int i = 0; i < countLineSensors; i++) { - arr[i] = getLine(i + 1); - } - return arr; -} - -void SensorsController::chooseDistanceSensor(int number) { - switch (number) { - case 1: - digitalWrite(constants.distance_sensor_a_pin, HIGH); - digitalWrite(constants.distance_sensor_b_pin, LOW); - digitalWrite(constants.distance_sensor_c_pin, LOW); - break; - case 2: - digitalWrite(constants.distance_sensor_a_pin, LOW); - digitalWrite(constants.distance_sensor_b_pin, HIGH); - digitalWrite(constants.distance_sensor_c_pin, HIGH); - break; - case 3: - digitalWrite(constants.distance_sensor_a_pin, LOW); - digitalWrite(constants.distance_sensor_b_pin, LOW); - digitalWrite(constants.distance_sensor_c_pin, HIGH); - break; - case 4: - digitalWrite(constants.distance_sensor_a_pin, HIGH); - digitalWrite(constants.distance_sensor_b_pin, LOW); - digitalWrite(constants.distance_sensor_c_pin, HIGH); - break; - case 5: - digitalWrite(constants.distance_sensor_a_pin, HIGH); - digitalWrite(constants.distance_sensor_b_pin, HIGH); - digitalWrite(constants.distance_sensor_c_pin, HIGH); - break; - default: - break; - } -} - - -int SensorsController::getDistance(int number) { - chooseDistanceSensor(number); - float volts = analogRead(A0); - float distance = (6762 / (volts)) - 4; - return distance; -} - -int* SensorsController::getDistanceAll() { - int* arr = new int[countDistanceSensors]; - for (int i = 0; i < countDistanceSensors; i++) { - arr[i] = getDistance(i + 1); - } - return arr; -} - -int SensorsController::getAverageDistance(int number, int n) { - int* arr = getDistanceNTime(number, n); - int averageDistance = 0; - for (int i = 0; i < n; i++) { - averageDistance += arr[i]; - } - return averageDistance / n; -} - - -int* SensorsController::getDistanceNTime(int number, int n) { - int* arr = new int[n]; - for (int i = 0; i < n; i++) { - arr[i] = getDistance(number); - } - return arr; -} - -SensorsController::~SensorsController() -{ -} diff --git a/code/Arduino/SensorsController.h b/code/Arduino/SensorsController.h deleted file mode 100644 index a59c69a..0000000 --- a/code/Arduino/SensorsController.h +++ /dev/null @@ -1,36 +0,0 @@ -#pragma once - -#include "ConnectingDevice.h" -#include "Constants.h" -#include "Arduino.h" -#include "MainController.h" -#include "CommandsEnum.h" - - - -class SensorsController: public MainController -{ -private: - int countDistanceSensors; - int countLineSensors; - int minimalLineBound; - -public: - Constants constants; - SensorsController(); - void exec(ConnectingDevice*, String); - - int getDistance(int); - int* getDistanceAll(); - void chooseDistanceSensor(int); - int* getDistanceNTime(int number, int n); - int getAverageDistance(int number, int n); - - - void chooseLineSensor(int); - int getLine(int); - int* getLineAll(); - - ~SensorsController(); -}; - diff --git a/code/Arduino/ServoController.cpp b/code/Arduino/ServoController.cpp deleted file mode 100644 index 3f5ab65..0000000 --- a/code/Arduino/ServoController.cpp +++ /dev/null @@ -1,76 +0,0 @@ -#include "ServoController.h" - - - -ServoController::ServoController() -{ - -} - -void ServoController::init() { - horizontalServo.attach(constants.servo_horizontal_pin); - verticalServo.attach(constants.servo_vertical_pin); - horizontalServo.write(0); - verticalServo.write(0); -} - -void ServoController::exec(ConnectingDevice* device, String command) { - switch (command[1]) - { - case set_horizontal_angle: - setHorizontalAngle(parse_command(command, 2, command.length())); - break; - case set_vertical_angle: - setVerticalAngle(parse_command(command, 2, command.length())); - break; - case set_horiz_vertical_angles: - setHorizontalAndVerticalAngle(parse_command(command, 2, constants.commands_delimetr, 2)); - break; - case get_coodrinates: - device->send(intArrayToString(getCoordinates(), 2)); - break; - default: - break; - } -} - -void ServoController::setHorizontalAngle(int angle) { - horizontalServo.write(angle); - delay(20); -} - -void ServoController::setVerticalAngle(int angle) { - verticalServo.write(angle); - delay(20); -} - -void ServoController::setHorizontalAndVerticalAngle(int angleX, int angleY) { - horizontalServo.write(angleX); - verticalServo.write(angleY); - delay(20); -} - -int* ServoController::getCoordinates() { - int* arr = new int[2]; - arr[0] = getHorizontalAngel(); - arr[1] = getVerticalAngel(); - return arr; -} - -void ServoController::setHorizontalAndVerticalAngle(int* arr) { - horizontalServo.write(arr[0]); - verticalServo.write(arr[1]); - delay(200); -} - -int ServoController::getHorizontalAngel() { - return horizontalServo.read(); -} - -int ServoController::getVerticalAngel() { - return verticalServo.read(); -} - -ServoController::~ServoController() -{ -} diff --git a/code/Arduino/ServoController.h b/code/Arduino/ServoController.h deleted file mode 100644 index 6a3dbcf..0000000 --- a/code/Arduino/ServoController.h +++ /dev/null @@ -1,27 +0,0 @@ -#pragma once -#include -#include "Constants.h" -#include "ConnectingDevice.h" -#include "MainController.h" - -class ServoController : public MainController -{ -private: - Servo horizontalServo; - Servo verticalServo; - -public: - Constants constants; - ServoController(); - void init(); - void exec(ConnectingDevice*, String); - void setHorizontalAngle(int angle); - void setVerticalAngle(int angle); - void setHorizontalAndVerticalAngle(int angleX, int angleY); - void setHorizontalAndVerticalAngle(int* arr); - int getHorizontalAngel(); - int getVerticalAngel(); - int* getCoordinates(); - ~ServoController(); -}; - diff --git a/code/Arduino/WiFi.cpp b/code/Arduino/WiFi.cpp deleted file mode 100644 index d01bebb..0000000 --- a/code/Arduino/WiFi.cpp +++ /dev/null @@ -1,12 +0,0 @@ -#include "WiFi.h" - - - -WiFi::WiFi(int rx, int tx, int speed) : ConnectingDevice(rx, tx, speed) -{ -} - - -WiFi::~WiFi() -{ -} diff --git a/code/Arduino/WiFi.h b/code/Arduino/WiFi.h deleted file mode 100644 index 0eb8f5f..0000000 --- a/code/Arduino/WiFi.h +++ /dev/null @@ -1,10 +0,0 @@ -#pragma once -#include "ConnectingDevice.h" - -class WiFi : public ConnectingDevice -{ -public: - WiFi(int rx, int tx, int speed); - ~WiFi(); -}; - diff --git a/code/Arduino/config/CommandsEnum.h b/code/Arduino/config/CommandsEnum.h new file mode 100644 index 0000000..462eb20 --- /dev/null +++ b/code/Arduino/config/CommandsEnum.h @@ -0,0 +1,80 @@ +#ifndef _COMMANDS_ENUM_H_ +#define _COMMANDS_ENUM_H_ + +enum ControllerEnum { + movementControllerID = '\001', + sensorsControllerID = '\002', + servoControllerID = '\003', + communicationControllerID = '\004', +}; + +enum SensorsEnum { + distance_sensor = '\001', //get value from single distance senceor + distance_sensor_all = '\002', //get value from all distance senceors + line_sensor = '\003', //get value from single line senceor + line_sensor_all = '\004' //get value from all line senceors +}; + +enum AreaType { + light = '\x00', // light area type + dark = '\x01', // dark area type +}; + +enum MoveEnum { + forward = '\001', //move forward: obsolete + left = '\002', //move left: obsolete + right = '\003', //move right: obsolete + back = '\004', //move back: obsolete + stop = '\005', //stop + forward_speed = '\006', //move forward with established speed + forward_time = '\007', //move forward while established time: obsolete + back_speed = '\x08', //move back with established speed: obsolete + track_set_speed = '\x09', //choose track and set passed speed + clockwise = '\x0A', //clockwise rotation with speed + track_all_set_speed = '\x0B', //set passed speed to every track +}; + +enum TrackIndex { + left_track = 0, //left track id + right_track = 1 //right track id +}; + +enum SensorManagerIndex { + line_sensor_index = 0, + distance_sensor_index = 1 +}; + +enum ServoIndex { + xy_plane = 1, //z axis + xz_plane = 2, //y axis +}; + +enum ServoCommands { + set_horizontal_angle = '\001', //set horizontal angle of servo: obsolete + set_vertical_angle = '\002', //set vertical angle of servo: obsolete + set_horiz_vertical_angles = '\003', //set horizontal and verticalse angles of servo: obsolete + get_coodrinates = '\004', //get current angels of horizontal and vertical servos: obsolete + set_angle = '\x05', //set axis angle + get_angle = '\x06', //get axis angle +}; + +enum CommunicationCommands { + startCommunicationCommand = 1, //starting communication command + stopCommunicationCommand = 2, //stopping communication command + refreshConnectionCommunicationCommand = 3, //refreshing connection timer communication command (since API v3) +}; + +/** + * @brief Describes trackPlatform API to working + * @see https://github.com/Lipotam/trackPlatform/wiki/Api + * @warning Each API must be described in @ConnectionController handler + * @warning If you add new version for API, check @ConnectionController::highestAPI field + */ +enum ApiVersion { + startBasicAPI = 1, //default API v1 + APIWithAnswer = 2, //API v2 + APIWithAutoDiconnect = 3, //API v3 + APIWithCRC = 4, //API v4 +}; + +#endif /* _COMMANDS_ENUM_H_ */ diff --git a/code/Arduino/config/Constants.cpp b/code/Arduino/config/Constants.cpp new file mode 100644 index 0000000..552ad65 --- /dev/null +++ b/code/Arduino/config/Constants.cpp @@ -0,0 +1,73 @@ +#include "Constants.h" + +/* Bluetooth (Hardware Serial3) */ +// const uint8_t Constants::bluetooth_RX = 15; +// const uint8_t Constants::bluetooth_TX = 14; +const uint32_t Constants::kBluetoothSerialSpeed = 9600; + +/* Wi-fi (Hardware Serial2) */ +// const uint8_t Constants::wifi_RX = 17; +// const uint8_t Constants::wifi_TX = 16; +const uint32_t Constants::kWifiSerialSpeed = 115200; + +/* USB (Hardware Serial) */ +// const uint8_t Constants::usb_RX = 0; +// const uint8_t Constants::usb_TX = 1; +const uint32_t Constants::kUsbSerialSpeed = 9600; + +/* Debug serial (Hardware Serial1) */ +//const uint8_t Constants::dbg_uart_RX = 19; +//const uint8_t Constants::dbg_uart_TX = 18; +const uint32_t Constants::kDbgUartSpeed = 9600; + +/* Movement controller (L298N) */ +const uint8_t Constants::kLeftEngineEnable = 11; +const uint8_t Constants::kLeftEngineStraightPin = 30; +const uint8_t Constants::kLeftEngineReversePin = 31; +const uint8_t Constants::kRightEngineStraightPin = 32; +const uint8_t Constants::kRightEngineReversePin = 33; +const uint8_t Constants::kRightEngineEnable = 10; + +/* Distanse controller */ +const uint8_t Constants::kDistanceSensorReadPin = A2; +const uint8_t Constants::kDistanceSensorAPin = 4; +const uint8_t Constants::kDistanceSensorBPin = 5; +const uint8_t Constants::kDistanceSensorCPin = A3; + +/* Line controller */ +const uint8_t Constants::kLineSensorReadPin = A0; +const uint8_t Constants::kLineSensorAPin = 6; +const uint8_t Constants::kLineSensorBPin = 7; +const uint8_t Constants::kLineSensorCPin = A1; + +/* Servo controller */ +const uint8_t Constants::kServoHorizontalPin = 34; +const uint8_t Constants::kServoVerticalPin = 35; + +const char Constants::kCommandsDelimetr = ';'; +const char Constants::kCommandsStopSymbol = '|'; +const uint32_t Constants::kCommandsWaitTime = 50; + +/* Class constants */ +const uint8_t Constants::kMinSpeed = 0; +const uint8_t Constants::kMaxSpeed = 255; +const uint16_t Constants::kServoDelay = 20; + +const uint8_t Constants::kCountDistanceSensors = 5; +const int16_t Constants::kSensorDelay = 10; + +const uint8_t Constants::kCountLineSensors = 5; +const uint16_t Constants::kMinimalLineBound = 270; + +const uint32_t Constants::kWaitCommandTimeInMs = 5000; + +const String Constants::kGoodAnswer = "OK"; +const String Constants::kBadAnswer = "ERROR"; + +Constants::Constants() +{ +} + +Constants::~Constants() +{ +} diff --git a/code/Arduino/config/Constants.h b/code/Arduino/config/Constants.h new file mode 100644 index 0000000..8fb74e1 --- /dev/null +++ b/code/Arduino/config/Constants.h @@ -0,0 +1,65 @@ +#pragma once +#include + +class Constants +{ +public: + // static const uint8_t bluetooth_RX; + // static const uint8_t bluetooth_TX; + static const uint32_t kBluetoothSerialSpeed; + + // static const uint8_t wifi_RX; + // static const uint8_t wifi_TX; + static const uint32_t kWifiSerialSpeed; + + // static const uint8_t usb_RX; + // static const uint8_t usb_TX; + static const uint32_t kUsbSerialSpeed; + + //static const uint8_t dbg_uart_RX; + //static const uint8_t dbg_uart_TX; + static const uint32_t kDbgUartSpeed; + + static const uint8_t kLeftEngineEnable; + static const uint8_t kLeftEngineStraightPin; + static const uint8_t kLeftEngineReversePin; + static const uint8_t kRightEngineStraightPin; + static const uint8_t kRightEngineReversePin; + static const uint8_t kRightEngineEnable; + + static const uint8_t kDistanceSensorReadPin; + static const uint8_t kDistanceSensorAPin; + static const uint8_t kDistanceSensorBPin; + static const uint8_t kDistanceSensorCPin; + + static const uint8_t kLineSensorReadPin; + static const uint8_t kLineSensorAPin; + static const uint8_t kLineSensorBPin; + static const uint8_t kLineSensorCPin; + + static const uint8_t kServoHorizontalPin; + static const uint8_t kServoVerticalPin; + + static const char kCommandsDelimetr; + static const char kCommandsStopSymbol; + static const uint32_t kCommandsWaitTime; + + static const uint8_t kMinSpeed; + static const uint8_t kMaxSpeed; + static const uint16_t kServoDelay; + + static const uint8_t kCountDistanceSensors; + static const int16_t kSensorDelay; + + static const uint8_t kCountLineSensors; + static const uint16_t kMinimalLineBound; + + static const uint32_t kWaitCommandTimeInMs; + + static const String kGoodAnswer; + static const String kBadAnswer; + + Constants(); + ~Constants(); +}; + diff --git a/code/Arduino/connection/Bluetooth.cpp b/code/Arduino/connection/Bluetooth.cpp new file mode 100644 index 0000000..12211f7 --- /dev/null +++ b/code/Arduino/connection/Bluetooth.cpp @@ -0,0 +1,16 @@ +#include "Bluetooth.h" + +bool Bluetooth::is_inited_ = false; + +Bluetooth::Bluetooth(unsigned long speed) : IConnector(&Serial3) +{ + if (!is_inited_) + { + is_inited_ = true; + Serial3.begin(speed); + } +} + +Bluetooth::~Bluetooth() +{ +} diff --git a/code/Arduino/connection/Bluetooth.h b/code/Arduino/connection/Bluetooth.h new file mode 100644 index 0000000..1af7003 --- /dev/null +++ b/code/Arduino/connection/Bluetooth.h @@ -0,0 +1,19 @@ +#pragma once +#include "IConnector.h" + +/** + * @brief Bluetooth controller class + * @attention Create first object of that class in setup() method only + */ +class Bluetooth : public IConnector +{ + /** + * @brief Block for double initialization + */ + static bool is_inited_; + +public: + explicit Bluetooth(unsigned long speed); + ~Bluetooth(); +}; + diff --git a/code/Arduino/connection/ConnectionManager.cpp b/code/Arduino/connection/ConnectionManager.cpp new file mode 100644 index 0000000..27a0c14 --- /dev/null +++ b/code/Arduino/connection/ConnectionManager.cpp @@ -0,0 +1,292 @@ +#include + +#include "../connection/USB.h" +#include "../connection/Bluetooth.h" +#include "../connection/WiFi_my.h" +#include "../config/Constants.h" +#include "../connection/DebugSerial.h" +#include "../management/MainManager.h" + +#include "ConnectionManager.h" + +ConnectionManager* ConnectionManager::manager_ = nullptr; + +ConnectionManager::ConnectionManager() +{ + connectors = new IConnector*[connectors_num]; + connectors[0] = new USB(Constants::kUsbSerialSpeed); + connectors[1] = new Bluetooth(Constants::kBluetoothSerialSpeed); + connectors[2] = new WiFi_my(Constants::kWifiSerialSpeed); + + timer.start_or_resume(); +} + +ConnectionManager::ConnectionManager(ConnectionManager&) +{ +} + +ConnectionManager* ConnectionManager::get_manager() +{ + if (!manager_) + { + manager_ = new ConnectionManager(); + } + return manager_; +} + +String ConnectionManager::read_command() +{ + if (connection_status == not_connected) + { + wait_for_connection(); + } + + String empty; + + if (timer.isFinished()) + { + reset_current_connection(); + DEBUG_PRINTLN("Disconnect by timeout"); + MainManager::get_manager()->stop_all(); + return empty; + } + + if (!current_connector) + { + DEBUG_PRINTLN("Bad connector when trying to read"); + return empty; + } + + if (current_connector->is_need_to_read_message()) + { + uint8_t buff[BUFFER_SIZE] = { 0 }; + const int length = current_connector->read_message(buff, BUFFER_SIZE); + if (is_message_is_command(buff, length)) + { + write_answer(Constants::kGoodAnswer); + timer.reset(); + return get_data_from_wrapper(buff, length); + } + + write_answer(Constants::kBadAnswer); + DEBUG_PRINT("Received message is not a command "); + DEBUG_PRINTLNHEX(buff, length); + } + + return empty; +} + +ConnectionManager::~ConnectionManager() +{ + if (connectors) { + for (int i = 0; i < connectors_num; ++i) { + if (connectors[i]) { + delete connectors[i]; + } + } + + delete[] connectors; + } +} + +String ConnectionManager::convert_pointer_to_string(const void* ptr, int size) +{ + const char* char_ptr = reinterpret_cast(ptr); + String res; + for (int i = 0; i < size; ++i) + { + res += char_ptr[i]; + } + return res; +} + +bool ConnectionManager::is_message_is_command(uint8_t* buffer, int length) +{ + if (length < (length_length + crc_length)) + { + DEBUG_PRINTF("Message size %d is too little\n", length); + return false; + } + + byte len = 0; + memcpy(&len, buffer, length_length); + + if (length != (len + length_length + crc_length)) + { + DEBUG_PRINTF("Message size %d is not equal first byte %d\n", length, (len + length_length + crc_length)); + return false; + } + + const uint16_t crc = crc_calculator.modbus(buffer, length); + + if (crc != 0) + { + DEBUG_PRINTF("Bad crc. Calculated %04X\n", crc); + return false; + } + + return true; +} + +void ConnectionManager::write_answer(String answer) +{ + const byte len = answer.length(); + + uint8_t buffer[BUFFER_SIZE] = {0}; + uint8_t buffer_length = 0; + memcpy(buffer + buffer_length, &len, length_length); + buffer_length += length_length; + memcpy(buffer + buffer_length, answer.c_str(), len); + buffer_length += len; + + const uint16_t crc = crc_calculator.modbus(buffer, buffer_length); + memcpy(buffer + buffer_length, &crc, crc_length); + buffer_length += crc_length; + + if (current_connector) + { + current_connector->write_answer(buffer, buffer_length); + } + else + { + DEBUG_PRINTLN("Current connector no set to write answer"); + } +} + +bool ConnectionManager::is_connected() const +{ + return connection_status == connected; +} + +void ConnectionManager::set_current_connection() +{ + connection_status = connected; + DEBUG_PRINTLN("Connected successful"); +} + +void ConnectionManager::reset_current_connection() +{ + connection_status = not_connected; + DEBUG_PRINTLN("Disconnected successful"); +} + +void ConnectionManager::reset_timer() +{ + timer.reset(); + DEBUG_PRINTLN("Timer resetting successful"); +} + +void ConnectionManager::wait_for_connection() +{ + DEBUG_PRINTLN("Arduino tries to found a manager"); + + connection_status = try_connect; + + int connector_index = connectors_num - 1; + while (!is_connected()) { + connector_index = (connector_index + 1) % connectors_num; + current_connector = connectors[connector_index]; + + timer.start_or_resume(); + timer.reset(); + + MainManager::get_manager()->run(); + } + + DEBUG_PRINTF("Arduino found a manager with index %d\n", connector_index); +} + +String ConnectionManager::get_data_from_wrapper(uint8_t* buffer, int length) +{ + //remove length + //buffer.remove(0, length_length); + + //remove crc + //buffer.remove(buffer.length() - crc_length, crc_length); + + String answer; + + for (int i = 1; i < (length - crc_length); ++i) + { + answer += static_cast(buffer[i]); + } + + return answer; +} + +//bool ConnectionManager::wait_for_command_on_device(Timer* timer) +//{ +// //compatibility with API v1 & v2 +// if (connectedAPIversion >= APIWithAutoDiconnect) +// { +// while (!current_connector->is_need_to_read_message() && timer->getState() != timerState_finished) +// { +// delay(1); +// } +// +// if (timer->getState() == timerState_finished) +// { +// return false; +// } +// } +// else +// { +// while (!current_connector->is_need_to_read_message()) +// { +// delay(1); +// } +// } +// +// return true; +//} +// +//String ConnectionManager::read_command() +//{ +// if (!isConnected) +// { +// return ""; +// } +// +// String command; +// Timer timer(Constants::wait_command_time_in_ms); +// timer.startOrResume(); +// do +// { +// if (!wait_for_command_on_device(&timer)) +// { +// isConnected = false; +// wait_for_connection(); +// timer.reset(); +// continue; +// } +// +// command = current_connector->read_message(); +// +// //API v1 & v2 compatibility +// if (connectedAPIversion >= APIWithAnswer) +// { +// current_connector->write_answer("OK"); +// } +// +// //debug +// DEBUG_PRINT("Command: "); +// DEBUG_PRINTLNHEX(command); +// +// if (command == disconnectCommand) +// { +// isConnected = false; +// wait_for_connection(); +// timer.reset(); +// continue; +// } +// +// if (connectedAPIversion >= APIWithAutoDiconnect && command == refreshCommand) +// { +// timer.reset(); +// continue; +// } +// +// break; +// } while (true); +// return command; +//} diff --git a/code/Arduino/connection/ConnectionManager.h b/code/Arduino/connection/ConnectionManager.h new file mode 100644 index 0000000..059e5f2 --- /dev/null +++ b/code/Arduino/connection/ConnectionManager.h @@ -0,0 +1,50 @@ +#pragma once +#include +#include + +#include "../connection/IConnector.h" +#include "../utils/Timer.h" +#include "../config/Constants.h" + +enum ConnectionStatus +{ + not_connected, + try_connect, + connected +}; + +class ConnectionManager +{ + static ConnectionManager* manager_; + ConnectionManager(); + ConnectionManager(ConnectionManager &); + ~ConnectionManager(); + + const int connectors_num = 3; + IConnector** connectors = nullptr; + IConnector* current_connector = nullptr; + FastCRC16 crc_calculator; + const int crc_length = sizeof (uint16_t); + const int length_length = sizeof (byte); + + Timer timer = Timer(Constants::kWaitCommandTimeInMs); + ConnectionStatus connection_status = not_connected; + + String convert_pointer_to_string(const void* ptr, int size); + + bool is_message_is_command(uint8_t* buffer, int length); + void wait_for_connection(); + String get_data_from_wrapper(uint8_t* buffer, int length); + +public: + static ConnectionManager* get_manager(); + + String read_command(); + void write_answer(String answer); + + //Command handlers + bool is_connected() const; + void set_current_connection(); + void reset_current_connection(); + void reset_timer(); +}; diff --git a/code/Arduino/connection/DebugSerial.cpp b/code/Arduino/connection/DebugSerial.cpp new file mode 100644 index 0000000..7b48f33 --- /dev/null +++ b/code/Arduino/connection/DebugSerial.cpp @@ -0,0 +1,82 @@ +#include +#include "../config/Constants.h" +#include "DebugSerial.h" + +#ifdef DEBUG_ON + +HardwareSerial* DebugSerial::serial_ = &Serial1; +bool DebugSerial::isInited = false; + +DebugSerial::DebugSerial(): IConnector(serial_) +{ + if (!isInited) + { + isInited = true; + serial_->begin(Constants::kDbgUartSpeed); + } +} + +Stream* DebugSerial::get_serial() +{ + return serial_; +} + +void DebugSerial::write_answer(uint8_t* answer_ptr, int length) +{ + IConnector::write_answer(answer_ptr, length); +} + +void DebugSerial::print(String data) +{ + device_->print(data); +} + +void DebugSerial::println(String data) +{ + device_->println(data); +} + +void DebugSerial::printHex(String data) +{ + for (unsigned int i = 0; i < data.length(); ++i) + { + printf("%02X ", data[i]); + } +} + +void DebugSerial::printHex(uint8_t* data, size_t size) +{ + for (unsigned int i = 0; i < size; ++i) + { + printf("%02X ", data[i]); + } +} + +void DebugSerial::printlnHex(String data) +{ + printHex(data); + device_->println(""); +} + +void DebugSerial::printlnHex(uint8_t* data, size_t size) +{ + printHex(data, size); + device_->println(""); +} + +void DebugSerial::printf(const char* format, ...) +{ + char buf[printfBuffSize] = {0}; + va_list ap; + va_start(ap, format); + vsnprintf(buf, sizeof(buf), format, ap); + for (char *p = &buf[0]; *p; p++) // emulate cooked mode for newlines + { + if (*p == '\n') + device_->write('\r'); + device_->write(*p); + } + va_end(ap); +} + +#endif diff --git a/code/Arduino/connection/DebugSerial.h b/code/Arduino/connection/DebugSerial.h new file mode 100644 index 0000000..4d8d300 --- /dev/null +++ b/code/Arduino/connection/DebugSerial.h @@ -0,0 +1,87 @@ +#pragma once +#include +#include + +#include "IConnector.h" + +/** + * @brief Define, if debug is require + */ +#define DEBUG_ON + +#ifdef DEBUG_ON + +#define DEBUG_PRINT(...) DebugSerial().print(__VA_ARGS__) +#define DEBUG_PRINTLN(...) DebugSerial().println(__VA_ARGS__) +#define DEBUG_PRINTHEX(...) DebugSerial().printHex(__VA_ARGS__) +#define DEBUG_PRINTLNHEX(...) DebugSerial().printlnHex(__VA_ARGS__) +#define DEBUG_PRINTF(...) DebugSerial().printf(__VA_ARGS__) + +#else + +#define DEBUG_PRINT(...) +#define DEBUG_PRINTLN(...) +#define DEBUG_PRINTHEX(...) +#define DEBUG_PRINTLNHEX(...) +#define DEBUG_PRINTF(...) + +#endif + +#ifdef DEBUG_ON +class DebugSerial : public IConnector +{ + static HardwareSerial* serial_; + static const int printfBuffSize = 120; + + /** + * @brief Block for double initialization + */ + static bool isInited; + +public: + DebugSerial(); + + static Stream* get_serial(); + + /** + * @brief println(String) duplicate + * + * @param answer_ptr String to send + */ + void write_answer(uint8_t* answer_ptr, int length) override; + /** + * @brief Prints data string to debug console + * + * @param data String to print + */ + void print(String data); + /** + * @brief Prints data to debug console and adds newline symbol in the end + * + * @param data String to print + */ + void println(String data); + /** + * @brief Prints data in hex view (with space delimiters) to debug console + * + * @param data String to print + */ + void printHex(String data); + void printHex(uint8_t* data, size_t size); + /** + * @brief Prints data in hex view (with space delimiters) to debug console and prints newline symbol at the end + * + * @param data String to print + */ + void printlnHex(String data); + + void printlnHex(uint8_t* data, size_t size); + /** + * @brief Prints data as simple printf function + * @warning No float/double support + * @warning Max buffer length (with printed values) must be less that @printBuffSize class member + */ + void printf(const char *format, ...); +}; + +#endif diff --git a/code/Arduino/connection/IConnector.cpp b/code/Arduino/connection/IConnector.cpp new file mode 100644 index 0000000..3ea0cab --- /dev/null +++ b/code/Arduino/connection/IConnector.cpp @@ -0,0 +1,52 @@ +#include + +#include "../config/Constants.h" +#include "IConnector.h" + +IConnector::IConnector(Stream* ptr) : device_(ptr) +{ + device_->setTimeout(Constants::kCommandsWaitTime); +} + +IConnector::IConnector(int rx, int tx, unsigned long speed) +{ + SoftwareSerial* serial_ptr = new SoftwareSerial(rx, tx); + serial_ptr->begin(speed); + serial_ptr->listen(); + + device_ = serial_ptr; + device_->setTimeout(Constants::kCommandsWaitTime); +} + +void IConnector::write_answer(uint8_t* answer_ptr, int length) +{ + for (int i = 0; i < length; ++i) + { + device_->print((reinterpret_cast(answer_ptr))[i]); + } +} + +bool IConnector::is_need_to_read_message() +{ + return device_->available(); +} + +int IConnector::read_message(uint8_t* pointer, int max_length) +{ + static const uint8_t kCrcLength = sizeof(uint16_t); + static const uint8_t kLengthLength = sizeof(uint8_t); + + if (device_->readBytes(pointer, kLengthLength) != kLengthLength) + { + return 0; + } + const uint8_t payload_length = pointer[0]; + int16_t package_length = (payload_length + kCrcLength + kLengthLength); + package_length = (package_length > max_length) ? max_length : package_length; + return (device_->readBytes(pointer + kLengthLength, package_length - kLengthLength) + kLengthLength); +} + + +IConnector::~IConnector() +{ +} diff --git a/code/Arduino/connection/IConnector.h b/code/Arduino/connection/IConnector.h new file mode 100644 index 0000000..a1ee0c4 --- /dev/null +++ b/code/Arduino/connection/IConnector.h @@ -0,0 +1,21 @@ +#pragma once +#include +#include + +#define BUFFER_SIZE 64 + +class IConnector +{ +protected: + explicit IConnector(Stream* ptr); + + Stream *device_; +public: + IConnector(int rx, int tx, unsigned long speed); + virtual ~IConnector(); + + virtual bool is_need_to_read_message(); + virtual int read_message(uint8_t* pointer, int max_length); + virtual void write_answer(uint8_t* answer_ptr, int length); +}; + diff --git a/code/Arduino/connection/USB.cpp b/code/Arduino/connection/USB.cpp new file mode 100644 index 0000000..1c4bbff --- /dev/null +++ b/code/Arduino/connection/USB.cpp @@ -0,0 +1,16 @@ +#include "USB.h" + +bool USB::is_inited_ = false; + +USB::USB(unsigned long speed) : IConnector(&Serial) +{ + if (!is_inited_) + { + is_inited_ = true; + Serial.begin(speed); + } +} + +USB::~USB() +{ +} diff --git a/code/Arduino/connection/USB.h b/code/Arduino/connection/USB.h new file mode 100644 index 0000000..c5beae0 --- /dev/null +++ b/code/Arduino/connection/USB.h @@ -0,0 +1,19 @@ +#pragma once + +#include "IConnector.h" + +/** + * @brief USB controller class + * @attention Create first object of that class in setup() method only + */ +class USB : public IConnector +{ + /** + * @brief Block for double initialization + */ + static bool is_inited_; + +public: + explicit USB(unsigned long speed); + ~USB(); +}; diff --git a/code/Arduino/connection/WiFi_my.cpp b/code/Arduino/connection/WiFi_my.cpp new file mode 100644 index 0000000..2c9a97d --- /dev/null +++ b/code/Arduino/connection/WiFi_my.cpp @@ -0,0 +1,259 @@ +#include "WiFi_my.h" +#include "../utils/Timer.h" +#include "DebugSerial.h" + +WiFi_my::WiFi_my(unsigned long speed) :IConnector(&Serial2) { + //Добавить вывод IP + DEBUG_PRINTLN("Constructor wifi"); + if (is_inited_) + { + return; + } + is_inited_ = true; + Serial2.begin(speed); + is_server_started_ = false; + DEBUG_PRINTLN("Constructor wifi2"); + for (uint32_t i = 0; i <= MAX_CONNECT_ID; i++) { + connected_ids_[i] = NOT_CONNECTED; + } + start_tcp_server(); + DEBUG_PRINTLN("Constructor wifi3"); +} + +bool WiFi_my::start_tcp_server() { + device_->print(SET_WIFI_MODE_COM); + String answer = read_answer(); + if (!answer.startsWith(SET_WIFI_MODE_COM) && !answer.endsWith(POSITIVE_ANSWER)) { + is_server_started_ = false; + return false; + } + DEBUG_PRINTLN("WiFi_my mode was set."); + + device_->print(ENABLE_MULTIPLE_CONNECTION_COM); + answer = read_answer(); + if (!answer.startsWith(ENABLE_MULTIPLE_CONNECTION_COM) && !answer.endsWith(POSITIVE_ANSWER)) { + is_server_started_ = false; + return false; + } + DEBUG_PRINTLN("multiple connection was set."); + + device_->print(SETUP_SERVER_COM); + answer = read_answer(); + if (!answer.startsWith(SETUP_SERVER_COM) && !answer.endsWith(POSITIVE_ANSWER)) { + is_server_started_ = false; + return false; + } + DEBUG_PRINTLN("server started."); + DEBUG_PRINTLN("Port: " + PORT); + device_->print(GET_IP_MAC); + answer = read_answer(); + String ip = answer.substring(answer.indexOf("+CIFSR:APIP,\"") + String("+CIFSR:APIP,\"").length(), + answer.indexOf("+CIFSR:APMAC,") - 3); + DEBUG_PRINTLN("IP: " + ip); + is_server_started_ = true; + return true; +} + +//void WiFi_my::stop_connection(int id) { +// device_->print(DELETE_TCP_CONNECTION + String(char(id)) + EOC); +// String answer = read_answer(); +// if (!answer.endsWith(POSITIVE_ANSWER)) { +// DEBUG_PRINTLN("Error in deleting the connection.(stopConnection method)."); +// } +//} + +String WiFi_my::read_answer() { + char buf[BUFFER_SIZE]; + for (uint32_t i = 0; i < BUFFER_SIZE; i++) { + buf[i] = 0; + } + + //block for not receiving data + Timer timer(MAX_WAIT_ANSWER_MS); + timer.start_or_resume(); + while (!timer.isFinished()) { + if (device_->available()) { + device_->readBytes(buf, BUFFER_SIZE); + break; + } + } + if (timer.isFinished()) + { + DEBUG_PRINTLN("WiFi read timer timeout. ERROR"); + } + + DEBUG_PRINTLN("Read ans: " + String(buf)); + DEBUG_PRINT("Read hex ans: "); + DEBUG_PRINTLNHEX(buf); + return String(buf); +} + +//int WiFi_my::wait_client() { +// String answer = read_answer(); +// String str_number = answer.substring(0, answer.indexOf(",CONNECT")); +// int num = atoi(str_number.c_str()); +// return num; +//} + +bool WiFi_my::is_need_to_read_message() { + if (!is_server_started_) + { + return false; + } + + //DEBUG_PRINTLN("IMPORTANT: " + String((int)'\|')); + //DEBUG_PRINTLN(String(__LINE__)); + char buf[BUFFER_SIZE]; + memset(buf, 0, BUFFER_SIZE); + if (device_->available()) { + device_->readBytes(buf, BUFFER_SIZE); + } + else { +#ifdef DEBUG_ON + static int i = 0; + i++; + if (i > 12000) + { + DEBUG_PRINTLN("From Wifi: " + String(__LINE__)); + i = 0; + } + + if (!data_buffer_.isEmpty()) + { + DEBUG_PRINTLN("Wifi: need to read message"); + } +#endif + return !data_buffer_.isEmpty(); + } + String buf_str(buf); + while (buf_str.startsWith("\r\n")) { + buf_str = buf_str.substring(2); + } + + if (buf_str.length() == 0) + { + return !data_buffer_.isEmpty(); + } + + DEBUG_PRINTLN("Text Buf: "); + DEBUG_PRINTLN(buf_str); + + DEBUG_PRINTLN("Buf: "); + DEBUG_PRINTLNHEX(buf_str); + + //don't lose last command + buf_str += EOC; + + String sub_str = buf_str.substring(0, buf_str.indexOf("\r\n")); + while (buf_str.indexOf("\r\n") != -1) { + //DEBUG_PRINT("SubStr: "); + //DEBUG_PRINTLNHEX(subStr); + if (sub_str.indexOf(",CONNECT") != -1) { + String str_number = sub_str.substring(0, sub_str.indexOf(",CONNECT")); + uint32_t num = str_number.toInt(); + connected_ids_[num] = CONNECTED; + DEBUG_PRINTLN("Connected: " + String(num)); + } + else if (sub_str.indexOf(",CLOSED") != -1) { + String str_number = sub_str.substring(0, sub_str.indexOf(",CLOSED")); + uint32_t num = str_number.toInt(); + connected_ids_[num] = NOT_CONNECTED; + DEBUG_PRINTLN("Disconnected: " + String(num)); + } + else if (sub_str.indexOf(INFO_PREFIX) != -1) { + DEBUG_PRINTLN("WiFi: IPD detect"); + String data = sub_str.substring(sub_str.indexOf(":") + 1); + DEBUG_PRINT("WiFi: data in IPD: "); + DEBUG_PRINTLNHEX(data); + if (data.length()) { + data_buffer_.push(data); + DEBUG_PRINT("Get data: "); + DEBUG_PRINTLNHEX(data); + } + } + //... + + buf_str = buf_str.substring(buf_str.indexOf("\r\n") + 2); + sub_str = buf_str.substring(0, buf_str.indexOf("\r\n")); + } + DEBUG_PRINTLN(String(__LINE__)); + DEBUG_PRINTF("Is data buffer empty: %d\n", data_buffer_.isEmpty()); + + return !data_buffer_.isEmpty(); +} + +String WiFi_my::get_message() { + char buf[BUFFER_SIZE]; + for (uint32_t i = 0; i < BUFFER_SIZE; i++) { + buf[i] = 0; + } + while (true) { + if (device_->available()) { + device_->readBytes(buf, BUFFER_SIZE); + break; + } + } + String data = String(buf); + DEBUG_PRINTLN("Read: " + data); + int infoStartIndex = data.indexOf(":") + 1; + String info = data.substring(infoStartIndex); + return info; +} + +void WiFi_my::write_answer(uint8_t* answer_ptr, int length) { + if (!length || !is_server_started_) { + return; + } + + //remove crc from message + static const int kCrcLength = sizeof(uint16_t); + length -= kCrcLength; + + String command = SEND_BUFFER_COM + length + EOC; // may be space needed.(between command and length.) + device_->print(command); + String answer = read_answer(); + if (!answer.indexOf('>') == -1) { + DEBUG_PRINTLN("Can't send info (method send)"); + is_server_started_ = false; + return; + } + IConnector::write_answer(answer_ptr, length); + answer = read_answer(); + if (!answer.endsWith("SEND OK" + EOC)) { + DEBUG_PRINTLN("Error in answer (method send)"); + } +} + +int WiFi_my::read_message(uint8_t* pointer, int max_length) +{ + if (!is_server_started_) + { + return 0; + } + + static const int kLenSize = 0; + static const int kCrcAndLenSize = 2 + kLenSize; + + if (!data_buffer_.isEmpty()) { + String data = data_buffer_.pop(); + DEBUG_PRINT("FROM VECTOR: "); + DEBUG_PRINTLNHEX(data); + + if (max_length < static_cast(data.length() + kCrcAndLenSize)) + { + DEBUG_PRINTF("Message was so long: %d (buffer size %d)\n", data.length(), max_length); + return 0; + } + + memset(pointer, 0, data.length() + kCrcAndLenSize); + + //length in message now + //memset(pointer, data.length(), kLenSize); + memcpy(pointer + kLenSize, data.c_str(), data.length()); + uint16_t crc16 = crc_calculator_.modbus(pointer, data.length() + kLenSize); + memcpy(pointer + data.length() + kLenSize, &crc16, kCrcAndLenSize - kLenSize); + + return (data.length() + kCrcAndLenSize); + } + return 0; +} \ No newline at end of file diff --git a/code/Arduino/connection/WiFi_my.h b/code/Arduino/connection/WiFi_my.h new file mode 100644 index 0000000..bf00ec2 --- /dev/null +++ b/code/Arduino/connection/WiFi_my.h @@ -0,0 +1,55 @@ +#pragma once +#include + +#include "../utils/Vector.h" +#include "IConnector.h" + +const uint32_t MAX_CONNECT_ID = 4; +const uint32_t CONNECTED = 1; +const uint32_t NOT_CONNECTED = 0; +const uint32_t MAX_WAIT_ANSWER_MS = 3000; + +// COM = command, EOC = end of command. +const String PORT = "333"; +const String LINK_ID = "0"; +const String EOC = "\r\n"; // end of command +const String POSITIVE_ANSWER = "OK" + EOC; +const String NEGATIVE_ANWSER = "ERROR" + EOC; +const String SET_WIFI_MODE_COM = "AT+CWMODE=3" + EOC; +const String ENABLE_MULTIPLE_CONNECTION_COM = "AT+CIPMUX=1" + EOC; +const String SETUP_SERVER_COM = "AT+CIPSERVER=1," + PORT + EOC; +const String SEND_BUFFER_COM = "AT+CIPSENDBUF=" + LINK_ID + ","; +const String DELETE_TCP_CONNECTION = "AT+CIPCLOSE="; +const String GET_IP_MAC = "AT+CIFSR" + EOC; +const String INFO_PREFIX = "+IPD,"; +// port: 333, IP: 192.168.4.1 +class WiFi_my : public IConnector +{ +private: + bool is_inited_ = false; + bool is_server_started_ = false; + Vector data_buffer_; + // 1 - there is connection with this ID, 0 - there is no connection with this ID. (id - is num of element) + uint32_t connected_ids_[MAX_CONNECT_ID + 1]; + FastCRC16 crc_calculator_; + + // port is declareted in constants above. + bool start_tcp_server(); + // if send 5 as id, you will discconect all connections + //void stop_connection(int id); + String read_answer(); + // retrun number of connection + //int wait_client(); + + // synchronous methods + String get_message(); + +public: + + WiFi_my(unsigned long speed); + + bool is_need_to_read_message() override; + // return empty string if there is not data. + int read_message(uint8_t* pointer, int max_length) override; + void write_answer(uint8_t* answer_ptr, int length) override; +}; \ No newline at end of file diff --git a/code/Arduino/management/CommandManager.cpp b/code/Arduino/management/CommandManager.cpp new file mode 100644 index 0000000..7325e4b --- /dev/null +++ b/code/Arduino/management/CommandManager.cpp @@ -0,0 +1,257 @@ +#include "../config/CommandsEnum.h" +#include "../management/MainManager.h" +#include "../utils/ErrorManager.h" +#include "../config/Constants.h" +#include "../connection/DebugSerial.h" + +#include "CommandManager.h" + +CommandManager* CommandManager::manager_ = nullptr; + +CommandManager::CommandManager() +{ +} + +CommandManager::CommandManager(CommandManager&) +{ +} + +String CommandManager::parse_and_execute_command_connected(String command) +{ + String res; + if (command.length() < 2) + { + ErrorManager::get_manager().set_error(); + DEBUG_PRINTLN("Command is too short"); + return res; + } + + switch (command[0]) { + case movementControllerID: + res = run_movement_manager_connected(command); + break; + case sensorsControllerID: + res = run_sensors_manager_connected(command); + break; + case servoControllerID: + res = run_servo_manager_connected(command); + break; + case communicationControllerID: + res = run_commumication_manager_connected(command); + break; + default: + ErrorManager::get_manager().set_error(); + DEBUG_PRINTLN("Cannot detect manager"); + break; + } + return res; +} + +String CommandManager::parse_and_execute_command_not_connected(String command) +{ + ErrorManager::get_manager().set_error(); + if (command.length() > 2) + { + if (command[0] == communicationControllerID && + command[1] == startCommunicationCommand) + { + current_api = static_cast(command[2]); + if (current_api >= min_api && current_api <= max_api) + { + MainManager::get_manager()->set_current_connection(); + ErrorManager::get_manager().reset_error(); + DEBUG_PRINTF("Connected with API %d\n", current_api); + } + else + { + DEBUG_PRINTF("Cannot connect with API %d. Minimum required %d, maximum %d\n", current_api, min_api, max_api); + } + } + else + { + DEBUG_PRINT("Bad command "); + DEBUG_PRINTLNHEX(command.substring(2)); + } + } + return ""; +} + +String CommandManager::run_movement_manager_connected(String command) +{ + String res; + int* input_args = nullptr; + DEBUG_PRINTLN("Movement command"); + + switch (command[1]) { + case track_set_speed: + input_args = parametr_converter.parse_command(command, param_start_pos, Constants::kCommandsDelimetr, 2); + move_controller.set_track_speed(static_cast(input_args[0]), input_args[1]); + break; + case track_all_set_speed: + input_args = parametr_converter.parse_command(command, param_start_pos, Constants::kCommandsDelimetr, 2); + move_controller.set_track_speed(left_track, input_args[0]); + move_controller.set_track_speed(right_track, input_args[1]); + break; + case forward_speed: + input_args = parametr_converter.parse_command(command, param_start_pos, Constants::kCommandsDelimetr, 1); + move_controller.move_forward(input_args[0]); + break; + case clockwise: + input_args = parametr_converter.parse_command(command, param_start_pos, Constants::kCommandsDelimetr, 1); + move_controller.move_clockwose(input_args[0]); + break; + case stop: + move_controller.stop_moving(); + break; + default: + ErrorManager::get_manager().set_error(); + DEBUG_PRINTLN("Cannot detect command"); + break; + } + + if (input_args) + { + delete[] input_args; + } + + return res; +} + +String CommandManager::run_sensors_manager_connected(String command) +{ + String res; + DEBUG_PRINTLN("Sensors command"); + + switch (command[1]) { + case distance_sensor: + res = get_sensor_value(command, distance_sensor_index); + break; + case distance_sensor_all: + res = get_sensor_all_values(distance_sensor_index); + break; + case line_sensor: + res = get_sensor_value(command, line_sensor_index); + break; + case line_sensor_all: + res = get_sensor_all_values(line_sensor_index); + break; + default: + ErrorManager::get_manager().set_error(); + DEBUG_PRINTLN("Cannot detect command"); + break; + } + + return res; +} + +String CommandManager::run_servo_manager_connected(String command) +{ + String res; + int* input_args = nullptr; + int res_num = 0; + DEBUG_PRINTLN("Servo command"); + + switch (command[1]) { + case set_angle: + input_args = parametr_converter.parse_command(command, param_start_pos, Constants::kCommandsDelimetr, 2); + servo_controller.set_servo_degree(static_cast(input_args[0]), input_args[1]); + break; + case get_angle: + input_args = parametr_converter.parse_command(command, param_start_pos, Constants::kCommandsDelimetr, 1); + res_num = servo_controller.get_servo_degree(static_cast(input_args[0])); + res = String(res_num); + break; + default: + ErrorManager::get_manager().set_error(); + DEBUG_PRINTLN("Cannot detect command"); + break; + } + + if (input_args) + { + delete[] input_args; + } + + return res; +} + +String CommandManager::run_commumication_manager_connected(String command) +{ + String res; + DEBUG_PRINTLN("Communication command"); + + switch (command[1]) { + case stopCommunicationCommand: + MainManager::get_manager()->reset_current_connection(); + break; + case refreshConnectionCommunicationCommand: + MainManager::get_manager()->reset_timer(); + break; + default: + ErrorManager::get_manager().set_error(); + DEBUG_PRINTLN("Cannot detect command"); + break; + } + + return res; +} + +String CommandManager::get_sensor_value(String command, SensorManagerIndex sensor_manager_index) +{ + int* input_args = parametr_converter.parse_command(command, param_start_pos, Constants::kCommandsDelimetr, 1); + const int res_num = sensors_controller.get_sensor_value(sensor_manager_index, input_args[0]); + String res = String(res_num); + + if (input_args) + { + delete[] input_args; + } + return res; +} + +String CommandManager::get_sensor_all_values(SensorManagerIndex sensor_manager_index) +{ + int* res_nums = sensors_controller.get_all_sensors_value(sensor_manager_index); + const int amount = sensors_controller.get_amount(sensor_manager_index); + String res = parametr_converter.int_array_to_string(res_nums, amount, Constants::kCommandsDelimetr); + + if (res_nums) + { + delete[] res_nums; + } + + return res; +} + +CommandManager* CommandManager::getManager() +{ + if (!manager_) + { + manager_ = new CommandManager(); + } + return manager_; +} + +String CommandManager::parse_and_execute_command(String command) +{ + String res; + if (!MainManager::get_manager()->is_connected()) + { + res = parse_and_execute_command_not_connected(command); + } + else + { + res = parse_and_execute_command_connected(command); + } + + return res; +} + +void CommandManager::stop_all() +{ + move_controller.stop_moving(); +} + +CommandManager::~CommandManager() +{ +} diff --git a/code/Arduino/management/CommandManager.h b/code/Arduino/management/CommandManager.h new file mode 100644 index 0000000..35efe92 --- /dev/null +++ b/code/Arduino/management/CommandManager.h @@ -0,0 +1,50 @@ +#pragma once + +#include +#include "../peripheral/SensorManager.h" +#include "../peripheral/EngineManager.h" +#include "../peripheral/ServoManager.h" +#include "../config/CommandsEnum.h" +#include "../utils/Converter.h" + +/** + * @brief Peripheral manager class (parse commands and execute it) + * @attention First call of @getManager() method must be in setup() method + */ +class CommandManager +{ + static CommandManager* manager_; + + CommandManager(); + CommandManager(CommandManager&); + ~CommandManager(); + + SensorManager sensors_controller; + EngineManager move_controller; + ServoManager servo_controller; + Converter parametr_converter; + + ApiVersion current_api = startBasicAPI; + const int param_start_pos = 2; + + String parse_and_execute_command_connected(String command); + String parse_and_execute_command_not_connected(String command); + String run_movement_manager_connected(String command); + String run_sensors_manager_connected(String command); + String run_servo_manager_connected(String command); + String run_commumication_manager_connected(String command); + + String get_sensor_value(String command, SensorManagerIndex sensor_manager_index); + String get_sensor_all_values(SensorManagerIndex sensor_manager_index); + +public: + static const ApiVersion min_api = APIWithCRC; + static const ApiVersion max_api = APIWithCRC; + + static CommandManager* getManager(); + + String parse_and_execute_command(String command); + + void stop_all(); +}; + diff --git a/code/Arduino/management/MainManager.cpp b/code/Arduino/management/MainManager.cpp new file mode 100644 index 0000000..759c863 --- /dev/null +++ b/code/Arduino/management/MainManager.cpp @@ -0,0 +1,85 @@ +#include "../utils/ErrorManager.h" +#include "../connection/ConnectionManager.h" +#include "../connection/DebugSerial.h" +#include "../config/Constants.h" +#include "CommandManager.h" + +#include "MainManager.h" + +MainManager* MainManager::manager_ = nullptr; + +MainManager::MainManager() +{ +} + +MainManager::MainManager(MainManager&) +{ +} + +MainManager::~MainManager() +{ +} + +MainManager* MainManager::get_manager() +{ + if (!manager_) + { + manager_ = new MainManager(); + } + + return manager_; +} + +void MainManager::run() +{ + ErrorManager::get_manager().reset_error(); + + String command = ConnectionManager::get_manager()->read_command(); + if (!command.length()) + { + return; + } + + DEBUG_PRINT("Command was getted: "); + DEBUG_PRINTLNHEX(command); + + String answer = CommandManager::getManager()->parse_and_execute_command(command); + + if (ErrorManager::get_manager().is_error_gotten()) + { + ConnectionManager::get_manager()->write_answer(Constants::kBadAnswer); + return; + } + + if (answer.length() > 0) + { + ConnectionManager::get_manager()->write_answer(answer); + } + + ConnectionManager::get_manager()->write_answer(Constants::kGoodAnswer); +} + +void MainManager::stop_all() +{ + CommandManager::getManager()->stop_all(); +} + +void MainManager::reset_current_connection() +{ + ConnectionManager::get_manager()->reset_current_connection(); +} + +void MainManager::set_current_connection() +{ + ConnectionManager::get_manager()->set_current_connection(); +} + +void MainManager::reset_timer() +{ + ConnectionManager::get_manager()->reset_timer(); +} + +bool MainManager::is_connected() +{ + return ConnectionManager::get_manager()->is_connected(); +} diff --git a/code/Arduino/management/MainManager.h b/code/Arduino/management/MainManager.h new file mode 100644 index 0000000..581ca4a --- /dev/null +++ b/code/Arduino/management/MainManager.h @@ -0,0 +1,21 @@ +#pragma once + +class MainManager +{ + static MainManager* manager_; + + MainManager(); + MainManager(MainManager&); + ~MainManager(); + +public: + static MainManager* get_manager(); + + void run(); + + void stop_all(); + void reset_current_connection(); + void set_current_connection(); + void reset_timer(); + bool is_connected(); +}; diff --git a/code/Arduino/peripheral/ConnectionController.cpp b/code/Arduino/peripheral/ConnectionController.cpp new file mode 100644 index 0000000..5a7ef36 --- /dev/null +++ b/code/Arduino/peripheral/ConnectionController.cpp @@ -0,0 +1,180 @@ +#include "../Constants.h" +#include "../CommandsEnum.h" +#include "../connectors/DebugSerial.h" +#include "../utils/Timer.h" + +#include "ConnectionController.h" + +const char ConnectionController::connectCommand[] = { communicationControllerID, startCommunicationCommand, 0 }; +const char ConnectionController::disconnectCommand[] = { communicationControllerID, stopCommunicationCommand, 0 }; +const char ConnectionController::refreshCommand[] = { communicationControllerID, refreshConnectionCommunicationCommand, 0 }; + +ConnectionController::ConnectionController() : connectedAPIversion(startBasicAPI) +{ + usb = new USB(Constants::usb_serial_speed); + wifi = new WiFi_my(); + bluetooth = new Bluetooth(Constants::bluetooth_serial_speed); +} + +ConnectionController::~ConnectionController() +{ + if (usb) + { + delete usb; + } + if (wifi) + { + delete wifi; + } + if (bluetooth) + { + delete bluetooth; + } +} + +void ConnectionController::waitForConnection() +{ + DEBUG_PRINTLN("Arduino tries to found a manager"); + + while (!isConnected) { + //waiting some info + while (!bluetooth->isActive() && !usb->isActive() && !wifi->isActive()) + { + delay(1); + } + + DEBUG_PRINTLN("Info was found"); + + //reading info + if (bluetooth->isActive()) { + device = bluetooth; + DEBUG_PRINTLN("Bluetooth sends something"); + } + else if (wifi->isActive()) { + device = wifi; + DEBUG_PRINTLN("Wifi sends something"); + } + else if (usb->isActive()) { + device = usb; + DEBUG_PRINTLN("USB sends something"); + } + + String readInfo = device->read(); + + //check first part of command (if that command is connection command) + if (readInfo.length() < sizeof (connectCommand) || (readInfo.substring(0, sizeof(connectCommand) - 1) != connectCommand)) + { + DEBUG_PRINT("Bad info: "); + DEBUG_PRINTLNHEX(readInfo); + continue; + } + + readInfo = readInfo.substring(sizeof(connectCommand) - 1); + + //check API version length + if (readInfo.length() != 1) + { + DEBUG_PRINTF("Bad API version. Version was very long: %d symbols\n", readInfo.length()); + continue; + } + + //check API version + connectedAPIversion = static_cast(readInfo[0]); + if (connectedAPIversion > highestAPI || connectedAPIversion < lowestAPI) + { + DEBUG_PRINTF("Bad API version. Was %d, required in [%d, %d] interval\n", connectedAPIversion, lowestAPI, highestAPI); + continue; + } + DEBUG_PRINTF("Connected API version: %d\n", connectedAPIversion); + isConnected = true; + } + + //API v1 & v2 compatibility + if (connectedAPIversion >= APIWithAnswer) + { + device->send("OK"); + } + DEBUG_PRINTLN("Arduino found a manager"); +} + +ConnectingDevice* ConnectionController::getDevice() const +{ + return device; +} + +bool ConnectionController::waitForCommandOnDevice(Timer* timer) +{ + //compatibility with API v1 & v2 + if (connectedAPIversion >= APIWithAutoDiconnect) + { + while (!device->isActive() && timer->getState() != timerState_finished) + { + delay(1); + } + + if (timer->getState() == timerState_finished) + { + return false; + } + } + else + { + while (!device->isActive()) + { + delay(1); + } + } + + return true; +} + +String ConnectionController::getCommand() +{ + if (!isConnected) + { + return ""; + } + + String command; + Timer timer(Constants::waitCommandTimeInMs); + timer.startOrResume(); + do + { + if (!waitForCommandOnDevice(&timer)) + { + isConnected = false; + waitForConnection(); + timer.reset(); + continue; + } + + command = device->read(); + + //API v1 & v2 compatibility + if (connectedAPIversion >= APIWithAnswer) + { + device->send("OK"); + } + + //debug + DEBUG_PRINT("Command: "); + DEBUG_PRINTLNHEX(command); + + if (command == disconnectCommand) + { + isConnected = false; + waitForConnection(); + timer.reset(); + continue; + } + + if (connectedAPIversion >= APIWithAutoDiconnect && command == refreshCommand) + { + timer.reset(); + continue; + } + + break; + } while (true); + return command; +} diff --git a/code/Arduino/peripheral/ConnectionController.h b/code/Arduino/peripheral/ConnectionController.h new file mode 100644 index 0000000..b51bfe5 --- /dev/null +++ b/code/Arduino/peripheral/ConnectionController.h @@ -0,0 +1,33 @@ +#pragma once +#include "../connectors/USB.h" +#include "../connectors/Bluetooth.h" +#include "../connectors/WiFi_my.h" +#include "../CommandsEnum.h" +#include "../utils/Timer.h" + +class ConnectionController +{ + USB* usb = nullptr; + Bluetooth* bluetooth = nullptr; + WiFi_my* wifi = nullptr; + ConnectingDevice *device = nullptr; + + static const char connectCommand[]; + static const char disconnectCommand[]; + static const char refreshCommand[]; + static const StartCommands lowestAPI = startBasicAPI; + static const StartCommands highestAPI = APIWithAutoDiconnect; + + bool isConnected = false; + StartCommands connectedAPIversion; + + bool waitForCommandOnDevice(Timer* timer); + +public: + ConnectionController(); + ~ConnectionController(); + + void waitForConnection(); + ConnectingDevice* getDevice() const; + String getCommand(); +}; diff --git a/code/Arduino/peripheral/DistanceSensorManager.cpp b/code/Arduino/peripheral/DistanceSensorManager.cpp new file mode 100644 index 0000000..245dbe2 --- /dev/null +++ b/code/Arduino/peripheral/DistanceSensorManager.cpp @@ -0,0 +1,54 @@ +#include "../connection/DebugSerial.h" +#include "../config/Constants.h" +#include "DistanceSensorManager.h" + +DistanceSensorManager::DistanceSensorManager() : sensor_driver_(Constants::kDistanceSensorReadPin, 1080) +{ + pinMode(Constants::kDistanceSensorAPin, OUTPUT); + pinMode(Constants::kDistanceSensorBPin, OUTPUT); + pinMode(Constants::kDistanceSensorCPin, OUTPUT); +} + +void DistanceSensorManager::choose_sensor(int number) { + switch (number) { + case 1: + digitalWrite(Constants::kDistanceSensorAPin, HIGH); + digitalWrite(Constants::kDistanceSensorBPin, LOW); + digitalWrite(Constants::kDistanceSensorCPin, LOW); + break; + case 2: + digitalWrite(Constants::kDistanceSensorAPin, LOW); + digitalWrite(Constants::kDistanceSensorBPin, HIGH); + digitalWrite(Constants::kDistanceSensorCPin, HIGH); + break; + case 3: + digitalWrite(Constants::kDistanceSensorAPin, LOW); + digitalWrite(Constants::kDistanceSensorBPin, LOW); + digitalWrite(Constants::kDistanceSensorCPin, HIGH); + break; + case 4: + digitalWrite(Constants::kDistanceSensorAPin, HIGH); + digitalWrite(Constants::kDistanceSensorBPin, LOW); + digitalWrite(Constants::kDistanceSensorCPin, HIGH); + break; + case 5: + digitalWrite(Constants::kDistanceSensorAPin, HIGH); + digitalWrite(Constants::kDistanceSensorBPin, HIGH); + digitalWrite(Constants::kDistanceSensorCPin, HIGH); + break; + default: + break; + } + delay(Constants::kSensorDelay); +} + +int DistanceSensorManager::get_sensor_value(int number) { + DEBUG_PRINTF("Get distance value from sensor %d\n", number); + choose_sensor(number); + return sensor_driver_.distance(); +} + +int DistanceSensorManager::get_amount() +{ + return Constants::kCountDistanceSensors; +} diff --git a/code/Arduino/peripheral/DistanceSensorManager.h b/code/Arduino/peripheral/DistanceSensorManager.h new file mode 100644 index 0000000..8f908de --- /dev/null +++ b/code/Arduino/peripheral/DistanceSensorManager.h @@ -0,0 +1,29 @@ +#pragma once + +#include "IBasicSensorManager.h" +#include "SharpIR.h" + +/** + * @brief Get information from distance sensors. Values are returned in centimeters + */ +class DistanceSensorManager : public IBasicSensorManager +{ +protected: + SharpIR sensor_driver_; + void choose_sensor(int number); + +public: + DistanceSensorManager(); + + /** + * @brief Get sensor value in sentimeters. + * Calculate value by formula: + * res = a / volts + b, + * where + * a, b - constants + * volts - current voltage from sensor pin (mapped to 1023 as max value) + */ + int get_sensor_value(int) override; + int get_amount() override; +}; + diff --git a/code/Arduino/peripheral/EngineManager.cpp b/code/Arduino/peripheral/EngineManager.cpp new file mode 100644 index 0000000..1c4b0ec --- /dev/null +++ b/code/Arduino/peripheral/EngineManager.cpp @@ -0,0 +1,78 @@ +#include "../config/Constants.h" +#include "../connection/DebugSerial.h" +#include "EngineManager.h" + +void EngineManager::manage_track(int speed, const uint8_t enable_pin, const uint8_t straight_pin, const uint8_t reverse_pin) +{ + if (!is_pin_num_good(enable_pin) || !is_pin_num_good(straight_pin) || !is_pin_num_good(reverse_pin)) { + return; + } + + const bool is_forward = (speed >= 0); + speed *= is_forward ? 1 : -1; + speed = (speed > Constants::kMaxSpeed) ? Constants::kMaxSpeed : speed; + + analogWrite(enable_pin, speed); + digitalWrite(straight_pin, is_forward ? HIGH : LOW); + digitalWrite(reverse_pin, is_forward ? LOW : HIGH); +} + +bool EngineManager::is_pin_num_good(const uint8_t pin) +{ + return (pin <= max_pin_num); +} + +EngineManager::EngineManager() +{ + pinMode(Constants::kLeftEngineEnable, OUTPUT); + pinMode(Constants::kLeftEngineStraightPin, OUTPUT); + pinMode(Constants::kLeftEngineReversePin, OUTPUT); + pinMode(Constants::kRightEngineStraightPin, OUTPUT); + pinMode(Constants::kRightEngineReversePin, OUTPUT); + pinMode(Constants::kRightEngineEnable, OUTPUT); + + stop_moving(); +} + +void EngineManager::move_forward(const int speed) { + DEBUG_PRINTF("Move forward with speed %d\n", speed); + left_track_control(speed); + right_track_control(speed); +} + +void EngineManager::move_clockwose(const int speed) { + DEBUG_PRINTF("Turn right with speed %d\n", speed); + left_track_control(speed); + right_track_control(-speed); +} + +void EngineManager::set_track_speed(TrackIndex track_index, const int speed) +{ + DEBUG_PRINTF("Set track %d speed %d\n", track_index, speed); + if (track_index == left_track) + { + left_track_control(speed); + } + else + { + right_track_control(speed); + } +} + +void EngineManager::stop_moving() { + DEBUG_PRINTF("Stop moving\n"); + set_track_speed(left_track, Constants::kMinSpeed); + set_track_speed(right_track, Constants::kMinSpeed); +} + +void EngineManager::left_track_control(const int speed) { + manage_track(speed, Constants::kLeftEngineEnable, Constants::kLeftEngineStraightPin, Constants::kLeftEngineReversePin); +} + +void EngineManager::right_track_control(const int speed) { + manage_track(speed, Constants::kRightEngineEnable, Constants::kRightEngineStraightPin, Constants::kRightEngineReversePin); +} + +EngineManager::~EngineManager() +{ +} diff --git a/code/Arduino/peripheral/EngineManager.h b/code/Arduino/peripheral/EngineManager.h new file mode 100644 index 0000000..4bd410f --- /dev/null +++ b/code/Arduino/peripheral/EngineManager.h @@ -0,0 +1,40 @@ +#pragma once + +#include + +#include "../config/CommandsEnum.h" + +class EngineManager +{ + const uint8_t max_pin_num = A15; + + /** + * @brief All track control + * + * @param speed Speed of control (must be in [-255, 255] ([-@MAX_SPEED, @MAX_SPEED]) range) + * @param enable_pin Pin to enable track + * @param straight_pin Pin to forward direction (LOW = enable forward direction) + * @param reverse_pin Pin to backward direction (LOW = enable backward direction) + */ + void manage_track(int speed, const uint8_t enable_pin, const uint8_t straight_pin, const uint8_t reverse_pin); + + /** + * @brief Validate pin number, used in @manage_track method + * + * @param pin Pin number to validate + * + * @return true, if pin number is valid, else false + */ + bool is_pin_num_good(const uint8_t pin); + void left_track_control(const int speed); + void right_track_control(const int speed); + +public: + EngineManager(); + ~EngineManager(); + + void move_forward(const int speed); + void move_clockwose(const int speed); + void set_track_speed(TrackIndex track_index, const int speed); + void stop_moving(); +}; diff --git a/code/Arduino/peripheral/IBasicSensorManager.h b/code/Arduino/peripheral/IBasicSensorManager.h new file mode 100644 index 0000000..5407e49 --- /dev/null +++ b/code/Arduino/peripheral/IBasicSensorManager.h @@ -0,0 +1,14 @@ +#pragma once + +/** + * @brief Basic sensor manager interface (abstract class) + */ +class IBasicSensorManager +{ +public: + virtual ~IBasicSensorManager() = default; + + virtual int get_sensor_value(int) = 0; + virtual int get_amount() = 0; +}; + diff --git a/code/Arduino/peripheral/LineSensorManager.cpp b/code/Arduino/peripheral/LineSensorManager.cpp new file mode 100644 index 0000000..70e20d2 --- /dev/null +++ b/code/Arduino/peripheral/LineSensorManager.cpp @@ -0,0 +1,53 @@ +#include "../connection/DebugSerial.h" +#include "../config/Constants.h" +#include "LineSensorManager.h" + +LineSensorManager::LineSensorManager() +{ + pinMode(Constants::kLineSensorAPin, OUTPUT); + pinMode(Constants::kLineSensorBPin, OUTPUT); + pinMode(Constants::kLineSensorCPin, OUTPUT); +} + +void LineSensorManager::choose_sensor(int number) { + switch (number) { + case 1: + digitalWrite(Constants::kLineSensorAPin, LOW); + digitalWrite(Constants::kLineSensorBPin, LOW); + digitalWrite(Constants::kLineSensorCPin, HIGH); + break; + case 2: + digitalWrite(Constants::kLineSensorAPin, HIGH); + digitalWrite(Constants::kLineSensorBPin, HIGH); + digitalWrite(Constants::kLineSensorCPin, HIGH); + break; + case 3: + digitalWrite(Constants::kLineSensorAPin, HIGH); + digitalWrite(Constants::kLineSensorBPin, LOW); + digitalWrite(Constants::kLineSensorCPin, HIGH); + break; + case 4: + digitalWrite(Constants::kLineSensorAPin, LOW); + digitalWrite(Constants::kLineSensorBPin, HIGH); + digitalWrite(Constants::kLineSensorCPin, HIGH); + break; + case 5: + digitalWrite(Constants::kLineSensorAPin, HIGH); + digitalWrite(Constants::kLineSensorBPin, LOW); + digitalWrite(Constants::kLineSensorCPin, LOW); + break; + default: + break; + } +} + +int LineSensorManager::get_sensor_value(int number) { + DEBUG_PRINTF("Get line value from sensor %d\n", number); + choose_sensor(number); + return (analogRead(Constants::kLineSensorReadPin) > static_cast(Constants::kMinimalLineBound)) ? 1 : 0; +} + +int LineSensorManager::get_amount() +{ + return Constants::kCountLineSensors; +} diff --git a/code/Arduino/peripheral/LineSensorManager.h b/code/Arduino/peripheral/LineSensorManager.h new file mode 100644 index 0000000..f96e036 --- /dev/null +++ b/code/Arduino/peripheral/LineSensorManager.h @@ -0,0 +1,19 @@ +#pragma once + +#include "IBasicSensorManager.h" + +/** + * @brief Get information from line sensors. Line values are returned as @AreaType values + */ +class LineSensorManager : public IBasicSensorManager +{ +protected: + void choose_sensor(int); + +public: + LineSensorManager(); + + int get_sensor_value(int) override; + int get_amount() override; +}; + diff --git a/code/Arduino/peripheral/SensorManager.cpp b/code/Arduino/peripheral/SensorManager.cpp new file mode 100644 index 0000000..084fb63 --- /dev/null +++ b/code/Arduino/peripheral/SensorManager.cpp @@ -0,0 +1,49 @@ +#include "../config/CommandsEnum.h" +#include "SensorManager.h" +#include "DistanceSensorManager.h" +#include "LineSensorManager.h" + +IBasicSensorManager*& SensorManager::get_manager(SensorManagerIndex sensor_manager_index) +{ + return sensor_managers[sensor_manager_index]; +} + +SensorManager::SensorManager() : managers_num(2) +{ + sensor_managers = new IBasicSensorManager*[managers_num]; + get_manager(line_sensor_index) = new LineSensorManager(); + get_manager(distance_sensor_index) = new DistanceSensorManager(); +} + +SensorManager::~SensorManager() +{ + if (sensor_managers) { + for (int i = 0; i < managers_num; ++i) { + if (sensor_managers[i]) { + delete sensor_managers[i]; + } + } + + delete[] sensor_managers; + } +} + +int SensorManager::get_sensor_value(SensorManagerIndex sensor_manager_index, int sensor_number) +{ + return get_manager(sensor_manager_index)->get_sensor_value(sensor_number); +} + +int* SensorManager::get_all_sensors_value(SensorManagerIndex sensor_manager_index) +{ + const int sensor_amount = get_amount(sensor_manager_index); + int* arr = new int[sensor_amount]; + for (int i = 0; i < sensor_amount; i++) { + arr[i] = get_sensor_value(sensor_manager_index, i); + } + return arr; +} + +int SensorManager::get_amount(SensorManagerIndex sensor_manager_index) +{ + return get_manager(sensor_manager_index)->get_amount(); +} diff --git a/code/Arduino/peripheral/SensorManager.h b/code/Arduino/peripheral/SensorManager.h new file mode 100644 index 0000000..9efba59 --- /dev/null +++ b/code/Arduino/peripheral/SensorManager.h @@ -0,0 +1,25 @@ +#pragma once + +#include "../config/CommandsEnum.h" +#include "IBasicSensorManager.h" + +/** + * @brief Get information from sensors: line and distance. Distance values are returned in centimeters + */ +class SensorManager +{ + const int managers_num; + IBasicSensorManager** sensor_managers; + + IBasicSensorManager*& get_manager(SensorManagerIndex sensor_manager_index); + +public: + SensorManager(); + ~SensorManager(); + + int get_sensor_value(SensorManagerIndex sensor_manager_index, int sensor_number); + int* get_all_sensors_value(SensorManagerIndex sensor_manager_index); + + int get_amount(SensorManagerIndex sensor_manager_index); +}; + diff --git a/code/Arduino/peripheral/ServoManager.cpp b/code/Arduino/peripheral/ServoManager.cpp new file mode 100644 index 0000000..bb9668e --- /dev/null +++ b/code/Arduino/peripheral/ServoManager.cpp @@ -0,0 +1,49 @@ +#include "../config/CommandsEnum.h" +#include "../connection/DebugSerial.h" +#include "../config/Constants.h" +#include "ServoManager.h" + +ServoManager::ServoManager() +{ + init(); +} + +void ServoManager::init() { + horizontal_servo.attach(Constants::kServoHorizontalPin); + vertical_servo.attach(Constants::kServoVerticalPin); + + set_servo_degree(xy_plane, 0); + set_servo_degree(xz_plane, 0); +} + +Servo* ServoManager::convert_servo_id(const ServoIndex servo_id) +{ + if (servo_id == xy_plane) + { + return &horizontal_servo; + } + if (servo_id == xz_plane) + { + return &vertical_servo; + } + + DEBUG_PRINTF("Bad servo index: %d", servo_id); + return &vertical_servo; +} + +ServoManager::~ServoManager() +{ +} + +int ServoManager::get_servo_degree(ServoIndex servo_id) +{ + DEBUG_PRINTF("Get %d servo angle\n", servo_id); + return convert_servo_id(servo_id)->read(); +} + +void ServoManager::set_servo_degree(ServoIndex servo_id, int degree) +{ + DEBUG_PRINTF("Set %d servo to angle %d\n", servo_id, degree); + convert_servo_id(servo_id)->write(degree); + delay(Constants::kServoDelay); +} diff --git a/code/Arduino/peripheral/ServoManager.h b/code/Arduino/peripheral/ServoManager.h new file mode 100644 index 0000000..120b261 --- /dev/null +++ b/code/Arduino/peripheral/ServoManager.h @@ -0,0 +1,23 @@ +#pragma once +#include + +/** + * @brief Servo controller for 2 axes: X & Y + * @attention Create only one object of that class. And create it in setup() method only + */ +class ServoManager +{ + Servo horizontal_servo; + Servo vertical_servo; + + void init(); + Servo* convert_servo_id(const ServoIndex servo_id); + +public: + ServoManager(); + ~ServoManager(); + + int get_servo_degree(ServoIndex servo_id); + void set_servo_degree(ServoIndex servo_id, int degree); +}; + diff --git a/code/Arduino/peripheral/SharpIR.cpp b/code/Arduino/peripheral/SharpIR.cpp new file mode 100644 index 0000000..3a68633 --- /dev/null +++ b/code/Arduino/peripheral/SharpIR.cpp @@ -0,0 +1,151 @@ +/* + SharpIR + + Arduino library for retrieving distance (in cm) from the analog GP2Y0A21Y and GP2Y0A02YK + + From an original version of Dr. Marcal Casas-Cartagena (marcal.casas@gmail.com) + + Version : 1.0 : Guillaume Rico + + Remove average and use median + + Definition of number of sample in .h + + Define IR pin as input + + Version : 1.1 : Thibaut Mauon + + Add SHARP GP2Y0A710K0F for 100cm to 500cm by Thibaut Mauron + + https://github.com/guillaume-rico/SharpIR + + Original comment from Dr. Marcal Casas-Cartagena : + The Sahrp IR sensors are cheap but somehow unreliable. I've found that when doing continous readings to a + fix object, the distance given oscilates quite a bit from time to time. For example I had an object at + 31 cm. The readings from the sensor were mainly steady at the correct distance but eventually the distance + given dropped down to 25 cm or even 16 cm. That's quite a bit and for some applications it is quite + unacceptable. I checked the library http://code.google.com/p/gp2y0a21yk-library/ by Jeroen Doggen + (jeroendoggen@gmail.com) and what the author was doing is to take a bunch of readings and give an average of them + + The present library works similary. It reads a bunch of readings (avg), it checks if the current reading + differs a lot from the previous one (tolerance) and if it doesn't differ a lot, it takes it into account + for the mean distance. + The distance is calculated from a formula extracted from the graphs on the sensors datasheets + After some tests, I think that a set of 20 to 25 readings is more than enough to get an accurate distance + Reading 25 times and return a mean distance takes 53 ms. For my application of the sensor is fast enough. + This library has the formulas to work with the GP2Y0A21Y and the GP2Y0A02YK sensors but exanding it for + other sensors is easy enough. +*/ + +#ifdef Arduino + #include "Arduino.h" +#elif defined(SPARK) + #include "Particle.h" + #include "math.h" +#endif +#include "SharpIR.h" + +// Initialisation function +// + irPin : is obviously the pin where the IR sensor is attached +// + sensorModel is a int to differentiate the two sensor models this library currently supports: +// > 1080 is the int for the GP2Y0A21Y and +// > 20150 is the int for GP2Y0A02YK and +// > 100500 is the long for GP2Y0A710K0F +// The numbers reflect the distance range they are designed for (in cm) +SharpIR::SharpIR(int irPin, long sensorModel) { + + _irPin=irPin; + _model=sensorModel; + + // Define pin as Input + pinMode (_irPin, INPUT); + + #ifdef ARDUINO + analogReference(DEFAULT); + #endif +} + +// Sort an array +void SharpIR::sort(int a[], int size) { + for(int i=0; i<(size-1); i++) { + bool flag = true; + for(int o=0; o<(size-(i+1)); o++) { + if(a[o] > a[o+1]) { + int t = a[o]; + a[o] = a[o+1]; + a[o+1] = t; + flag = false; + } + } + if (flag) break; + } +} + +// Read distance and compute it +int SharpIR::distance() { + + int ir_val[NB_SAMPLE]; + int distanceCM; + float current; + + + for (int i=0; i 3300) { + //false data + distanceCM = 0; + } else { + distanceCM = 1.0 / (((current - 1125.0) / 1000.0) / 137.5); + } + } + + return distanceCM; +} + + + + diff --git a/code/Arduino/peripheral/SharpIR.h b/code/Arduino/peripheral/SharpIR.h new file mode 100644 index 0000000..d5f6788 --- /dev/null +++ b/code/Arduino/peripheral/SharpIR.h @@ -0,0 +1,40 @@ +/* + SharpIR + + Arduino library for retrieving distance (in cm) from the analog GP2Y0A21Y and GP2Y0A02YK + + From an original version of Dr. Marcal Casas-Cartagena (marcal.casas@gmail.com) + + Version : 1.0 : Guillaume Rico + + https://github.com/guillaume-rico/SharpIR + +*/ + +#ifndef SharpIR_h +#define SharpIR_h + +#define NB_SAMPLE 25 + +#ifdef ARDUINO + #include "Arduino.h" +#elif defined(SPARK) + #include "Particle.h" +#endif + +class SharpIR +{ + public: + + SharpIR (int irPin, long sensorModel); + int distance(); + + private: + + void sort(int a[], int size); + + int _irPin; + long _model; +}; + +#endif diff --git a/code/Arduino/trackPlatform.ino b/code/Arduino/trackPlatform.ino index cf94e21..573f1f4 100644 --- a/code/Arduino/trackPlatform.ino +++ b/code/Arduino/trackPlatform.ino @@ -1,43 +1,29 @@ -#include "Constants.h" -#include "ConnectingDevice.h" -#include "Bluetooth.h" -#include "WiFi.h" -#include "SoftwareSerial.h" -#include "CommandsController.h" -#include "ServoController.h" - -Constants constants; -Bluetooth bluetooth(constants.bluetooth_RX, constants.bluetooth_TX, constants.bluetooth_serial_speed); -WiFi wifi(constants.wifi_RX, constants.wifi_TX, constants.wifi_serial_speed); -ConnectingDevice *device; -CommandsController controller; -ServoController servoController; - -bool connected = false; +#include +#include +#include +#include +#include +#include "connection/DebugSerial.h" +#include "management/MainManager.h" +#include "management/CommandManager.h" +#include "connection/ConnectionManager.h" void setup() { - servoController.init(); + DEBUG_PRINTF("Firmware was compiled on %s %s\n", __DATE__, __TIME__); + DEBUG_PRINTF("Supports API from %d to %d\n", CommandManager::min_api, CommandManager::max_api); + + DEBUG_PRINTLN("Trying to start Arduino"); - while (!connected) { - if (bluetooth.isActive()) { - connected = true; - device = &bluetooth; - } - else if (wifi.isActive()) { - connected = true; - device = &wifi; - } - } + // First init of static fields + MainManager::get_manager(); + ConnectionManager::get_manager(); + CommandManager::getManager(); + + DEBUG_PRINTLN("Arduino was started"); } void loop() -{ - delay(100); //for sending commands from mobile - String command = device->read(); - if (command[0] == servoControllerID) { - servoController.exec(device, command); - } else { - controller.handle(device, device->read()); - } +{ + MainManager::get_manager()->run(); } diff --git a/code/Arduino/trackPlatform.vcxproj b/code/Arduino/trackPlatform.vcxproj index b2db8b8..6fa02b7 100644 --- a/code/Arduino/trackPlatform.vcxproj +++ b/code/Arduino/trackPlatform.vcxproj @@ -49,10 +49,10 @@ Level3 Disabled true - C:\Program Files (x86)\Arduino\hardware\arduino\avr\libraries\SoftwareSerial\src;C:\Program Files (x86)\Arduino\libraries\Servo\src;C:\Program Files (x86)\Arduino\libraries;C:\Program Files (x86)\Arduino\hardware\arduino\avr\libraries;C:\Users\Mikhail\Documents\Arduino\libraries;C:\Program Files (x86)\Arduino\hardware\arduino\avr\cores\arduino;C:\Program Files (x86)\Arduino\hardware\arduino\avr\variants\mega;$(ProjectDir)..\Arduino;C:\Program Files (x86)\Arduino\hardware\tools\avr\avr\include\;C:\Program Files (x86)\Arduino\hardware\tools\avr\avr\include\avr\;C:\Program Files (x86)\Arduino\hardware\tools\avr\lib\gcc\avr\4.8.1\include;%(AdditionalIncludeDirectories) + C:\Program Files (x86)\Arduino\libraries\Servo\src;C:\Program Files (x86)\Arduino\hardware\arduino\avr\libraries\SoftwareSerial\src;C:\Program Files (x86)\Arduino\libraries;C:\Program Files (x86)\Arduino\hardware\arduino\avr\libraries;C:\Users\Kimentii\Documents\Arduino\libraries;C:\Program Files (x86)\Arduino\hardware\arduino\avr\cores\arduino;C:\Program Files (x86)\Arduino\hardware\arduino\avr\variants\mega;$(ProjectDir)..\Arduino;C:\Program Files (x86)\Arduino\hardware\tools\avr\avr\include\;C:\Program Files (x86)\Arduino\hardware\tools\avr\avr\include\avr\;C:\Program Files (x86)\Arduino\hardware\tools\avr\lib\gcc\avr\4.8.1\include;C:\Program Files (x86)\Arduino\hardware\tools\avr\lib\gcc\avr\4.9.2\include;C:\Program Files (x86)\Arduino\hardware\tools\avr\lib\gcc\avr\4.9.3\include;%(AdditionalIncludeDirectories) $(ProjectDir)__vm\.Arduino.vsarduino.h;%(ForcedIncludeFiles) false - __AVR_ATmega2560__;_VMDEBUG=1;F_CPU=16000000L;ARDUINO=10801;ARDUINO_AVR_MEGA2560;ARDUINO_ARCH_AVR;__cplusplus=201103L;%(PreprocessorDefinitions) + __AVR_ATmega2560__;_VMDEBUG=1;F_CPU=16000000L;ARDUINO=10804;ARDUINO_AVR_MEGA2560;ARDUINO_ARCH_AVR;__cplusplus=201103L;_VMICRO_INTELLISENSE;%(PreprocessorDefinitions) true @@ -65,10 +65,10 @@ true true true - C:\Program Files (x86)\Arduino\hardware\arduino\avr\libraries\SoftwareSerial\src;C:\Program Files (x86)\Arduino\libraries;C:\Program Files (x86)\Arduino\hardware\arduino\avr\libraries;C:\Users\Mikhail\Documents\Arduino\libraries;C:\Program Files (x86)\Arduino\hardware\arduino\avr\cores\arduino;C:\Program Files (x86)\Arduino\hardware\arduino\avr\variants\mega;$(ProjectDir)..\Arduino;C:\Program Files (x86)\Arduino\hardware\tools\avr\avr\include\;C:\Program Files (x86)\Arduino\hardware\tools\avr\avr\include\avr\;C:\Program Files (x86)\Arduino\hardware\tools\avr\lib\gcc\avr\4.8.1\include;%(AdditionalIncludeDirectories) + C:\Users\Kimentii\Documents\Arduino\libraries\FastCRC-master;C:\Program Files (x86)\Arduino\libraries\Servo\src;C:\Program Files (x86)\Arduino\hardware\arduino\avr\libraries\SoftwareSerial\src;C:\Program Files (x86)\Arduino\libraries;C:\Program Files (x86)\Arduino\hardware\arduino\avr\libraries;C:\Users\Kimentii\Documents\Arduino\libraries;C:\Program Files (x86)\Arduino\hardware\arduino\avr\cores\arduino;C:\Program Files (x86)\Arduino\hardware\arduino\avr\variants\mega;$(ProjectDir)..\Arduino;C:\Program Files (x86)\Arduino\hardware\tools\avr\avr\include\;C:\Program Files (x86)\Arduino\hardware\tools\avr\avr\include\avr\;C:\Program Files (x86)\Arduino\hardware\tools\avr\lib\gcc\avr\4.8.1\include;C:\Program Files (x86)\Arduino\hardware\tools\avr\lib\gcc\avr\4.9.2\include;C:\Program Files (x86)\Arduino\hardware\tools\avr\lib\gcc\avr\4.9.3\include;%(AdditionalIncludeDirectories) $(ProjectDir)__vm\.Arduino.vsarduino.h;%(ForcedIncludeFiles) false - __AVR_ATmega2560__;F_CPU=16000000L;ARDUINO=10801;ARDUINO_AVR_MEGA2560;ARDUINO_ARCH_AVR;__cplusplus=201103L;%(PreprocessorDefinitions) + __AVR_ATmega2560__;F_CPU=16000000L;ARDUINO=10804;ARDUINO_AVR_MEGA2560;ARDUINO_ARCH_AVR;__cplusplus=201103L;_VMICRO_INTELLISENSE;%(PreprocessorDefinitions) true @@ -85,30 +85,50 @@ - - - - - - - + + + + + + + + + + + + + + + + - - - + + + + + - - - - - - - - - + + + + + + + + + + + + + + + + + + @@ -121,7 +141,7 @@ - + \ No newline at end of file diff --git a/code/Arduino/trackPlatform.vcxproj.filters b/code/Arduino/trackPlatform.vcxproj.filters index f8efdf5..f27af4b 100644 --- a/code/Arduino/trackPlatform.vcxproj.filters +++ b/code/Arduino/trackPlatform.vcxproj.filters @@ -1,10 +1,6 @@  - - {4FC737F1-C7A5-4376-A066-2A32D752A2FF} - cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx - {93995380-89BD-4b04-88EB-625FBE52EBFB} h;hh;hpp;hxx;hm;inl;inc;xsd @@ -13,6 +9,57 @@ {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + {8e5e8e86-61de-4400-bc87-9882d23f80b0} + + + {5a05d265-b32e-4399-9fbd-931b3b0be584} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {0331c73c-5716-43bd-a435-2ed6e0b5999b} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {7492051d-9540-415b-b623-46b80c5f0577} + + + {9ab2f623-714d-45f8-bddf-f73617228341} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {764c9bee-87ce-4cfc-9000-81d3bd8a32a0} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {db8a3430-0759-4521-b1c4-3a54a7982dbe} + + + {1ef73a08-0bf9-43fd-a993-e89ddf728bca} + + + {2a9ef8d7-251c-42b3-9d48-b1de5e4eea6c} + + + {74b21982-b2e8-4edf-9736-a64fe4f15db4} + + + {1977162e-941e-4830-897c-6f5f9e48bd2a} + + + {90908eb7-ec64-40b2-aff2-a99bc208f526} + + + {d18e222c-a964-4c1b-af76-c7e6c7c79696} + + + {59c1c582-bece-4678-8894-1f186df97c5b} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {4d8737a4-6736-4d31-803f-f0f98e318ba5} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + @@ -21,70 +68,130 @@ Header Files - - Header Files - Header Files - + Header Files - - Header Files + + utils\header - - Header Files + + utils\header - - Header Files + + peripheral\header - - Header Files + + peripheral\header - - Header Files + + peripheral\header - - Header Files + + peripheral\header - - Header Files + + peripheral\header - - Header Files + + peripheral\header - - Header Files + + config\header + + + config\header + + + management\header + + + connection\header + + + connection\header + + + connection + + + connection\header + + + connection\header + + + utils\header + + + management\header + + + utils\header + + + connection\header + + + peripheral\header - - Source Files + + utils\source + + + peripheral\source + + + peripheral\source + + + peripheral\source + + + peripheral\source + + + peripheral\source + + + config\source + + + management\source + + + connection\source + + + connection\source - - Source Files + + connection - - Source Files + + connection\source - - Source Files + + connection\source - - Source Files + + utils\source - - Source Files + + management\source - - Source Files + + utils\source - - Source Files + + connection\source - - Source Files + + peripheral\source diff --git a/code/Arduino/utils/Converter.cpp b/code/Arduino/utils/Converter.cpp new file mode 100644 index 0000000..ae59695 --- /dev/null +++ b/code/Arduino/utils/Converter.cpp @@ -0,0 +1,53 @@ +#include "Converter.h" + +Converter::Converter() { + +} + + +int* Converter::parse_command(String command, int begin, char delimetr, int params_num) { + int* arr = new int[params_num]; + // clean all allocated memory (can use memset from cstdlib) + for (int i = 0; i < params_num; ++i) + { + arr[i] = 0; + } + + command = command.substring(begin); + begin = 0; + int delimetr_pos = command.indexOf(delimetr); + for (int i = 0; (i < params_num); i++) { + if ((delimetr_pos < 0)) + { + arr[i] = command.substring(begin).toInt(); + break; + } + arr[i] = command.substring(begin, delimetr_pos).toInt(); + command = command.substring(delimetr_pos + 1); + begin = 0; + delimetr_pos = command.indexOf(delimetr); + } + return arr; +} + +int Converter::parse_command(String command, int begin, int end) { + return command.substring(begin, end).toInt(); +} + + +String Converter::int_array_to_string(int* arr, int size, char delimiter) { + String str; + for (int i = 0; i < size; i++) { + if (i > 0) + { + str += delimiter; + } + str += String(arr[i]); + } + return str; +} + + +Converter::~Converter() { + +} \ No newline at end of file diff --git a/code/Arduino/utils/Converter.h b/code/Arduino/utils/Converter.h new file mode 100644 index 0000000..3c560b1 --- /dev/null +++ b/code/Arduino/utils/Converter.h @@ -0,0 +1,13 @@ +#pragma once +#include + +class Converter +{ +public: + Converter(); + int* parse_command(String command, int begin, char delimetr, int params_num); + int parse_command(String command, int begin, int end); + + String int_array_to_string(int* arr, int size, char delimiter); + ~Converter(); +}; diff --git a/code/Arduino/utils/ErrorManager.cpp b/code/Arduino/utils/ErrorManager.cpp new file mode 100644 index 0000000..5c747e1 --- /dev/null +++ b/code/Arduino/utils/ErrorManager.cpp @@ -0,0 +1,35 @@ +#include "ErrorManager.h" + +ErrorManager ErrorManager::manager; + +ErrorManager::ErrorManager() +{ +} + +ErrorManager::ErrorManager(ErrorManager&) +{ +} + +ErrorManager::~ErrorManager() +{ +} + +ErrorManager& ErrorManager::get_manager() +{ + return manager; +} + +void ErrorManager::set_error() +{ + is_error_now = true; +} + +void ErrorManager::reset_error() +{ + is_error_now = false; +} + +bool ErrorManager::is_error_gotten() const +{ + return is_error_now; +} diff --git a/code/Arduino/utils/ErrorManager.h b/code/Arduino/utils/ErrorManager.h new file mode 100644 index 0000000..7f76567 --- /dev/null +++ b/code/Arduino/utils/ErrorManager.h @@ -0,0 +1,19 @@ +#pragma once + +class ErrorManager +{ + static ErrorManager manager; + + ErrorManager(); + ErrorManager(ErrorManager &); + ~ErrorManager(); + + bool is_error_now = false; + +public: + static ErrorManager& get_manager(); + + void set_error(); + void reset_error(); + bool is_error_gotten() const; +}; diff --git a/code/Arduino/utils/Timer.cpp b/code/Arduino/utils/Timer.cpp new file mode 100644 index 0000000..95a81cb --- /dev/null +++ b/code/Arduino/utils/Timer.cpp @@ -0,0 +1,102 @@ +#include "../connection/DebugSerial.h" + +#include "Timer.h" + +void Timer::update_state() +{ + if (state == timerState_started) + { + auto current_ms = millis(); + if (static_cast(current_ms - startTime_ms) >= timeToSet_ms) + { + state = timerState_finished; + } + } +} + +Timer::Timer(uint32_t timeToSet) : startTime_ms(0), timeToSet_ms(timeToSet), passedTime_ms(0), state(timerState_stopped) +{ +} + +void Timer::start_or_resume() +{ + switch (state) + { + case timerState_paused: { + startTime_ms = millis() - passedTime_ms; + passedTime_ms = 0; + state = timerState_started; + break; + } + case timerState_stopped: { + DEBUG_PRINTLN("Timer start"); + startTime_ms = millis(); + state = timerState_started; + break; + } + default: { break; } + } +} + +void Timer::stop() +{ + switch (state) + { + case timerState_started: + case timerState_paused: { + state = timerState_stopped; + break; + } + default: { break; } + } +} + +void Timer::reset() +{ + switch (state) + { + case timerState_started: { + startTime_ms = millis(); + break; + } + case timerState_paused: { + passedTime_ms = 0; + break; + } + case timerState_finished: { + state = timerState_stopped; + break; + } + default: { break; } + } +} + +void Timer::pause() +{ + switch (state) + { + case timerState_started: { + passedTime_ms = millis() - startTime_ms; + state = timerState_paused; + break; + } + default: { break; } + } +} + +void Timer::setSetTime(uint32_t timeToSet) +{ + timeToSet_ms = timeToSet; + update_state(); +} + +TimerState Timer::getState() +{ + update_state(); + return state; +} + +bool Timer::isFinished() +{ + return (getState() == timerState_finished); +} diff --git a/code/Arduino/utils/Timer.h b/code/Arduino/utils/Timer.h new file mode 100644 index 0000000..77379b8 --- /dev/null +++ b/code/Arduino/utils/Timer.h @@ -0,0 +1,68 @@ +#pragma once + +#include + +enum TimerState { + timerState_none, + timerState_started, + timerState_paused, + timerState_stopped, + timerState_finished +}; + +class Timer +{ + uint32_t startTime_ms; + uint32_t timeToSet_ms; + uint32_t passedTime_ms; //used only to pause timer + TimerState state; + +protected: + /** + * @brief Updates current state information + */ + void update_state(); + +public: + /** + * @brief Creates timer and sets + * + * @param timeToSet Time to set timer in milliseconds + */ + Timer(uint32_t timeToSet); + + /** + * @brief Starts or resumes setting timer + */ + void start_or_resume(); + /** + * @brief Stop setting timer and resets time to beginning value + * @warning Cannot stop finished timer (it will not change state) + */ + void stop(); + /** + * @brief Resets timer (resets time to require to set timer to beginnig value, but not pause/stop it) + * @warning If timer was finished before, it will be in stopped state + */ + void reset(); + /** + * @brief Pause setting timer + */ + void pause(); + /** + * @brief Sets time to set to timer, but not reset timer (reset it manual, if require) + * + * @param timeToSet New time to set timer in milliseconds + */ + void setSetTime(uint32_t timeToSet); + /** + * @brief Checks timeout and gets timer state + * @return State of timer + */ + TimerState getState(); + /** + * @brief Checks timeout and gets is timer setted + * @return true, if timer setted/finished (time were passed), else false + */ + bool isFinished(); +}; diff --git a/code/Arduino/utils/Vector.h b/code/Arduino/utils/Vector.h new file mode 100644 index 0000000..09a18b9 --- /dev/null +++ b/code/Arduino/utils/Vector.h @@ -0,0 +1,90 @@ +#pragma once +#include "../connection/DebugSerial.h" + +template +class Vector +{ + template + struct Node + { + T1 obj; + Node* next = nullptr; + }; + + Node* begin = nullptr; + Node* end = nullptr; +public: + ~Vector(); + + void push(const T& t); + T pop(); + + bool isEmpty() const; +}; + +template +Vector::~Vector() +{ + while (!isEmpty()) + { + pop(); + } +} + +template +void Vector::push(const T& t) +{ + // creating new block + Node * newEnd = new Node; + if (!newEnd) + { + DEBUG_PRINTLN("Cannot allocate memory for new vector element"); + return; + } + + newEnd->obj = t; + + // linking new block + if (begin == nullptr) + { + begin = end = newEnd; + } + else + { + end->next = newEnd; + end = newEnd; + } +} + +template +T Vector::pop() +{ + if (isEmpty()) + { + return T(); + } + + // save pop result + T result = begin->obj; + + // move begin pointer + Node* oldBegin = begin; + begin = begin->next; + + // null end pointer if require + if (oldBegin == end) + { + end = nullptr; + } + + // clear old memory + delete oldBegin; + + return result; +} + +template +bool Vector::isEmpty() const +{ + return !begin; +} diff --git a/code/Java/Mobile/TestApplication/TrackPlatformAPI/.gitignore b/code/Java/Mobile/Application2.0/.gitignore old mode 100755 new mode 100644 similarity index 58% rename from code/Java/Mobile/TestApplication/TrackPlatformAPI/.gitignore rename to code/Java/Mobile/Application2.0/.gitignore index a4c7838..bd1302f --- a/code/Java/Mobile/TestApplication/TrackPlatformAPI/.gitignore +++ b/code/Java/Mobile/Application2.0/.gitignore @@ -1,9 +1,18 @@ -*.iml -.gradle -/local.properties -/.idea/workspace.xml -/.idea/libraries -.DS_Store -/build -/captures -.externalNativeBuild +*.iml +/local.properties +/.idea/workspace.xml +/.idea/libraries +.DS_Store +/captures +.externalNativeBuild +*.log + +# Gradle files +.gradle/ +build/ + +# Generated files +bin/ +gen/ +out/ + diff --git a/code/Java/Mobile/TestApplication/TrackPlatformAPI/app/.gitignore b/code/Java/Mobile/Application2.0/app/.gitignore old mode 100755 new mode 100644 similarity index 87% rename from code/Java/Mobile/TestApplication/TrackPlatformAPI/app/.gitignore rename to code/Java/Mobile/Application2.0/app/.gitignore index 3543521..796b96d --- a/code/Java/Mobile/TestApplication/TrackPlatformAPI/app/.gitignore +++ b/code/Java/Mobile/Application2.0/app/.gitignore @@ -1 +1 @@ -/build +/build diff --git a/code/Java/Mobile/TestApplication/TrackPlatformAPI/app/build.gradle b/code/Java/Mobile/Application2.0/app/build.gradle old mode 100755 new mode 100644 similarity index 70% rename from code/Java/Mobile/TestApplication/TrackPlatformAPI/app/build.gradle rename to code/Java/Mobile/Application2.0/app/build.gradle index ea934a0..6978f68 --- a/code/Java/Mobile/TestApplication/TrackPlatformAPI/app/build.gradle +++ b/code/Java/Mobile/Application2.0/app/build.gradle @@ -1,31 +1,32 @@ -apply plugin: 'com.android.application' - -android { - compileSdkVersion 25 - buildToolsVersion "25.0.2" - defaultConfig { - applicationId "com.example.yuras.trackplatformapi" - minSdkVersion 17 - targetSdkVersion 25 - versionCode 1 - versionName "1.0" - testInstrumentationRunner "android.support.test.runner.AndroidJUnitRunner" - } - buildTypes { - release { - minifyEnabled false - proguardFiles getDefaultProguardFile('proguard-android.txt'), 'proguard-rules.pro' - } - } -} - -dependencies { - compile fileTree(dir: 'libs', include: ['*.jar']) - androidTestCompile('com.android.support.test.espresso:espresso-core:2.2.2', { - exclude group: 'com.android.support', module: 'support-annotations' - }) - compile 'com.android.support:appcompat-v7:25.1.0' - compile 'com.android.support.constraint:constraint-layout:1.0.2' - compile 'com.android.support:design:25.3.1' - testCompile 'junit:junit:4.12' -} +apply plugin: 'com.android.application' + +android { + compileSdkVersion 25 + buildToolsVersion '25.0.2' + defaultConfig { + applicationId "com.example.kimentii.application20" + minSdkVersion 17 + targetSdkVersion 17 + versionCode 1 + versionName "1.0" + testInstrumentationRunner "android.support.test.runner.AndroidJUnitRunner" + } + buildTypes { + release { + minifyEnabled false + proguardFiles getDefaultProguardFile('proguard-android.txt'), 'proguard-rules.pro' + } + } + productFlavors { + } +} + +dependencies { + compile fileTree(include: ['*.jar'], dir: 'libs') + androidTestCompile('com.android.support.test.espresso:espresso-core:2.2.2', { + exclude group: 'com.android.support', module: 'support-annotations' + }) + compile 'com.android.support:appcompat-v7:25.3.1' + compile 'com.android.support.constraint:constraint-layout:1.0.2' + testCompile 'junit:junit:4.12' +} diff --git a/code/Java/Mobile/TestApplication/TrackPlatformAPI/app/proguard-rules.pro b/code/Java/Mobile/Application2.0/app/proguard-rules.pro old mode 100755 new mode 100644 similarity index 64% rename from code/Java/Mobile/TestApplication/TrackPlatformAPI/app/proguard-rules.pro rename to code/Java/Mobile/Application2.0/app/proguard-rules.pro index 2504588..ce3149c --- a/code/Java/Mobile/TestApplication/TrackPlatformAPI/app/proguard-rules.pro +++ b/code/Java/Mobile/Application2.0/app/proguard-rules.pro @@ -1,17 +1,25 @@ -# Add project specific ProGuard rules here. -# By default, the flags in this file are appended to flags specified -# in C:\Users\yuras\AppData\Local\Android\Sdk/tools/proguard/proguard-android.txt -# You can edit the include path and order by changing the proguardFiles -# directive in build.gradle. -# -# For more details, see -# http://developer.android.com/guide/developing/tools/proguard.html - -# Add any project specific keep options here: - -# If your project uses WebView with JS, uncomment the following -# and specify the fully qualified class name to the JavaScript interface -# class: -#-keepclassmembers class fqcn.of.javascript.interface.for.webview { -# public *; -#} +# Add project specific ProGuard rules here. +# By default, the flags in this file are appended to flags specified +# in C:\Android\sdk/tools/proguard/proguard-android.txt +# You can edit the include path and order by changing the proguardFiles +# directive in build.gradle. +# +# For more details, see +# http://developer.android.com/guide/developing/tools/proguard.html + +# Add any project specific keep options here: + +# If your project uses WebView with JS, uncomment the following +# and specify the fully qualified class name to the JavaScript interface +# class: +#-keepclassmembers class fqcn.of.javascript.interface.for.webview { +# public *; +#} + +# Uncomment this to preserve the line number information for +# debugging stack traces. +#-keepattributes SourceFile,LineNumberTable + +# If you keep the line number information, uncomment this to +# hide the original source file name. +#-renamesourcefileattribute SourceFile diff --git a/code/Java/Mobile/TestApplication/TrackPlatformAPI/app/src/androidTest/java/com/example/yuras/trackplatformapi/ExampleInstrumentedTest.java b/code/Java/Mobile/Application2.0/app/src/androidTest/java/com/example/kimentii/application20/ExampleInstrumentedTest.java old mode 100755 new mode 100644 similarity index 83% rename from code/Java/Mobile/TestApplication/TrackPlatformAPI/app/src/androidTest/java/com/example/yuras/trackplatformapi/ExampleInstrumentedTest.java rename to code/Java/Mobile/Application2.0/app/src/androidTest/java/com/example/kimentii/application20/ExampleInstrumentedTest.java index 92e5a3f..6c71eb3 --- a/code/Java/Mobile/TestApplication/TrackPlatformAPI/app/src/androidTest/java/com/example/yuras/trackplatformapi/ExampleInstrumentedTest.java +++ b/code/Java/Mobile/Application2.0/app/src/androidTest/java/com/example/kimentii/application20/ExampleInstrumentedTest.java @@ -1,26 +1,26 @@ -package com.example.yuras.trackplatformapi; - -import android.content.Context; -import android.support.test.InstrumentationRegistry; -import android.support.test.runner.AndroidJUnit4; - -import org.junit.Test; -import org.junit.runner.RunWith; - -import static org.junit.Assert.*; - -/** - * Instrumentation test, which will execute on an Android device. - * - * @see Testing documentation - */ -@RunWith(AndroidJUnit4.class) -public class ExampleInstrumentedTest { - @Test - public void useAppContext() throws Exception { - // Context of the app under test. - Context appContext = InstrumentationRegistry.getTargetContext(); - - assertEquals("com.example.yuras.trackplatformapi", appContext.getPackageName()); - } -} +package com.example.kimentii.application20; + +import android.content.Context; +import android.support.test.InstrumentationRegistry; +import android.support.test.runner.AndroidJUnit4; + +import org.junit.Test; +import org.junit.runner.RunWith; + +import static org.junit.Assert.*; + +/** + * Instrumentation test, which will execute on an Android device. + * + * @see Testing documentation + */ +@RunWith(AndroidJUnit4.class) +public class ExampleInstrumentedTest { + @Test + public void useAppContext() throws Exception { + // Context of the app under test. + Context appContext = InstrumentationRegistry.getTargetContext(); + + assertEquals("com.example.kimentii.application20", appContext.getPackageName()); + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/AndroidManifest.xml b/code/Java/Mobile/Application2.0/app/src/main/AndroidManifest.xml new file mode 100644 index 0000000..3aefa4b --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/AndroidManifest.xml @@ -0,0 +1,37 @@ + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/MainActivity.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/MainActivity.java new file mode 100644 index 0000000..8ea9c9c --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/MainActivity.java @@ -0,0 +1,164 @@ +package com.example.kimentii.application20.activities; + +import android.bluetooth.BluetoothAdapter; +import android.content.Intent; +import android.os.Bundle; +import android.os.Handler; +import android.os.Message; +import android.support.v7.app.AppCompatActivity; +import android.util.Log; +import android.view.View; +import android.widget.Button; +import android.widget.TextView; + +import com.example.kimentii.application20.R; +import com.example.kimentii.application20.connectors.BluetoothConnector; +import com.example.kimentii.application20.settings.Settings; +import com.example.kimentii.application20.wrappers.LanguageWrapper; + +public class MainActivity extends AppCompatActivity { + + public static final String TAG = "TAG"; + private static final int REQUEST_ENABLE_BT = 1; + + private Button motionButton; + private Button servoButton; + private Button sensorsButton; + private Button settingsButton; + private Button exitButton; + private TextView connectionStateTextView; + + private BluetoothConnector bluetoothConnector; + + class Listener implements View.OnClickListener { + Intent intent; + + @Override + public void onClick(View v) { + switch (v.getId()) { + case R.id.motion_button: + intent = MotionActivity.newIntent(getApplicationContext()); + startActivity(intent); + break; + case R.id.servo_button: + intent = ServoActivity.newIntent(getApplicationContext()); + startActivity(intent); + break; + case R.id.sensors_button: + intent = SensorsActivity.newIntent(getApplicationContext()); + startActivity(intent); + break; + case R.id.settings_button: + intent = SettingsActivity.newIntent(getApplicationContext()); + startActivity(intent); + break; + case R.id.exit_button: + try { + if (bluetoothConnector != null) { + bluetoothConnector.disconnect(); + bluetoothConnector.join(); + } + } catch (InterruptedException e) { + e.printStackTrace(); + } + finish(); + break; + } + } + } + + private void updateConnectionStateView() { + if (bluetoothConnector != null && bluetoothConnector.isConnected()) { + connectionStateTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.CONNECTED)); + } else { + connectionStateTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.NO_CONNECTION)); + } + } + + private void setLocaleLanguage() { + updateConnectionStateView(); + // buttons + motionButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.MOTION_BUTTON)); + servoButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.SERVO_BUTTON)); + sensorsButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.SENSORS_BUTTON)); + settingsButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.SETTINGS_BUTTON)); + exitButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.EXIT_BUTTON)); + } + + @Override + protected void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.activity_main); + Listener listener = new Listener(); + motionButton = (Button) findViewById(R.id.motion_button); + servoButton = (Button) findViewById(R.id.servo_button); + sensorsButton = (Button) findViewById(R.id.sensors_button); + settingsButton = (Button) findViewById(R.id.settings_button); + exitButton = (Button) findViewById(R.id.exit_button); + connectionStateTextView = (TextView) findViewById(R.id.connection_state_tv_main_activity); + motionButton.setOnClickListener(listener); + servoButton.setOnClickListener(listener); + sensorsButton.setOnClickListener(listener); + settingsButton.setOnClickListener(listener); + exitButton.setOnClickListener(listener); + setLocaleLanguage(); + + + BluetoothAdapter bluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); + if (bluetoothAdapter == null) { + connectionStateTextView.setText(R.string.have_no_bluetooth_module); + Log.d(TAG, "You have no bluetooth."); + } + if (bluetoothAdapter != null && bluetoothAdapter.isEnabled()) { + Handler handler = new Handler() { + @Override + public void handleMessage(Message msg) { + super.handleMessage(msg); + + } + }; + bluetoothConnector = BluetoothConnector.getInstance(); + bluetoothConnector.connect(); + bluetoothConnector.setHandler(handler); + updateConnectionStateView(); + } else { + // Bluetooth выключен. Предложим пользователю включить его. + Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); + startActivityForResult(enableBtIntent, REQUEST_ENABLE_BT); + } + + } + + @Override + protected void onResume() { + super.onResume(); + setLocaleLanguage(); + } + + @Override + protected void onActivityResult(int requestCode, int resultCode, Intent data) { + super.onActivityResult(requestCode, resultCode, data); + if (requestCode == REQUEST_ENABLE_BT && requestCode == RESULT_OK) { + Log.d(TAG, "Bluetooth connected"); + Handler handler = new Handler() { + @Override + public void handleMessage(Message msg) { + super.handleMessage(msg); + + } + }; + bluetoothConnector = BluetoothConnector.getInstance(); + bluetoothConnector.connect(); + bluetoothConnector.setHandler(handler); + updateConnectionStateView(); + } + } + +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/MotionActivity.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/MotionActivity.java new file mode 100644 index 0000000..d2f13bc --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/MotionActivity.java @@ -0,0 +1,117 @@ +package com.example.kimentii.application20.activities; + +import android.content.Context; +import android.content.Intent; +import android.os.Bundle; +import android.os.Handler; +import android.os.Message; +import android.support.v7.app.ActionBar; +import android.support.v7.app.AppCompatActivity; +import android.view.MotionEvent; +import android.view.View; +import android.widget.Button; +import android.widget.TextView; + +import com.example.kimentii.application20.R; +import com.example.kimentii.application20.connectors.BluetoothConnector; +import com.example.kimentii.application20.controllers.MotionController; +import com.example.kimentii.application20.settings.Settings; +import com.example.kimentii.application20.wrappers.LanguageWrapper; + +public class MotionActivity extends AppCompatActivity { + + private Button forwardButton; + private Button rightButton; + private Button leftButton; + private Button backButton; + private Button stopButton; + private TextView connectionStateTextView; + + private BluetoothConnector bluetoothConnector; + private MotionController motionController; + + private void setLocaleLanguage() { + if (bluetoothConnector != null && bluetoothConnector.isConnected()) { + connectionStateTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.CONNECTED)); + } else { + connectionStateTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.NO_CONNECTION)); + } + forwardButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.FORWARD_BUTTON)); + rightButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.RIGHT_BUTTON)); + leftButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.LEFT_BUTTON)); + backButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.BACK_BUTTON)); + stopButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.STOP_BUTTON)); + } + + @Override + protected void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.activity_motion); + ActionBar actionBar = getSupportActionBar(); + actionBar.setHomeButtonEnabled(true); + actionBar.setDisplayHomeAsUpEnabled(true); + + Handler handler = new Handler() { + @Override + public void handleMessage(Message msg) { + super.handleMessage(msg); + + } + }; + bluetoothConnector = BluetoothConnector.getInstance(); + bluetoothConnector.setHandler(handler); + + forwardButton = (Button) findViewById(R.id.forward_button); + rightButton = (Button) findViewById(R.id.right_button); + leftButton = (Button) findViewById(R.id.left_button); + backButton = (Button) findViewById(R.id.back_button); + stopButton = (Button) findViewById(R.id.stop_button); + connectionStateTextView = (TextView) findViewById(R.id.connection_state_tv_motion_activity); + setLocaleLanguage(); + + motionController = new MotionController(); + View.OnTouchListener touchListener = new View.OnTouchListener() { + @Override + public boolean onTouch(View view, MotionEvent motionEvent) { + if (motionEvent.getAction() == MotionEvent.ACTION_DOWN) { + switch (view.getId()) { + case R.id.forward_button: + motionController.moveForward(); + break; + case R.id.right_button: + motionController.moveRight(); + break; + case R.id.left_button: + motionController.moveLeft(); + break; + case R.id.back_button: + motionController.moveBack(); + break; + case R.id.stop_button: + motionController.stop(); + break; + } + } else if (motionEvent.getAction() == MotionEvent.ACTION_UP) { + motionController.stop(); + } + return false; + } + }; + forwardButton.setOnTouchListener(touchListener); + rightButton.setOnTouchListener(touchListener); + leftButton.setOnTouchListener(touchListener); + backButton.setOnTouchListener(touchListener); + stopButton.setOnTouchListener(touchListener); + } + + public static Intent newIntent(Context context) { + return new Intent(context, MotionActivity.class); + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/SensorsActivity.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/SensorsActivity.java new file mode 100644 index 0000000..4e77542 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/SensorsActivity.java @@ -0,0 +1,173 @@ +package com.example.kimentii.application20.activities; + +import android.content.Context; +import android.content.Intent; +import android.os.Bundle; +import android.os.Handler; +import android.os.Message; +import android.support.v7.app.ActionBar; +import android.support.v7.app.AppCompatActivity; +import android.widget.TextView; + +import com.example.kimentii.application20.R; +import com.example.kimentii.application20.connectors.BluetoothConnector; +import com.example.kimentii.application20.constants.Constants; +import com.example.kimentii.application20.controllers.SensorsController; +import com.example.kimentii.application20.settings.Settings; +import com.example.kimentii.application20.wrappers.LanguageWrapper; + +public class SensorsActivity extends AppCompatActivity { + + private TextView distanceSensorsTV; + private TextView lineSensorsTV; + private TextView connectionStateTextView; + + // distance sensors + private TextView firstDistanceSensorTV; + private TextView secondDistanceSensorTV; + private TextView thirdDistanceSensorTV; + private TextView fourthDistanceSensorTV; + private TextView fifthDistanceSensorTV; + // distance sensors values + private TextView firstDistanceSensorValueTV; + private TextView secondDistanceSensorValueTV; + private TextView thirdDistanceSensorValueTV; + private TextView fourthDistanceSensorValueTV; + private TextView fifthDistanceSensorValueTV; + + // line sensors + private TextView firstLineSensorTV; + private TextView secondLineSensorTV; + private TextView thirdLineSensorTV; + private TextView fourthLineSensorTV; + private TextView fifthLineSensorTV; + // line sensors values + private TextView firstLineSensorValueTV; + private TextView secondLineSensorValueTV; + private TextView thirdLineSensorValueTV; + private TextView fourthLineSensorValueTV; + private TextView fifthLineSensorValueTV; + + BluetoothConnector bluetoothConnector; + SensorsController sensorsController; + + private void setLocaleLanguage() { + if (bluetoothConnector != null && bluetoothConnector.isConnected()) { + connectionStateTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.CONNECTED)); + } else { + connectionStateTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.NO_CONNECTION)); + } + distanceSensorsTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.DISTANCE_SENSORS)); + lineSensorsTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.LINE_SENSORS)); + + // distance sensors + firstDistanceSensorTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.FIRST_SENSOR)); + secondDistanceSensorTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.SECOND_SENSOR)); + thirdDistanceSensorTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.THIRD_SENSOR)); + fourthDistanceSensorTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.FOURTH_SENSOR)); + fifthDistanceSensorTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.FIRST_SENSOR)); + + // line sensors + firstLineSensorTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.FIRST_SENSOR)); + secondLineSensorTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.SECOND_SENSOR)); + thirdLineSensorTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.THIRD_SENSOR)); + fourthLineSensorTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.FOURTH_SENSOR)); + fifthLineSensorTV.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.FIFTH_SENSOR)); + + } + + @Override + protected void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.activity_sensors); + ActionBar actionBar = getSupportActionBar(); + actionBar.setHomeButtonEnabled(true); + actionBar.setDisplayHomeAsUpEnabled(true); + + Handler handler = new Handler() { + @Override + public void handleMessage(Message msg) { + if (msg.what == Constants.Messages.MESSAGES_READ_DISTANCE_SENSORS_VALUES.getValue()) { + int data[] = (int[]) msg.obj; + firstDistanceSensorValueTV.setText(String.valueOf(data[0])); + secondDistanceSensorValueTV.setText(String.valueOf(data[1])); + thirdDistanceSensorValueTV.setText(String.valueOf(data[2])); + fourthDistanceSensorValueTV.setText(String.valueOf(data[3])); + fifthDistanceSensorValueTV.setText(String.valueOf(data[4])); + } else if (msg.what == Constants.Messages.MESSAGES_READ_LINE_SENSORS_VALUES.getValue()) { + int data[] = (int[]) msg.obj; + firstLineSensorValueTV.setText(String.valueOf(data[0])); + secondLineSensorValueTV.setText(String.valueOf(data[1])); + thirdLineSensorValueTV.setText(String.valueOf(data[2])); + fourthLineSensorValueTV.setText(String.valueOf(data[3])); + fifthLineSensorValueTV.setText(String.valueOf(data[4])); + } + + } + }; + bluetoothConnector = BluetoothConnector.getInstance(); + bluetoothConnector.setHandler(handler); + + sensorsController = new SensorsController(); + + connectionStateTextView = (TextView) findViewById(R.id.connection_state_tv_sensors_activity); + distanceSensorsTV = (TextView) findViewById(R.id.distance_sensors_tv); + lineSensorsTV = (TextView) findViewById(R.id.line_sensors_tv); + + // distance sensors + firstDistanceSensorTV = (TextView) findViewById(R.id.first_distance_sensor_tv); + secondDistanceSensorTV = (TextView) findViewById(R.id.second_distance_sensor_tv); + thirdDistanceSensorTV = (TextView) findViewById(R.id.third_distance_sensor_tv); + fourthDistanceSensorTV = (TextView) findViewById(R.id.fourth_distance_sensor_tv); + fifthDistanceSensorTV = (TextView) findViewById(R.id.fifth_distance_sensor_tv); + + // line sensors + firstLineSensorTV = (TextView) findViewById(R.id.first_line_sensor_tv); + secondLineSensorTV = (TextView) findViewById(R.id.second_line_sensor_tv); + thirdLineSensorTV = (TextView) findViewById(R.id.third_line_sensor_tv); + fourthLineSensorTV = (TextView) findViewById(R.id.fourth_line_sensor_tv); + fifthLineSensorTV = (TextView) findViewById(R.id.fifth_line_sensor_tv); + + setLocaleLanguage(); + + // distance sensors values + firstDistanceSensorValueTV = (TextView) findViewById(R.id.first_distance_sensor_value_tv); + secondDistanceSensorValueTV = (TextView) findViewById(R.id.second_distance_sensor_value_tv); + thirdDistanceSensorValueTV = (TextView) findViewById(R.id.third_distance_sensor_value_tv); + fourthDistanceSensorValueTV = (TextView) findViewById(R.id.fourth_distance_sensor_value_tv); + fifthDistanceSensorValueTV = (TextView) findViewById(R.id.fifth_distance_sensor_value_tv); + + // line sensors values + firstLineSensorValueTV = (TextView) findViewById(R.id.first_line_sensor_value_tv); + secondLineSensorValueTV = (TextView) findViewById(R.id.second_line_sensor_value_tv); + thirdLineSensorValueTV = (TextView) findViewById(R.id.third_line_sensor_value_tv); + fourthLineSensorValueTV = (TextView) findViewById(R.id.fourth_line_sensor_value_tv); + fifthLineSensorValueTV = (TextView) findViewById(R.id.fifth_line_sensor_value_tv); + + sensorsController.getDataFromDistanceSensors(); + try { + Thread.sleep(1000); + } catch (InterruptedException e) { + e.printStackTrace(); + } + sensorsController.getDataFromLineSensors(); + } + + public static Intent newIntent(Context context) { + return new Intent(context, SensorsActivity.class); + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/ServoActivity.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/ServoActivity.java new file mode 100644 index 0000000..a8805cf --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/ServoActivity.java @@ -0,0 +1,103 @@ +package com.example.kimentii.application20.activities; + +import android.content.Context; +import android.content.Intent; +import android.os.Bundle; +import android.os.Handler; +import android.os.Message; +import android.support.v7.app.ActionBar; +import android.support.v7.app.AppCompatActivity; +import android.view.View; +import android.widget.Button; +import android.widget.TextView; + +import com.example.kimentii.application20.R; +import com.example.kimentii.application20.connectors.BluetoothConnector; +import com.example.kimentii.application20.controllers.ServoController; +import com.example.kimentii.application20.settings.Settings; +import com.example.kimentii.application20.wrappers.LanguageWrapper; + +public class ServoActivity extends AppCompatActivity { + + private TextView connectionStateTextView; + private BluetoothConnector bluetoothConnector; + private ServoController servoController; + + private Button upButton; + private Button rightButton; + private Button leftButton; + private Button downButton; + + private void setLocaleLanguage() { + if (bluetoothConnector != null && bluetoothConnector.isConnected()) { + connectionStateTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.CONNECTED)); + } else { + connectionStateTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.NO_CONNECTION)); + } + upButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.UP_SERVO_BUTTON)); + rightButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.RIGHT_SERVO_BUTTON)); + leftButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.LEFT_SERVO_BUTTON)); + downButton.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.DOWN_SERVO_BUTTON)); + } + + @Override + protected void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.activity_servo); + ActionBar actionBar = getSupportActionBar(); + actionBar.setHomeButtonEnabled(true); + actionBar.setDisplayHomeAsUpEnabled(true); + + Handler handler = new Handler() { + @Override + public void handleMessage(Message msg) { + super.handleMessage(msg); + + } + }; + bluetoothConnector = BluetoothConnector.getInstance(); + bluetoothConnector.setHandler(handler); + + connectionStateTextView = (TextView) findViewById(R.id.connection_state_tv_servo_activity); + upButton = (Button) findViewById(R.id.up_sero_button); + rightButton = (Button) findViewById(R.id.right_servo_button); + leftButton = (Button) findViewById(R.id.left_servo_button); + downButton = (Button) findViewById(R.id.down_servo_button); + setLocaleLanguage(); + + servoController = new ServoController(); + View.OnClickListener clickListener = new View.OnClickListener() { + @Override + public void onClick(View v) { + switch (v.getId()) { + case R.id.up_sero_button: + servoController.turnUpOnOneDegree(); + break; + case R.id.right_servo_button: + servoController.turnRightOnOneDegree(); + break; + case R.id.left_servo_button: + servoController.turnLeftOnOneDegree(); + break; + case R.id.down_servo_button: + servoController.turnDownOnOneDegree(); + break; + } + } + }; + upButton.setOnClickListener(clickListener); + rightButton.setOnClickListener(clickListener); + leftButton.setOnClickListener(clickListener); + downButton.setOnClickListener(clickListener); + } + + public static Intent newIntent(Context context) { + return new Intent(context, ServoActivity.class); + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/SettingsActivity.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/SettingsActivity.java new file mode 100644 index 0000000..51551a8 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/SettingsActivity.java @@ -0,0 +1,131 @@ +package com.example.kimentii.application20.activities; + +import android.content.Context; +import android.content.Intent; +import android.os.Bundle; +import android.os.Handler; +import android.os.Message; +import android.support.v7.app.ActionBar; +import android.support.v7.app.AppCompatActivity; +import android.util.Log; +import android.view.View; +import android.widget.AdapterView; +import android.widget.Spinner; +import android.widget.TextView; + +import com.example.kimentii.application20.R; +import com.example.kimentii.application20.connectors.BluetoothConnector; +import com.example.kimentii.application20.constants.Constants; +import com.example.kimentii.application20.settings.Settings; +import com.example.kimentii.application20.wrappers.LanguageWrapper; + +public class SettingsActivity extends AppCompatActivity { + public static final String TAG = "TAG"; + public static final int RUSSIAN_LANGUAGE_POSITION = 0; + public static final int ENGLISH_LANGUAGE_POSITION = 1; + public static final int API1_POSITION = 0; + public static final int API2_POSITION = 1; + public static final int API3_POSITION = 2; + public static final int API4_POSITION = 3; + + + private TextView languageTextView; + private TextView connectionStateTextView; + private Spinner languageSpinner; + private Spinner apiSpinner; + + private BluetoothConnector bluetoothConnector; + + private void setLocaleLanguage() { + if (bluetoothConnector != null && bluetoothConnector.isConnected()) { + connectionStateTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.CONNECTED)); + } else { + connectionStateTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.NO_CONNECTION)); + } + languageTextView.setText(Settings.getInstance().getLanguageWrapper(). + getViewString(LanguageWrapper.LANGUAGE)); + } + + @Override + protected void onCreate(Bundle savedInstanceState) { + super.onCreate(savedInstanceState); + setContentView(R.layout.activity_settings); + ActionBar actionBar = getSupportActionBar(); + actionBar.setHomeButtonEnabled(true); + actionBar.setDisplayHomeAsUpEnabled(true); + + Handler handler = new Handler() { + @Override + public void handleMessage(Message msg) { + super.handleMessage(msg); + } + }; + bluetoothConnector = BluetoothConnector.getInstance(); + bluetoothConnector.setHandler(handler); + + connectionStateTextView = (TextView) findViewById(R.id.connection_state_tv_settings_activity); + languageTextView = (TextView) findViewById(R.id.language_tv); + setLocaleLanguage(); + + languageSpinner = (Spinner) findViewById(R.id.language_spinner); + apiSpinner = (Spinner) findViewById(R.id.api_spinner); + + if (Settings.getInstance().getLanguageWrapper().getLanguage() == LanguageWrapper.RUSSIAN) { + languageSpinner.setSelection(RUSSIAN_LANGUAGE_POSITION); + } else { + languageSpinner.setSelection(ENGLISH_LANGUAGE_POSITION); + } + + languageSpinner.setOnItemSelectedListener(new AdapterView.OnItemSelectedListener() { + @Override + public void onItemSelected(AdapterView parent, View view, int position, long id) { + if (position == RUSSIAN_LANGUAGE_POSITION) { + Log.d(TAG, "Russian was set."); + Settings.getInstance().getLanguageWrapper().setLanguage(LanguageWrapper.RUSSIAN); + setLocaleLanguage(); + } else { + Log.d(TAG, "English was set."); + Settings.getInstance().getLanguageWrapper().setLanguage(LanguageWrapper.ENGLISH); + setLocaleLanguage(); + } + } + + @Override + public void onNothingSelected(AdapterView parent) { + + } + }); + + apiSpinner.setSelection(Settings.getInstance().getApi().getApiEnum().getValue() - 1); + apiSpinner.setOnItemSelectedListener(new AdapterView.OnItemSelectedListener() { + @Override + public void onItemSelected(AdapterView parent, View view, int position, long id) { + switch (position) { + case API1_POSITION: + Settings.getInstance().setApi(Constants.ApiEnum.API1); + break; + case API2_POSITION: + Settings.getInstance().setApi(Constants.ApiEnum.API2); + break; + case API3_POSITION: + Settings.getInstance().setApi(Constants.ApiEnum.API3); + break; + case API4_POSITION: + Settings.getInstance().setApi(Constants.ApiEnum.API4); + break; + } + } + + @Override + public void onNothingSelected(AdapterView parent) { + + } + }); + } + + public static Intent newIntent(Context context) { + return new Intent(context, SettingsActivity.class); + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API.java new file mode 100644 index 0000000..0b5e998 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API.java @@ -0,0 +1,47 @@ +package com.example.kimentii.application20.api; + + +import com.example.kimentii.application20.constants.Constants; + +public abstract class API { + public static final char XY = '1'; + public static final char XZ = '2'; + + protected Constants.ApiEnum apiEnum; + + public Constants.ApiEnum getApiEnum() { + return apiEnum; + } + + // communication + public abstract byte[] getConnectCommand(Constants.ApiEnum api); + + public abstract byte[] getDisconnectCommand(); + + public abstract byte[] getReconnectCommand(); + + // motion activity + public abstract byte[] getMoveForwardCommand(); + + public abstract byte[] getMoveRightCommand(); + + public abstract byte[] getMoveLeftCommand(); + + public abstract byte[] getMoveBackCommand(); + + public abstract byte[] getStopCommand(); + + // servo activity + public abstract byte[] getGetAngleCommand(); + + public abstract byte[] getSetAngleCommand(int angle, char surface); + + // sensors activity + public abstract byte[] getInfoFromDistanceSensorCommand(int i); + + public abstract byte[] getInfoFromLineSensorCommand(int i); + + public abstract byte[] getInfoFromAllDistanceSensorsCommand(); + + public abstract byte[] getInfoFromAllLineSensorsCommand(); +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API1.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API1.java new file mode 100644 index 0000000..5d64887 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API1.java @@ -0,0 +1,82 @@ +package com.example.kimentii.application20.api; + +import com.example.kimentii.application20.constants.Constants; + +public class API1 extends API { + + public API1() { + apiEnum = Constants.ApiEnum.API1; + } + + @Override + public byte[] getConnectCommand(Constants.ApiEnum api) { + return new byte[0]; + } + + @Override + public byte[] getDisconnectCommand() { + return new byte[0]; + } + + @Override + public byte[] getReconnectCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveForwardCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveRightCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveLeftCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveBackCommand() { + return new byte[0]; + } + + @Override + public byte[] getStopCommand() { + return new byte[0]; + } + + @Override + public byte[] getGetAngleCommand() { + return new byte[0]; + } + + @Override + public byte[] getSetAngleCommand(int angle, char surface) { + return new byte[0]; + } + + + @Override + public byte[] getInfoFromDistanceSensorCommand(int i) { + return new byte[0]; + } + + @Override + public byte[] getInfoFromLineSensorCommand(int i) { + return new byte[0]; + } + + @Override + public byte[] getInfoFromAllDistanceSensorsCommand() { + return new byte[0]; + } + + @Override + public byte[] getInfoFromAllLineSensorsCommand() { + return new byte[0]; + } + +} \ No newline at end of file diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API2.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API2.java new file mode 100644 index 0000000..f92df56 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API2.java @@ -0,0 +1,81 @@ +package com.example.kimentii.application20.api; + +import com.example.kimentii.application20.constants.Constants; + +public class API2 extends API { + + public API2() { + apiEnum = Constants.ApiEnum.API2; + } + + @Override + public byte[] getConnectCommand(Constants.ApiEnum api) { + return new byte[0]; + } + + @Override + public byte[] getDisconnectCommand() { + return new byte[0]; + } + + @Override + public byte[] getReconnectCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveForwardCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveRightCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveLeftCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveBackCommand() { + return new byte[0]; + } + + @Override + public byte[] getStopCommand() { + return new byte[0]; + } + + @Override + public byte[] getGetAngleCommand() { + return new byte[0]; + } + + @Override + public byte[] getSetAngleCommand(int angle, char surface) { + return new byte[0]; + } + + @Override + public byte[] getInfoFromDistanceSensorCommand(int i) { + return new byte[0]; + } + + @Override + public byte[] getInfoFromLineSensorCommand(int i) { + return new byte[0]; + } + + @Override + public byte[] getInfoFromAllDistanceSensorsCommand() { + return new byte[0]; + } + + @Override + public byte[] getInfoFromAllLineSensorsCommand() { + return new byte[0]; + } + +} \ No newline at end of file diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API3.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API3.java new file mode 100644 index 0000000..a4ee745 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API3.java @@ -0,0 +1,81 @@ +package com.example.kimentii.application20.api; + +import com.example.kimentii.application20.constants.Constants; + +public class API3 extends API { + + public API3() { + apiEnum = Constants.ApiEnum.API3; + } + + @Override + public byte[] getConnectCommand(Constants.ApiEnum api) { + return new byte[0]; + } + + @Override + public byte[] getDisconnectCommand() { + return new byte[0]; + } + + @Override + public byte[] getReconnectCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveForwardCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveRightCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveLeftCommand() { + return new byte[0]; + } + + @Override + public byte[] getMoveBackCommand() { + return new byte[0]; + } + + @Override + public byte[] getStopCommand() { + return new byte[0]; + } + + @Override + public byte[] getGetAngleCommand() { + return new byte[0]; + } + + @Override + public byte[] getSetAngleCommand(int angle, char surface) { + return new byte[0]; + } + + + @Override + public byte[] getInfoFromDistanceSensorCommand(int i) { + return new byte[0]; + } + + @Override + public byte[] getInfoFromLineSensorCommand(int i) { + return new byte[0]; + } + + @Override + public byte[] getInfoFromAllDistanceSensorsCommand() { + return new byte[0]; + } + + @Override + public byte[] getInfoFromAllLineSensorsCommand() { + return new byte[0]; + } +} \ No newline at end of file diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API4.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API4.java new file mode 100644 index 0000000..99e71c2 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API4.java @@ -0,0 +1,169 @@ +package com.example.kimentii.application20.api; + + +import android.util.Log; + +import com.example.kimentii.application20.constants.Constants; + +public class API4 extends API { + public final String TAG = "TAG"; + + + public API4() { + apiEnum = Constants.ApiEnum.API4; + } + + @Override + public byte[] getConnectCommand(Constants.ApiEnum api) { + byte command[] = {(byte) 0x03, Constants.Controllers.COMMUNICATION_CONTROLLER_ID.getValue(), + Constants.Communication.START_COMMUNICATION.getValue(), api.getValue(), + (byte) 0x00, (byte) 0x00}; + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, command.length - CRC16Modbus.SIZE_CRC_IN_BYTES); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + + // не тещено + @Override + public byte[] getDisconnectCommand() { + byte command[] = {(byte) 0x02, Constants.Controllers.COMMUNICATION_CONTROLLER_ID.getValue(), + Constants.Communication.STOP_COMMUNICATION.getValue(), (byte) 0x00, (byte) 0x00}; + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, command.length - CRC16Modbus.SIZE_CRC_IN_BYTES); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + + @Override + public byte[] getReconnectCommand() { + byte command[] = {(byte) 0x02, Constants.Controllers.COMMUNICATION_CONTROLLER_ID.getValue(), + Constants.Communication.REFRESH_CONNECTION.getValue(), (byte) 0x00, (byte) 0x00}; + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, command.length - CRC16Modbus.SIZE_CRC_IN_BYTES); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + + @Override + public byte[] getMoveForwardCommand() { + byte command[] = {(byte) 0x05, Constants.Controllers.MOVEMENT_CONTROLLER_ID.getValue(), + Constants.Movement.FORWARD_WITH_SPEED.getValue(), (byte) '1', (byte) '5', (byte) '0', + (byte) 0x00, (byte) 0x00}; + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, command.length - CRC16Modbus.SIZE_CRC_IN_BYTES); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + + @Override + public byte[] getMoveRightCommand() { + byte command[] = {(byte) 0x05, Constants.Controllers.MOVEMENT_CONTROLLER_ID.getValue(), + Constants.Movement.TURN_IN_CLOCK_ARROW_DIRECTION.getValue(), (byte) '1', (byte) '5', (byte) '0', + (byte) 0x00, (byte) 0x00}; + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, command.length - 2); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + + @Override + public byte[] getMoveLeftCommand() { + byte command[] = {(byte) 0x06, Constants.Controllers.MOVEMENT_CONTROLLER_ID.getValue(), + Constants.Movement.TURN_IN_CLOCK_ARROW_DIRECTION.getValue(), (byte) '-', (byte) '1', (byte) '5', + (byte) '0', (byte) 0x00, (byte) 0x00}; + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, command.length - CRC16Modbus.SIZE_CRC_IN_BYTES); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + + @Override + public byte[] getMoveBackCommand() { + byte command[] = {(byte) 0x06, Constants.Controllers.MOVEMENT_CONTROLLER_ID.getValue(), + Constants.Movement.FORWARD_WITH_SPEED.getValue(), (byte) '-', (byte) '1', (byte) '5', + (byte) '0', (byte) 0x00, (byte) 0x00}; + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, command.length - CRC16Modbus.SIZE_CRC_IN_BYTES); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + + @Override + public byte[] getStopCommand() { + byte command[] = {(byte) 0x02, Constants.Controllers.MOVEMENT_CONTROLLER_ID.getValue(), + Constants.Movement.STOP.getValue(), (byte) 0x00, (byte) 0x00}; + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, command.length - CRC16Modbus.SIZE_CRC_IN_BYTES); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + + @Override + public byte[] getGetAngleCommand() { + return new byte[0]; + } + + // не тещено + @Override + public byte[] getSetAngleCommand(int angle, char surface) { + Log.d(TAG, "angle: " + String.valueOf(angle)); + byte angleBytes[] = String.valueOf(angle).getBytes(); + byte prefix[] = {Constants.Controllers.SERVO_CONTROLLER_ID.getValue(), + Constants.Servo.SET_ANGLE.getValue(), (byte) surface, (byte) ';'}; + byte command[] = new byte[angleBytes.length + prefix.length + 3]; + command[0] = (byte) (angleBytes.length + prefix.length); + for (int i = 0; i < prefix.length; i++) { + command[i + 1] = prefix[i]; + } + for (int i = 0; i < angleBytes.length; i++) { + command[i + prefix.length + 1] = angleBytes[i]; + } + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, angleBytes.length + prefix.length + 1); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + + @Override + public byte[] getInfoFromDistanceSensorCommand(int i) { + return new byte[0]; + } + + @Override + public byte[] getInfoFromLineSensorCommand(int i) { + return new byte[0]; + } + + @Override + public byte[] getInfoFromAllDistanceSensorsCommand() { + byte command[] = {(byte) 0x02, Constants.Controllers.SENSORS_CONTROLLER_ID.getValue(), + Constants.Sensors.DISTANCE_SENSOR_ALL.getValue(), (byte) 0x00, (byte) 0x00}; + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, command.length - CRC16Modbus.SIZE_CRC_IN_BYTES); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + + @Override + public byte[] getInfoFromAllLineSensorsCommand() { + byte command[] = {(byte) 0x02, Constants.Controllers.SENSORS_CONTROLLER_ID.getValue(), + Constants.Sensors.LINE_SENSOR_ALL.getValue(), (byte) 0x00, (byte) 0x00}; + CRC16Modbus crc = new CRC16Modbus(); + crc.update(command, 0, command.length - CRC16Modbus.SIZE_CRC_IN_BYTES); + command[command.length - 2] = (byte) ((crc.getValue() & 0x000000ff)); + command[command.length - 1] = (byte) ((crc.getValue() & 0x0000ff00) >>> 8); + return command; + } + +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/CRC16Modbus.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/CRC16Modbus.java new file mode 100644 index 0000000..260f943 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/CRC16Modbus.java @@ -0,0 +1,71 @@ +package com.example.kimentii.application20.api; + +import java.util.zip.Checksum; + +public class CRC16Modbus implements Checksum { + + public static final int SIZE_CRC_IN_BYTES = 2; + + private static final int[] TABLE = { + 0x0000, 0xc0c1, 0xc181, 0x0140, 0xc301, 0x03c0, 0x0280, 0xc241, + 0xc601, 0x06c0, 0x0780, 0xc741, 0x0500, 0xc5c1, 0xc481, 0x0440, + 0xcc01, 0x0cc0, 0x0d80, 0xcd41, 0x0f00, 0xcfc1, 0xce81, 0x0e40, + 0x0a00, 0xcac1, 0xcb81, 0x0b40, 0xc901, 0x09c0, 0x0880, 0xc841, + 0xd801, 0x18c0, 0x1980, 0xd941, 0x1b00, 0xdbc1, 0xda81, 0x1a40, + 0x1e00, 0xdec1, 0xdf81, 0x1f40, 0xdd01, 0x1dc0, 0x1c80, 0xdc41, + 0x1400, 0xd4c1, 0xd581, 0x1540, 0xd701, 0x17c0, 0x1680, 0xd641, + 0xd201, 0x12c0, 0x1380, 0xd341, 0x1100, 0xd1c1, 0xd081, 0x1040, + 0xf001, 0x30c0, 0x3180, 0xf141, 0x3300, 0xf3c1, 0xf281, 0x3240, + 0x3600, 0xf6c1, 0xf781, 0x3740, 0xf501, 0x35c0, 0x3480, 0xf441, + 0x3c00, 0xfcc1, 0xfd81, 0x3d40, 0xff01, 0x3fc0, 0x3e80, 0xfe41, + 0xfa01, 0x3ac0, 0x3b80, 0xfb41, 0x3900, 0xf9c1, 0xf881, 0x3840, + 0x2800, 0xe8c1, 0xe981, 0x2940, 0xeb01, 0x2bc0, 0x2a80, 0xea41, + 0xee01, 0x2ec0, 0x2f80, 0xef41, 0x2d00, 0xedc1, 0xec81, 0x2c40, + 0xe401, 0x24c0, 0x2580, 0xe541, 0x2700, 0xe7c1, 0xe681, 0x2640, + 0x2200, 0xe2c1, 0xe381, 0x2340, 0xe101, 0x21c0, 0x2080, 0xe041, + 0xa001, 0x60c0, 0x6180, 0xa141, 0x6300, 0xa3c1, 0xa281, 0x6240, + 0x6600, 0xa6c1, 0xa781, 0x6740, 0xa501, 0x65c0, 0x6480, 0xa441, + 0x6c00, 0xacc1, 0xad81, 0x6d40, 0xaf01, 0x6fc0, 0x6e80, 0xae41, + 0xaa01, 0x6ac0, 0x6b80, 0xab41, 0x6900, 0xa9c1, 0xa881, 0x6840, + 0x7800, 0xb8c1, 0xb981, 0x7940, 0xbb01, 0x7bc0, 0x7a80, 0xba41, + 0xbe01, 0x7ec0, 0x7f80, 0xbf41, 0x7d00, 0xbdc1, 0xbc81, 0x7c40, + 0xb401, 0x74c0, 0x7580, 0xb541, 0x7700, 0xb7c1, 0xb681, 0x7640, + 0x7200, 0xb2c1, 0xb381, 0x7340, 0xb101, 0x71c0, 0x7080, 0xb041, + 0x5000, 0x90c1, 0x9181, 0x5140, 0x9301, 0x53c0, 0x5280, 0x9241, + 0x9601, 0x56c0, 0x5780, 0x9741, 0x5500, 0x95c1, 0x9481, 0x5440, + 0x9c01, 0x5cc0, 0x5d80, 0x9d41, 0x5f00, 0x9fc1, 0x9e81, 0x5e40, + 0x5a00, 0x9ac1, 0x9b81, 0x5b40, 0x9901, 0x59c0, 0x5880, 0x9841, + 0x8801, 0x48c0, 0x4980, 0x8941, 0x4b00, 0x8bc1, 0x8a81, 0x4a40, + 0x4e00, 0x8ec1, 0x8f81, 0x4f40, 0x8d01, 0x4dc0, 0x4c80, 0x8c41, + 0x4400, 0x84c1, 0x8581, 0x4540, 0x8701, 0x47c0, 0x4680, 0x8641, + 0x8201, 0x42c0, 0x4380, 0x8341, 0x4100, 0x81c1, 0x8081, 0x4040 + }; + + + private int sum = 0xFFFF; + + public long getValue() { + return sum; + } + + public void reset() { + sum = 0xFFFF; + } + + public void update(byte[] b, int off, int len) { + for (int i = off; i < off + len; i++) + update((int) b[i]); + } + + public void update(int b) { + sum = (sum >> 8) ^ TABLE[((sum) ^ (b & 0xff)) & 0xff]; + } + + public byte[] getCrcBytes() { + long crc = (int) this.getValue(); + byte[] byteStr = new byte[2]; + byteStr[0] = (byte) ((crc & 0x000000ff)); + byteStr[1] = (byte) ((crc & 0x0000ff00) >>> 8); + return byteStr; + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/connectors/BluetoothConnector.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/connectors/BluetoothConnector.java new file mode 100644 index 0000000..bea6d52 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/connectors/BluetoothConnector.java @@ -0,0 +1,210 @@ +package com.example.kimentii.application20.connectors; + +import android.bluetooth.BluetoothAdapter; +import android.bluetooth.BluetoothDevice; +import android.bluetooth.BluetoothSocket; +import android.os.Handler; +import android.os.Message; +import android.util.Log; + +import com.example.kimentii.application20.constants.Constants; +import com.example.kimentii.application20.settings.Settings; + +import java.io.DataInputStream; +import java.io.DataOutputStream; +import java.io.IOException; +import java.lang.reflect.Method; +import java.util.regex.Matcher; +import java.util.regex.Pattern; + +// необзодимо переработать отсылку команд. ГУИ должно добавлять команду в буфер, а поток со +// связью должен брать команды из очереди и выполнять их +public class BluetoothConnector extends Thread { + public static final String TAG = "TAG"; + + private static BluetoothConnector bluetoothConnector; + private BluetoothSocket bluetoothSocket; + private Handler handler; + private volatile boolean isConnected = false; + private volatile boolean isRepeat = false; + private DataInputStream dataInputStream; + private DataOutputStream dataOutputStream; + + + private BluetoothConnector() { + } + + public void connect() { + BluetoothAdapter bluetoothAdapter = BluetoothAdapter.getDefaultAdapter(); + BluetoothDevice device = bluetoothAdapter.getRemoteDevice(Constants.BLUETOOTH_MAC); + try { + bluetoothSocket = createBluetoothSocket(device); + bluetoothAdapter.cancelDiscovery(); + bluetoothSocket.connect(); + Log.d(TAG, "connected to the device"); + } catch (IOException e) { + e.printStackTrace(); + Log.d(TAG, "Can't connect to the device."); + setConnected(false); + return; + } + try { + dataInputStream = new DataInputStream(bluetoothSocket.getInputStream()); + dataOutputStream = new DataOutputStream(bluetoothSocket.getOutputStream()); + } catch (IOException e) { + e.printStackTrace(); + } + setConnected(true); + start(); + } + + private BluetoothSocket createBluetoothSocket(BluetoothDevice device) throws IOException { + BluetoothSocket socket = null; + try { + Method m = device.getClass().getMethod( + "createRfcommSocket", new Class[]{int.class}); + + socket = (BluetoothSocket) m.invoke(device, 1); + } catch (Exception e) { + e.printStackTrace(); + } + return socket; + } + + + public void write(byte[] message) { + try { + if (isConnected()) { + synchronized (dataOutputStream) { + dataOutputStream.write(message); + } + } + } catch (IOException e) { + e.printStackTrace(); + } + } + + public static BluetoothConnector getInstance() { + if (bluetoothConnector == null) { + bluetoothConnector = new BluetoothConnector(); + } + return bluetoothConnector; + } + + public synchronized void setConnected(boolean connected) { + isConnected = connected; + } + + public synchronized boolean isConnected() { + return isConnected; + } + + private synchronized boolean isRepeat() { + return isRepeat; + } + + private synchronized void setRepeat(boolean repeat) { + isRepeat = repeat; + } + + public void setHandler(Handler handler) { + synchronized (handler) { + this.handler = handler; + } + } + + @Override + public void run() { + Log.d(TAG, "Bluetooth Connector started."); + write(Settings.getInstance().getApi().getConnectCommand(Settings.getInstance().getApi().getApiEnum())); + byte buf[] = new byte[100]; + setRepeat(true); + Thread autoConnector = new Thread() { + private int DELAY_TIME_IM_MS = 4000; + + @Override + public void run() { + while (isRepeat()) { + write(Settings.getInstance().getApi().getReconnectCommand()); + try { + for (int i = 0; i < 5; i++) { + synchronized (dataInputStream) { + dataInputStream.read(); + } + } + Thread.sleep(DELAY_TIME_IM_MS); + } catch (InterruptedException e) { + e.printStackTrace(); + } catch (IOException e) { + e.printStackTrace(); + } + } + } + }; + autoConnector.start(); + while (isRepeat()) { + try { + int dataSize; + byte buf2[]; + synchronized (dataInputStream) { + dataSize = dataInputStream.read(); + buf2 = new byte[dataSize]; + for (int j = 0; j < dataSize; j++) { + buf2[j] = dataInputStream.readByte(); + } + // read CTC + dataInputStream.read(); + dataInputStream.read(); + } + String str = ""; + String strChar = ""; + for (int i = 0; i < dataSize; i++) { + str += String.format("%02x ", buf2[i]); + strChar += String.format("%c", (char) buf2[i]); + } + Log.d(TAG, str); + Log.d(TAG, strChar); + if (strChar.equals("OK")) { + continue; + } else if (strChar.equals("ERROR")) { + continue; + } else { + Pattern p = Pattern.compile("([0-9]{1,3})(;)" + + "([0-9]{1,3})(;)" + "([0-9]{1,3})(;)" + "([0-9]{1,3})(;)" + "([0-9]{1,3})"); + Matcher matcher = p.matcher(strChar); + if (matcher.find()) { + Log.d(TAG, "GOOOOOOOOD"); + Log.d(TAG, "Group count: " + matcher.groupCount()); + int data[] = new int[5]; + for (int i = 0, j = 1; i < 5; i++, j += 2) { + data[i] = Integer.parseInt(matcher.group(j)); + } + if (matcher.group(1).equals("1") || matcher.group(1).equals("0")) { + Message message = handler.obtainMessage(Constants.Messages.MESSAGES_READ_LINE_SENSORS_VALUES.getValue(), + data.length, -1, data); + message.sendToTarget(); + } else { + Message message = handler.obtainMessage(Constants.Messages.MESSAGES_READ_DISTANCE_SENSORS_VALUES.getValue(), + data.length, -1, data); + message.sendToTarget(); + } + } + } + } catch (IOException e) { + e.printStackTrace(); + } + } + } + + public void disconnect() { + write(Settings.getInstance().getApi().getDisconnectCommand()); + try { + if (bluetoothSocket != null) { + bluetoothSocket.close(); + } + } catch (IOException e) { + e.printStackTrace(); + } + setRepeat(false); + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/constants/Constants.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/constants/Constants.java new file mode 100644 index 0000000..d482db4 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/constants/Constants.java @@ -0,0 +1,128 @@ +package com.example.kimentii.application20.constants; + +public interface Constants { + String BLUETOOTH_MAC = "00:21:13:03:71:23"; + + enum ApiEnum { + API1((byte) 0x01), + API2((byte) 0x02), + API3((byte) 0x03), + API4((byte) 0x04); + + private byte value; + + ApiEnum(byte value) { + this.value = value; + } + + public byte getValue() { + return value; + } + } + + enum Controllers { + MOVEMENT_CONTROLLER_ID((byte) 0x01), + SENSORS_CONTROLLER_ID((byte) 0x02), + SERVO_CONTROLLER_ID((byte) 0x03), + COMMUNICATION_CONTROLLER_ID((byte) 0x04); + + + private byte value; + + Controllers(byte value) { + this.value = value; + } + + public byte getValue() { + return value; + } + } + + enum Sensors { + DISTANCE_SENSOR((byte) 0x01), + DISTANCE_SENSOR_ALL((byte) 0x02), + LINE_SENSOR((byte) 0x03), + LINE_SENSOR_ALL((byte) 0x04); + + + private byte value; + + Sensors(byte value) { + this.value = value; + } + + public byte getValue() { + return value; + } + } + + enum Servo { + SET_HORIZONTAL_ANGLE((byte) 0x01), + SET_VERTICAL_ANGLE((byte) 0x02), + SET_HORIZONTAL_VERTICAL_ANGLES((byte) 0x03), + GET_COORDINATES((byte) 0x04), + SET_ANGLE((byte) 0x05), + GET_ANGLE((byte) 0x06); + private byte value; + + Servo(byte value) { + this.value = value; + } + + public byte getValue() { + return value; + } + } + + enum Movement { + FORWARD((byte) 0x01), + LEFT((byte) 0x02), + RIGHT((byte) 0x03), + BACK((byte) 0x04), + STOP((byte) 0x05), + FORWARD_WITH_SPEED((byte) 0x06), + TURN_IN_CLOCK_ARROW_DIRECTION((byte) 0x0A); + + + private byte value; + + Movement(byte value) { + this.value = value; + } + + public byte getValue() { + return value; + } + } + + enum Communication { + START_COMMUNICATION((byte) 0x01), + STOP_COMMUNICATION((byte) 0x02), + REFRESH_CONNECTION((byte) 0x03); + + private byte value; + + Communication(byte value) { + this.value = value; + } + + public byte getValue() { + return value; + } + } + + enum Messages { + MESSAGES_READ_DISTANCE_SENSORS_VALUES(1), + MESSAGES_READ_LINE_SENSORS_VALUES(2); + + private int value; + + Messages(int value) { + this.value = value; + } + + public int getValue() { + return value; + } + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/MotionController.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/MotionController.java new file mode 100644 index 0000000..3d4c5e7 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/MotionController.java @@ -0,0 +1,39 @@ +package com.example.kimentii.application20.controllers; + +import com.example.kimentii.application20.api.API; +import com.example.kimentii.application20.connectors.BluetoothConnector; +import com.example.kimentii.application20.settings.Settings; + +public class MotionController { + public void moveForward() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + bluetoothConnector.write(api.getMoveForwardCommand()); + } + + public void moveRight() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + bluetoothConnector.write(api.getMoveRightCommand()); + + } + + public void moveLeft() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + bluetoothConnector.write(api.getMoveLeftCommand()); + } + + public void moveBack() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + bluetoothConnector.write(api.getMoveBackCommand()); + } + + public void stop() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + bluetoothConnector.write(api.getStopCommand()); + } + +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/SensorsController.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/SensorsController.java new file mode 100644 index 0000000..8e79524 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/SensorsController.java @@ -0,0 +1,21 @@ +package com.example.kimentii.application20.controllers; + + +import com.example.kimentii.application20.api.API; +import com.example.kimentii.application20.connectors.BluetoothConnector; +import com.example.kimentii.application20.settings.Settings; + +public class SensorsController { + + public void getDataFromDistanceSensors() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + bluetoothConnector.write(api.getInfoFromAllDistanceSensorsCommand()); + } + + public void getDataFromLineSensors() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + bluetoothConnector.write(api.getInfoFromAllLineSensorsCommand()); + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/ServoController.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/ServoController.java new file mode 100644 index 0000000..8da389d --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/ServoController.java @@ -0,0 +1,55 @@ +package com.example.kimentii.application20.controllers; + +import com.example.kimentii.application20.api.API; +import com.example.kimentii.application20.connectors.BluetoothConnector; +import com.example.kimentii.application20.settings.Settings; + +public class ServoController { + public static final int MAX_ANGLE = 180; + public static final int MIN_ANGLE = 0; + + + private int angleXY; + private int angleXZ; + + public ServoController() { + angleXY = 0; + angleXZ = 0; + } + + public void turnUpOnOneDegree() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + if (angleXZ + 5 <= 180) { + angleXZ += 5; + bluetoothConnector.write(api.getSetAngleCommand(++angleXZ, API.XZ)); + } + } + + public void turnRightOnOneDegree() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + if (angleXY + 5 <= 180) { + angleXY += 5; + bluetoothConnector.write(api.getSetAngleCommand(++angleXY, API.XY)); + } + } + + public void turnLeftOnOneDegree() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + if (angleXY - 5 >= 0) { + angleXY -= 5; + bluetoothConnector.write(api.getSetAngleCommand(angleXY, API.XY)); + } + } + + public void turnDownOnOneDegree() { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + if (angleXZ - 5 >= 0) { + angleXZ -= 5; + bluetoothConnector.write(api.getSetAngleCommand(angleXZ, API.XZ)); + } + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/SettingsController.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/SettingsController.java new file mode 100644 index 0000000..e4d0a5e --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/SettingsController.java @@ -0,0 +1,15 @@ +package com.example.kimentii.application20.controllers; + +import com.example.kimentii.application20.api.API; +import com.example.kimentii.application20.connectors.BluetoothConnector; +import com.example.kimentii.application20.constants.Constants; +import com.example.kimentii.application20.settings.Settings; + +public class SettingsController { + public void changeAPI(Constants.ApiEnum apiEnum) { + BluetoothConnector bluetoothConnector = BluetoothConnector.getInstance(); + API api = Settings.getInstance().getApi(); + bluetoothConnector.write(api.getDisconnectCommand()); + bluetoothConnector.write(api.getConnectCommand(apiEnum)); + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/language_resources/EnglishLanguage.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/language_resources/EnglishLanguage.java new file mode 100644 index 0000000..a6dd562 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/language_resources/EnglishLanguage.java @@ -0,0 +1,74 @@ +package com.example.kimentii.application20.language_resources; + + +import com.example.kimentii.application20.wrappers.LanguageWrapper; + +import java.util.ListResourceBundle; + +public class EnglishLanguage extends ListResourceBundle { + @Override + protected Object[][] getContents() { + Object[][] resources = new Object[24][2]; + int i = 0; + resources[i][0] = LanguageWrapper.NO_CONNECTION; + resources[i++][1] = "no connection"; + resources[i][0] = LanguageWrapper.CONNECTED; + resources[i++][1] = "connected"; + + // main menu activity + resources[i][0] = LanguageWrapper.MOTION_BUTTON; + resources[i++][1] = "motion"; + resources[i][0] = LanguageWrapper.SERVO_BUTTON; + resources[i++][1] = "servo"; + resources[i][0] = LanguageWrapper.SENSORS_BUTTON; + resources[i++][1] = "sensors"; + resources[i][0] = LanguageWrapper.SETTINGS_BUTTON; + resources[i++][1] = "settings"; + resources[i][0] = LanguageWrapper.EXIT_BUTTON; + resources[i++][1] = "exit"; + + // motion activity + resources[i][0] = LanguageWrapper.FORWARD_BUTTON; + resources[i++][1] = "forward"; + resources[i][0] = LanguageWrapper.RIGHT_BUTTON; + resources[i++][1] = "right"; + resources[i][0] = LanguageWrapper.LEFT_BUTTON; + resources[i++][1] = "left"; + resources[i][0] = LanguageWrapper.BACK_BUTTON; + resources[i++][1] = "back"; + resources[i][0] = LanguageWrapper.STOP_BUTTON; + resources[i++][1] = "stop"; + + // servo activity + resources[i][0] = LanguageWrapper.UP_SERVO_BUTTON; + resources[i++][1] = "up"; + resources[i][0] = LanguageWrapper.RIGHT_SERVO_BUTTON; + resources[i++][1] = "right"; + resources[i][0] = LanguageWrapper.LEFT_SERVO_BUTTON; + resources[i++][1] = "left"; + resources[i][0] = LanguageWrapper.DOWN_SERVO_BUTTON; + resources[i++][1] = "down"; + + // sensors activity + resources[i][0] = LanguageWrapper.DISTANCE_SENSORS; + resources[i++][1] = "Distance sensors"; + resources[i][0] = LanguageWrapper.LINE_SENSORS; + resources[i++][1] = "Line sensors"; + resources[i][0] = LanguageWrapper.FIRST_SENSOR; + resources[i++][1] = "First sensor"; + resources[i][0] = LanguageWrapper.SECOND_SENSOR; + resources[i++][1] = "Second sensor"; + resources[i][0] = LanguageWrapper.THIRD_SENSOR; + resources[i++][1] = "Third sensor"; + resources[i][0] = LanguageWrapper.FOURTH_SENSOR; + resources[i++][1] = "Fourth sensor"; + resources[i][0] = LanguageWrapper.FIFTH_SENSOR; + resources[i++][1] = "Fifth sensor"; + + // settings activity + resources[i][0] = LanguageWrapper.LANGUAGE; + resources[i++][1] = "Language"; + + return resources; + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/language_resources/RussianLanguage.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/language_resources/RussianLanguage.java new file mode 100644 index 0000000..5d1c7d8 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/language_resources/RussianLanguage.java @@ -0,0 +1,73 @@ +package com.example.kimentii.application20.language_resources; + +import com.example.kimentii.application20.wrappers.LanguageWrapper; + +import java.util.ListResourceBundle; + +public class RussianLanguage extends ListResourceBundle { + @Override + protected Object[][] getContents() { + Object[][] resources = new Object[24][2]; + int i = 0; + resources[i][0] = LanguageWrapper.NO_CONNECTION; + resources[i++][1] = "нет подключения"; + resources[i][0] = LanguageWrapper.CONNECTED; + resources[i++][1] = "подключен"; + + // main menu activity + resources[i][0] = LanguageWrapper.MOTION_BUTTON; + resources[i++][1] = "движение"; + resources[i][0] = LanguageWrapper.SERVO_BUTTON; + resources[i++][1] = "сервоприводы"; + resources[i][0] = LanguageWrapper.SENSORS_BUTTON; + resources[i++][1] = "сенсоры"; + resources[i][0] = LanguageWrapper.SETTINGS_BUTTON; + resources[i++][1] = "настройки"; + resources[i][0] = LanguageWrapper.EXIT_BUTTON; + resources[i++][1] = "выход"; + + // motion activity + resources[i][0] = LanguageWrapper.FORWARD_BUTTON; + resources[i++][1] = "вперед"; + resources[i][0] = LanguageWrapper.RIGHT_BUTTON; + resources[i++][1] = "вправо"; + resources[i][0] = LanguageWrapper.LEFT_BUTTON; + resources[i++][1] = "влево"; + resources[i][0] = LanguageWrapper.BACK_BUTTON; + resources[i++][1] = "назад"; + resources[i][0] = LanguageWrapper.STOP_BUTTON; + resources[i++][1] = "стоп"; + + // servo activity + resources[i][0] = LanguageWrapper.UP_SERVO_BUTTON; + resources[i++][1] = "вверх"; + resources[i][0] = LanguageWrapper.RIGHT_SERVO_BUTTON; + resources[i++][1] = "вправо"; + resources[i][0] = LanguageWrapper.LEFT_SERVO_BUTTON; + resources[i++][1] = "влево"; + resources[i][0] = LanguageWrapper.DOWN_SERVO_BUTTON; + resources[i++][1] = "вниз"; + + // sensors activity + resources[i][0] = LanguageWrapper.DISTANCE_SENSORS; + resources[i++][1] = "Датчики расстояния"; + resources[i][0] = LanguageWrapper.LINE_SENSORS; + resources[i++][1] = "Дитчики линии"; + resources[i][0] = LanguageWrapper.FIRST_SENSOR; + resources[i++][1] = "Первый датчик"; + resources[i][0] = LanguageWrapper.SECOND_SENSOR; + resources[i++][1] = "Второй датчик"; + resources[i][0] = LanguageWrapper.THIRD_SENSOR; + resources[i++][1] = "Третий датчик"; + resources[i][0] = LanguageWrapper.FOURTH_SENSOR; + resources[i++][1] = "Четвертый датчик"; + resources[i][0] = LanguageWrapper.FIFTH_SENSOR; + resources[i++][1] = "Пятый датчик"; + + // settings activity + resources[i][0] = LanguageWrapper.LANGUAGE; + resources[i++][1] = "Язык"; + + return resources; + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/settings/Settings.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/settings/Settings.java new file mode 100644 index 0000000..722c6f3 --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/settings/Settings.java @@ -0,0 +1,53 @@ +package com.example.kimentii.application20.settings; + +import com.example.kimentii.application20.api.API; +import com.example.kimentii.application20.api.API1; +import com.example.kimentii.application20.api.API2; +import com.example.kimentii.application20.api.API3; +import com.example.kimentii.application20.api.API4; +import com.example.kimentii.application20.connectors.BluetoothConnector; +import com.example.kimentii.application20.constants.Constants; +import com.example.kimentii.application20.wrappers.LanguageWrapper; + +public class Settings { + private LanguageWrapper languageWrapper; + private API api; + private static Settings settings; + + private Settings() { + languageWrapper = new LanguageWrapper(LanguageWrapper.ENGLISH); + api = new API4(); + } + + public static Settings getInstance() { + if (settings == null) { + settings = new Settings(); + } + return settings; + } + + public LanguageWrapper getLanguageWrapper() { + return languageWrapper; + } + + public API getApi() { + return api; + } + + public void setApi(Constants.ApiEnum api) { + switch (api) { + case API1: + this.api = new API1(); + break; + case API2: + this.api = new API2(); + break; + case API3: + this.api = new API3(); + break; + case API4: + this.api = new API4(); + break; + } + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/wrappers/LanguageWrapper.java b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/wrappers/LanguageWrapper.java new file mode 100644 index 0000000..260b64b --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/wrappers/LanguageWrapper.java @@ -0,0 +1,66 @@ +package com.example.kimentii.application20.wrappers; + +import java.util.ResourceBundle; + +public class LanguageWrapper { + public static final String RUSSIAN = "RUSSIAN"; + public static final String ENGLISH = "ENGLISH"; + public static final String NO_CONNECTION = "no connection"; + public static final String CONNECTED = "connected"; + + // main menu buttons + public static final String MOTION_BUTTON = "motion button"; + public static final String SERVO_BUTTON = "servo button"; + public static final String SENSORS_BUTTON = "sensors button"; + public static final String SETTINGS_BUTTON = "settings button"; + public static final String EXIT_BUTTON = "exit button"; + + // motion activity buttons + public static final String FORWARD_BUTTON = "forward button"; + public static final String RIGHT_BUTTON = "right button"; + public static final String LEFT_BUTTON = "left button"; + public static final String BACK_BUTTON = "back button"; + public static final String STOP_BUTTON = "stop button"; + + // servo activity buttons + public static final String UP_SERVO_BUTTON = "up servo button"; + public static final String RIGHT_SERVO_BUTTON = "right servo button"; + public static final String LEFT_SERVO_BUTTON = "left servo button"; + public static final String DOWN_SERVO_BUTTON = "down servo button"; + + // sensors activity + public static final String DISTANCE_SENSORS = "distance sensors"; + public static final String LINE_SENSORS = "line sensors"; + public static final String FIRST_SENSOR = "first sensor"; + public static final String SECOND_SENSOR = "second sensor"; + public static final String THIRD_SENSOR = "third sensor"; + public static final String FOURTH_SENSOR = "fourth sensor"; + public static final String FIFTH_SENSOR = "fifth sensor"; + + // settings activity + public static final String LANGUAGE = "language"; + + private ResourceBundle languageResourceBundle; + private String language; + + public LanguageWrapper(String language) { + setLanguage(language); + } + + public void setLanguage(String language) { + if (language.equals(RUSSIAN)) { + languageResourceBundle = ResourceBundle.getBundle("com.example.kimentii.application20.language_resources.RussianLanguage"); + } else { + languageResourceBundle = ResourceBundle.getBundle("com.example.kimentii.application20.language_resources.EnglishLanguage"); + } + this.language = language; + } + + public String getViewString(String key) { + return languageResourceBundle.getString(key); + } + + public String getLanguage() { + return language; + } +} diff --git a/code/Java/Mobile/Application2.0/app/src/main/res/layout/activity_main.xml b/code/Java/Mobile/Application2.0/app/src/main/res/layout/activity_main.xml new file mode 100644 index 0000000..29b1eba --- /dev/null +++ b/code/Java/Mobile/Application2.0/app/src/main/res/layout/activity_main.xml @@ -0,0 +1,58 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/code/c#/Sample App/MainWindow.xaml.cs b/code/c#/Sample App/MainWindow.xaml.cs new file mode 100644 index 0000000..a6fbcf5 --- /dev/null +++ b/code/c#/Sample App/MainWindow.xaml.cs @@ -0,0 +1,45 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Runtime.InteropServices; +using System.Text; +using System.Windows; +using System.Windows.Controls; +using System.Windows.Data; +using System.Windows.Documents; +using System.Windows.Input; +using System.Windows.Media; +using System.Windows.Media.Imaging; +using System.Windows.Navigation; +using System.Windows.Shapes; + +namespace Sample_App +{ + /// + /// Interaction logic for MainWindow.xaml + /// + public partial class MainWindow : Window + { + private readonly MainWindowViewModel _vm; + + public MainWindow() + { + InitializeComponent(); + _vm = DataContext as MainWindowViewModel; + + //Dispose resources + Dispatcher.ShutdownStarted += (sender, args) => + { + _vm.Dispose(); + }; + } + + private void OnConnectClicked(object sender, RoutedEventArgs e) + { + if (!_vm.ToggleConnection()) + { + MessageBox.Show("Cannot connect or disconnect from device"); + } + } + } +} diff --git a/code/c#/Sample App/MainWindowViewModel.cs b/code/c#/Sample App/MainWindowViewModel.cs new file mode 100644 index 0000000..c80199e --- /dev/null +++ b/code/c#/Sample App/MainWindowViewModel.cs @@ -0,0 +1,134 @@ +using System; +using System.ComponentModel; +using System.Windows; +using System.Windows.Threading; + +namespace Sample_App +{ + public class MainWindowViewModel : INotifyPropertyChanged, IDisposable + { + #region INotifyPropertyChanged implementation + + /// + /// Call to change property + /// + /// Property type + /// New property value + /// Field with old property value (masked field) + /// Name of property + protected void ChangeProperty(ref T value, ref T maskedValue, string propertyName) + { + bool isChanged; + if (maskedValue == null) + { + isChanged = (value != null); + } + else + { + isChanged = !maskedValue.Equals(value); + } + maskedValue = value; + if (isChanged) + { + OnPropertyChanged(propertyName); + } + } + + public event PropertyChangedEventHandler PropertyChanged; + + protected virtual void OnPropertyChanged(string propertyName) + { + PropertyChanged?.Invoke(this, new PropertyChangedEventArgs(propertyName)); + } + + #endregion + + private bool _maskIsConnected = false; + + private const int DinstanseNum = 5; + private const int LineNum = 5; + private const int LineWhite = 0; + + public uint[] Distanse { get; } = new uint[DinstanseNum]; + /// + /// Contains true if Line is white, else false + /// + public bool[] Line { get; } = new bool[LineNum]; + + public string SelectedPort { get; set; } + public uint Speed { get; } = 9600; + + public bool IsConnected + { + get => _maskIsConnected; + set => ChangeProperty(ref value, ref _maskIsConnected, nameof(IsConnected)); + } + + private readonly ApiManager _api; + + public MainWindowViewModel() + { + ApiManager.SensorCallback lineCallback = (index, value) => + { + Line[index] = (value == LineWhite); + OnPropertyChanged(nameof(Line)); + }; + ApiManager.SensorCallback distanceCallback = (index, value) => + { + Distanse[index] = value; + OnPropertyChanged(nameof(Distanse)); + }; + + _api = new ApiManager(distanceCallback, lineCallback); + } + + /// + /// Connect to device with selected configuration + /// + /// true, if successfully connected, else false + private bool Connect() + { + bool res = _api.ConnectToDevice(SelectedPort, Speed); + IsConnected = res; + return res; + } + + /// + /// Disconnect from device + /// + private void Disconnect() + { + _api.Disconnect(); + IsConnected = false; + } + + /// + /// Toggle connection to device + /// + /// true if all is successful, else false + public bool ToggleConnection() + { + try + { + if (IsConnected) + { + Disconnect(); + return true; + } + + return Connect(); + } + catch (Exception e) + { + MessageBox.Show(e.Message, "We have an error", MessageBoxButton.OK, MessageBoxImage.Error); + IsConnected = false; + return false; + } + } + + public void Dispose() + { + _api?.Dispose(); + } + } +} \ No newline at end of file diff --git a/code/c#/Sample App/Properties/AssemblyInfo.cs b/code/c#/Sample App/Properties/AssemblyInfo.cs new file mode 100644 index 0000000..fe295f7 --- /dev/null +++ b/code/c#/Sample App/Properties/AssemblyInfo.cs @@ -0,0 +1,55 @@ +using System.Reflection; +using System.Resources; +using System.Runtime.CompilerServices; +using System.Runtime.InteropServices; +using System.Windows; + +// General Information about an assembly is controlled through the following +// set of attributes. Change these attribute values to modify the information +// associated with an assembly. +[assembly: AssemblyTitle("Sample App")] +[assembly: AssemblyDescription("")] +[assembly: AssemblyConfiguration("")] +[assembly: AssemblyCompany("")] +[assembly: AssemblyProduct("Sample App")] +[assembly: AssemblyCopyright("Copyright © 2017")] +[assembly: AssemblyTrademark("")] +[assembly: AssemblyCulture("")] + +// Setting ComVisible to false makes the types in this assembly not visible +// to COM components. If you need to access a type in this assembly from +// COM, set the ComVisible attribute to true on that type. +[assembly: ComVisible(false)] + +//In order to begin building localizable applications, set +//CultureYouAreCodingWith in your .csproj file +//inside a . For example, if you are using US english +//in your source files, set the to en-US. Then uncomment +//the NeutralResourceLanguage attribute below. Update the "en-US" in +//the line below to match the UICulture setting in the project file. + +//[assembly: NeutralResourcesLanguage("en-US", UltimateResourceFallbackLocation.Satellite)] + + +[assembly: ThemeInfo( + ResourceDictionaryLocation.None, //where theme specific resource dictionaries are located + //(used if a resource is not found in the page, + // or application resource dictionaries) + ResourceDictionaryLocation.SourceAssembly //where the generic resource dictionary is located + //(used if a resource is not found in the page, + // app, or any theme specific resource dictionaries) +)] + + +// Version information for an assembly consists of the following four values: +// +// Major Version +// Minor Version +// Build Number +// Revision +// +// You can specify all the values or you can default the Build and Revision Numbers +// by using the '*' as shown below: +// [assembly: AssemblyVersion("1.0.*")] +[assembly: AssemblyVersion("1.0.0.0")] +[assembly: AssemblyFileVersion("1.0.0.0")] diff --git a/code/c#/Sample App/Properties/Resources.Designer.cs b/code/c#/Sample App/Properties/Resources.Designer.cs new file mode 100644 index 0000000..6f1c9f9 --- /dev/null +++ b/code/c#/Sample App/Properties/Resources.Designer.cs @@ -0,0 +1,71 @@ +//------------------------------------------------------------------------------ +// +// This code was generated by a tool. +// Runtime Version:4.0.30319.42000 +// +// Changes to this file may cause incorrect behavior and will be lost if +// the code is regenerated. +// +//------------------------------------------------------------------------------ + +namespace Sample_App.Properties +{ + + + /// + /// A strongly-typed resource class, for looking up localized strings, etc. + /// + // This class was auto-generated by the StronglyTypedResourceBuilder + // class via a tool like ResGen or Visual Studio. + // To add or remove a member, edit your .ResX file then rerun ResGen + // with the /str option, or rebuild your VS project. + [global::System.CodeDom.Compiler.GeneratedCodeAttribute("System.Resources.Tools.StronglyTypedResourceBuilder", "4.0.0.0")] + [global::System.Diagnostics.DebuggerNonUserCodeAttribute()] + [global::System.Runtime.CompilerServices.CompilerGeneratedAttribute()] + internal class Resources + { + + private static global::System.Resources.ResourceManager resourceMan; + + private static global::System.Globalization.CultureInfo resourceCulture; + + [global::System.Diagnostics.CodeAnalysis.SuppressMessageAttribute("Microsoft.Performance", "CA1811:AvoidUncalledPrivateCode")] + internal Resources() + { + } + + /// + /// Returns the cached ResourceManager instance used by this class. + /// + [global::System.ComponentModel.EditorBrowsableAttribute(global::System.ComponentModel.EditorBrowsableState.Advanced)] + internal static global::System.Resources.ResourceManager ResourceManager + { + get + { + if ((resourceMan == null)) + { + global::System.Resources.ResourceManager temp = new global::System.Resources.ResourceManager("Sample_App.Properties.Resources", typeof(Resources).Assembly); + resourceMan = temp; + } + return resourceMan; + } + } + + /// + /// Overrides the current thread's CurrentUICulture property for all + /// resource lookups using this strongly typed resource class. + /// + [global::System.ComponentModel.EditorBrowsableAttribute(global::System.ComponentModel.EditorBrowsableState.Advanced)] + internal static global::System.Globalization.CultureInfo Culture + { + get + { + return resourceCulture; + } + set + { + resourceCulture = value; + } + } + } +} diff --git a/code/c#/Sample App/Properties/Resources.resx b/code/c#/Sample App/Properties/Resources.resx new file mode 100644 index 0000000..af7dbeb --- /dev/null +++ b/code/c#/Sample App/Properties/Resources.resx @@ -0,0 +1,117 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + \ No newline at end of file diff --git a/code/c#/Sample App/Properties/Settings.Designer.cs b/code/c#/Sample App/Properties/Settings.Designer.cs new file mode 100644 index 0000000..e7042ac --- /dev/null +++ b/code/c#/Sample App/Properties/Settings.Designer.cs @@ -0,0 +1,30 @@ +//------------------------------------------------------------------------------ +// +// This code was generated by a tool. +// Runtime Version:4.0.30319.42000 +// +// Changes to this file may cause incorrect behavior and will be lost if +// the code is regenerated. +// +//------------------------------------------------------------------------------ + +namespace Sample_App.Properties +{ + + + [global::System.Runtime.CompilerServices.CompilerGeneratedAttribute()] + [global::System.CodeDom.Compiler.GeneratedCodeAttribute("Microsoft.VisualStudio.Editors.SettingsDesigner.SettingsSingleFileGenerator", "11.0.0.0")] + internal sealed partial class Settings : global::System.Configuration.ApplicationSettingsBase + { + + private static Settings defaultInstance = ((Settings)(global::System.Configuration.ApplicationSettingsBase.Synchronized(new Settings()))); + + public static Settings Default + { + get + { + return defaultInstance; + } + } + } +} diff --git a/code/c#/Sample App/Properties/Settings.settings b/code/c#/Sample App/Properties/Settings.settings new file mode 100644 index 0000000..033d7a5 --- /dev/null +++ b/code/c#/Sample App/Properties/Settings.settings @@ -0,0 +1,7 @@ + + + + + + + \ No newline at end of file diff --git a/code/c#/Sample App/Sample App.csproj b/code/c#/Sample App/Sample App.csproj new file mode 100644 index 0000000..5325cd7 --- /dev/null +++ b/code/c#/Sample App/Sample App.csproj @@ -0,0 +1,96 @@ + + + + + Debug + AnyCPU + {73F9C67C-685E-4C8E-A9B5-4F0D83A0B0A1} + WinExe + Sample_App + Sample App + v4.0 + 512 + {60dc8134-eba5-43b8-bcc9-bb4bc16c2548};{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC} + 4 + + + x86 + true + full + false + bin\Debug\ + DEBUG;TRACE + prompt + 4 + true + + + x86 + pdbonly + true + bin\Release\ + TRACE + prompt + 4 + true + + + + + + + + + + + 4.0 + + + + + + + + MSBuild:Compile + Designer + + + MSBuild:Compile + Designer + + + + App.xaml + Code + + + MainWindow.xaml + Code + + + + + + Code + + + True + True + Resources.resx + + + True + Settings.settings + True + + + ResXFileCodeGenerator + Resources.Designer.cs + + + SettingsSingleFileGenerator + Settings.Designer.cs + + + + \ No newline at end of file diff --git a/code/c++/.gitignore b/code/c++/.gitignore new file mode 100644 index 0000000..1d434d3 --- /dev/null +++ b/code/c++/.gitignore @@ -0,0 +1,299 @@ +## Ignore Visual Studio temporary files, build results, and +## files generated by popular Visual Studio add-ons. +## +## Get latest from https://github.com/github/gitignore/blob/master/VisualStudio.gitignore + +# User-specific files +*.suo +*.user +*.userosscache +*.sln.docstates + +# User-specific files (MonoDevelop/Xamarin Studio) +*.userprefs + +# Build results +[Dd]ebug/ +[Dd]ebugPublic/ +[Rr]elease/ +[Rr]eleases/ +x64/ +x86/ +bld/ +[Bb]in/ +[Oo]bj/ +[Ll]og/ + +# Visual Studio 2015 cache/options directory +.vs/ +# Uncomment if you have tasks that create the project's static files in wwwroot +#wwwroot/ + +# MSTest test Results +[Tt]est[Rr]esult*/ +[Bb]uild[Ll]og.* + +# NUNIT +*.VisualState.xml +TestResult.xml + +# Build Results of an ATL Project +[Dd]ebugPS/ +[Rr]eleasePS/ +dlldata.c + +# Benchmark Results +BenchmarkDotNet.Artifacts/ + +# .NET Core +project.lock.json +project.fragment.lock.json +artifacts/ +**/Properties/launchSettings.json + +*_i.c +*_p.c +*_i.h +*.ilk +*.meta +*.obj +*.pch +*.pdb +*.pgc +*.pgd +*.rsp +*.sbr +*.tlb +*.tli +*.tlh +*.tmp +*.tmp_proj +*.log +*.vspscc +*.vssscc +.builds +*.pidb +*.svclog +*.scc + +# Chutzpah Test files +_Chutzpah* + +# Visual C++ cache files +ipch/ +*.aps +*.ncb +*.opendb +*.opensdf +*.sdf +*.cachefile +*.VC.db +*.VC.VC.opendb + +# Visual Studio profiler +*.psess +*.vsp +*.vspx +*.sap + +# TFS 2012 Local Workspace +$tf/ + +# Guidance Automation Toolkit +*.gpState + +# ReSharper is a .NET coding add-in +_ReSharper*/ +*.[Rr]e[Ss]harper +*.DotSettings.user + +# JustCode is a .NET coding add-in +.JustCode + +# TeamCity is a build add-in +_TeamCity* + +# DotCover is a Code Coverage Tool +*.dotCover + +# Visual Studio code coverage results +*.coverage +*.coveragexml + +# NCrunch +_NCrunch_* +.*crunch*.local.xml +nCrunchTemp_* + +# MightyMoose +*.mm.* +AutoTest.Net/ + +# Web workbench (sass) +.sass-cache/ + +# Installshield output folder +[Ee]xpress/ + +# DocProject is a documentation generator add-in +DocProject/buildhelp/ +DocProject/Help/*.HxT +DocProject/Help/*.HxC +DocProject/Help/*.hhc +DocProject/Help/*.hhk +DocProject/Help/*.hhp +DocProject/Help/Html2 +DocProject/Help/html + +# Click-Once directory +publish/ + +# Publish Web Output +*.[Pp]ublish.xml +*.azurePubxml +# TODO: Comment the next line if you want to checkin your web deploy settings +# but database connection strings (with potential passwords) will be unencrypted +*.pubxml +*.publishproj + +# Microsoft Azure Web App publish settings. Comment the next line if you want to +# checkin your Azure Web App publish settings, but sensitive information contained +# in these scripts will be unencrypted +PublishScripts/ + +# NuGet Packages +*.nupkg +# The packages folder can be ignored because of Package Restore +**/packages/* +# except build/, which is used as an MSBuild target. +!**/packages/build/ +# Uncomment if necessary however generally it will be regenerated when needed +#!**/packages/repositories.config +# NuGet v3's project.json files produces more ignorable files +*.nuget.props +*.nuget.targets + +# Microsoft Azure Build Output +csx/ +*.build.csdef + +# Microsoft Azure Emulator +ecf/ +rcf/ + +# Windows Store app package directories and files +AppPackages/ +BundleArtifacts/ +Package.StoreAssociation.xml +_pkginfo.txt +*.appx + +# Visual Studio cache files +# files ending in .cache can be ignored +*.[Cc]ache +# but keep track of directories ending in .cache +!*.[Cc]ache/ + +# Others +ClientBin/ +~$* +*~ +*.dbmdl +*.dbproj.schemaview +*.jfm +*.pfx +*.publishsettings +orleans.codegen.cs + +# Since there are multiple workflows, uncomment next line to ignore bower_components +# (https://github.com/github/gitignore/pull/1529#issuecomment-104372622) +#bower_components/ + +# RIA/Silverlight projects +Generated_Code/ + +# Backup & report files from converting an old project file +# to a newer Visual Studio version. Backup files are not needed, +# because we have git ;-) +_UpgradeReport_Files/ +Backup*/ +UpgradeLog*.XML +UpgradeLog*.htm + +# SQL Server files +*.mdf +*.ldf +*.ndf + +# Business Intelligence projects +*.rdl.data +*.bim.layout +*.bim_*.settings + +# Microsoft Fakes +FakesAssemblies/ + +# GhostDoc plugin setting file +*.GhostDoc.xml + +# Node.js Tools for Visual Studio +.ntvs_analysis.dat +node_modules/ + +# Typescript v1 declaration files +typings/ + +# Visual Studio 6 build log +*.plg + +# Visual Studio 6 workspace options file +*.opt + +# Visual Studio 6 auto-generated workspace file (contains which files were open etc.) +*.vbw + +# Visual Studio LightSwitch build output +**/*.HTMLClient/GeneratedArtifacts +**/*.DesktopClient/GeneratedArtifacts +**/*.DesktopClient/ModelManifest.xml +**/*.Server/GeneratedArtifacts +**/*.Server/ModelManifest.xml +_Pvt_Extensions + +# Paket dependency manager +.paket/paket.exe +paket-files/ + +# FAKE - F# Make +.fake/ + +# JetBrains Rider +.idea/ +*.sln.iml + +# CodeRush +.cr/ + +# Python Tools for Visual Studio (PTVS) +__pycache__/ +*.pyc + +# Cake - Uncomment if you are using it +# tools/** +# !tools/packages.config + +# Tabs Studio +*.tss + +# Telerik's JustMock configuration file +*.jmconfig + +# BizTalk build output +*.btp.cs +*.btm.cs +*.odx.cs +*.xsd.cs + +# AJIOB_Exclude +Output +Build* diff --git a/code/c++/cxx-api/.gitignore b/code/c++/cxx-api/.gitignore new file mode 100644 index 0000000..1d434d3 --- /dev/null +++ b/code/c++/cxx-api/.gitignore @@ -0,0 +1,299 @@ +## Ignore Visual Studio temporary files, build results, and +## files generated by popular Visual Studio add-ons. +## +## Get latest from https://github.com/github/gitignore/blob/master/VisualStudio.gitignore + +# User-specific files +*.suo +*.user +*.userosscache +*.sln.docstates + +# User-specific files (MonoDevelop/Xamarin Studio) +*.userprefs + +# Build results +[Dd]ebug/ +[Dd]ebugPublic/ +[Rr]elease/ +[Rr]eleases/ +x64/ +x86/ +bld/ +[Bb]in/ +[Oo]bj/ +[Ll]og/ + +# Visual Studio 2015 cache/options directory +.vs/ +# Uncomment if you have tasks that create the project's static files in wwwroot +#wwwroot/ + +# MSTest test Results +[Tt]est[Rr]esult*/ +[Bb]uild[Ll]og.* + +# NUNIT +*.VisualState.xml +TestResult.xml + +# Build Results of an ATL Project +[Dd]ebugPS/ +[Rr]eleasePS/ +dlldata.c + +# Benchmark Results +BenchmarkDotNet.Artifacts/ + +# .NET Core +project.lock.json +project.fragment.lock.json +artifacts/ +**/Properties/launchSettings.json + +*_i.c +*_p.c +*_i.h +*.ilk +*.meta +*.obj +*.pch +*.pdb +*.pgc +*.pgd +*.rsp +*.sbr +*.tlb +*.tli +*.tlh +*.tmp +*.tmp_proj +*.log +*.vspscc +*.vssscc +.builds +*.pidb +*.svclog +*.scc + +# Chutzpah Test files +_Chutzpah* + +# Visual C++ cache files +ipch/ +*.aps +*.ncb +*.opendb +*.opensdf +*.sdf +*.cachefile +*.VC.db +*.VC.VC.opendb + +# Visual Studio profiler +*.psess +*.vsp +*.vspx +*.sap + +# TFS 2012 Local Workspace +$tf/ + +# Guidance Automation Toolkit +*.gpState + +# ReSharper is a .NET coding add-in +_ReSharper*/ +*.[Rr]e[Ss]harper +*.DotSettings.user + +# JustCode is a .NET coding add-in +.JustCode + +# TeamCity is a build add-in +_TeamCity* + +# DotCover is a Code Coverage Tool +*.dotCover + +# Visual Studio code coverage results +*.coverage +*.coveragexml + +# NCrunch +_NCrunch_* +.*crunch*.local.xml +nCrunchTemp_* + +# MightyMoose +*.mm.* +AutoTest.Net/ + +# Web workbench (sass) +.sass-cache/ + +# Installshield output folder +[Ee]xpress/ + +# DocProject is a documentation generator add-in +DocProject/buildhelp/ +DocProject/Help/*.HxT +DocProject/Help/*.HxC +DocProject/Help/*.hhc +DocProject/Help/*.hhk +DocProject/Help/*.hhp +DocProject/Help/Html2 +DocProject/Help/html + +# Click-Once directory +publish/ + +# Publish Web Output +*.[Pp]ublish.xml +*.azurePubxml +# TODO: Comment the next line if you want to checkin your web deploy settings +# but database connection strings (with potential passwords) will be unencrypted +*.pubxml +*.publishproj + +# Microsoft Azure Web App publish settings. Comment the next line if you want to +# checkin your Azure Web App publish settings, but sensitive information contained +# in these scripts will be unencrypted +PublishScripts/ + +# NuGet Packages +*.nupkg +# The packages folder can be ignored because of Package Restore +**/packages/* +# except build/, which is used as an MSBuild target. +!**/packages/build/ +# Uncomment if necessary however generally it will be regenerated when needed +#!**/packages/repositories.config +# NuGet v3's project.json files produces more ignorable files +*.nuget.props +*.nuget.targets + +# Microsoft Azure Build Output +csx/ +*.build.csdef + +# Microsoft Azure Emulator +ecf/ +rcf/ + +# Windows Store app package directories and files +AppPackages/ +BundleArtifacts/ +Package.StoreAssociation.xml +_pkginfo.txt +*.appx + +# Visual Studio cache files +# files ending in .cache can be ignored +*.[Cc]ache +# but keep track of directories ending in .cache +!*.[Cc]ache/ + +# Others +ClientBin/ +~$* +*~ +*.dbmdl +*.dbproj.schemaview +*.jfm +*.pfx +*.publishsettings +orleans.codegen.cs + +# Since there are multiple workflows, uncomment next line to ignore bower_components +# (https://github.com/github/gitignore/pull/1529#issuecomment-104372622) +#bower_components/ + +# RIA/Silverlight projects +Generated_Code/ + +# Backup & report files from converting an old project file +# to a newer Visual Studio version. Backup files are not needed, +# because we have git ;-) +_UpgradeReport_Files/ +Backup*/ +UpgradeLog*.XML +UpgradeLog*.htm + +# SQL Server files +*.mdf +*.ldf +*.ndf + +# Business Intelligence projects +*.rdl.data +*.bim.layout +*.bim_*.settings + +# Microsoft Fakes +FakesAssemblies/ + +# GhostDoc plugin setting file +*.GhostDoc.xml + +# Node.js Tools for Visual Studio +.ntvs_analysis.dat +node_modules/ + +# Typescript v1 declaration files +typings/ + +# Visual Studio 6 build log +*.plg + +# Visual Studio 6 workspace options file +*.opt + +# Visual Studio 6 auto-generated workspace file (contains which files were open etc.) +*.vbw + +# Visual Studio LightSwitch build output +**/*.HTMLClient/GeneratedArtifacts +**/*.DesktopClient/GeneratedArtifacts +**/*.DesktopClient/ModelManifest.xml +**/*.Server/GeneratedArtifacts +**/*.Server/ModelManifest.xml +_Pvt_Extensions + +# Paket dependency manager +.paket/paket.exe +paket-files/ + +# FAKE - F# Make +.fake/ + +# JetBrains Rider +.idea/ +*.sln.iml + +# CodeRush +.cr/ + +# Python Tools for Visual Studio (PTVS) +__pycache__/ +*.pyc + +# Cake - Uncomment if you are using it +# tools/** +# !tools/packages.config + +# Tabs Studio +*.tss + +# Telerik's JustMock configuration file +*.jmconfig + +# BizTalk build output +*.btp.cs +*.btm.cs +*.odx.cs +*.xsd.cs + +# AJIOB_Exclude +Output +Build* diff --git a/code/c++/cxx-api/AutoConnector.cpp b/code/c++/cxx-api/AutoConnector.cpp new file mode 100644 index 0000000..d7a9834 --- /dev/null +++ b/code/c++/cxx-api/AutoConnector.cpp @@ -0,0 +1,42 @@ +#include "AutoConnector.h" + +AutoConnector::AutoConnector(std::function c, uint32_t f) : pConnectingThread(nullptr), callback(c), + frequency(f) +{ + isRepeat.store(false); +} + +AutoConnector::~AutoConnector() { + stop(); +} + +void AutoConnector::start() { + if (!isRepeat.load() && !pConnectingThread) + { + Data d; + d.callback = callback; + d.pIsRepeat = &isRepeat; + d.frequency = frequency; + isRepeat.store(true); + pConnectingThread = new std::thread([d]() { + while (d.pIsRepeat->load()) + { + d.callback(); + std::this_thread::sleep_for(std::chrono::milliseconds(d.frequency)); + } + }); + } +} + +void AutoConnector::stop() { + if (isRepeat.load() && pConnectingThread) { + isRepeat.store(false); + pConnectingThread->join(); + delete pConnectingThread; + pConnectingThread = nullptr; + } +} + +bool AutoConnector::isConnecting() { + return isRepeat.load(); +} \ No newline at end of file diff --git a/code/c++/cxx-api/AutoConnector.h b/code/c++/cxx-api/AutoConnector.h new file mode 100644 index 0000000..f9cb263 --- /dev/null +++ b/code/c++/cxx-api/AutoConnector.h @@ -0,0 +1,30 @@ +#pragma once +#include +#include +#include +#include + +struct Data { + std::function callback; + std::atomic_bool* pIsRepeat; + uint32_t frequency; +}; + +class AutoConnector { +private: + std::thread* pConnectingThread; + std::function callback; + std::atomic_bool isRepeat; + uint32_t frequency; + +public: + /** + * @param c Callback to run by timer + * @param f Time to wait before next callback call in milliseconds + */ + AutoConnector(std::function c, uint32_t f); + ~AutoConnector(); + void start(); + void stop(); + bool isConnecting(); +}; \ No newline at end of file diff --git a/code/c++/cxx-api/BadAddressOrPortException.h b/code/c++/cxx-api/BadAddressOrPortException.h new file mode 100644 index 0000000..9bc8745 --- /dev/null +++ b/code/c++/cxx-api/BadAddressOrPortException.h @@ -0,0 +1,14 @@ +#ifndef _BAD_ADDRESS_OR_PORT_EXCEPTION_H_ +#define _BAD_ADDRESS_OR_PORT_EXCEPTION_H_ + +#include "TrackPlatformException.h" + +class BadAddressOrPortException : public TrackPlatformException +{ +public: + explicit BadAddressOrPortException(int errorCode) : TrackPlatformException(std::to_string(errorCode)) + { + } +}; + +#endif /* _BAD_ADDRESS_OR_PORT_EXCEPTION_H_ */ diff --git a/code/c++/cxx-api/CannotConnectToArduinoException.h b/code/c++/cxx-api/CannotConnectToArduinoException.h new file mode 100644 index 0000000..abd54f9 --- /dev/null +++ b/code/c++/cxx-api/CannotConnectToArduinoException.h @@ -0,0 +1,14 @@ +#ifndef _CANNOT_CONNECT_TO_ARDUINO_EXCEPTION_H_ +#define _CANNOT_CONNECT_TO_ARDUINO_EXCEPTION_H_ + +#include "TrackPlatformException.h" + +class CannotConnectToArduinoException : public TrackPlatformException +{ +public: + explicit CannotConnectToArduinoException() : TrackPlatformException() + { + } +}; + +#endif /* _CANNOT_CONNECT_TO_ARDUINO_EXCEPTION_H_ */ diff --git a/code/c++/cxx-api/CommandsEnum.h b/code/c++/cxx-api/CommandsEnum.h new file mode 100644 index 0000000..462eb20 --- /dev/null +++ b/code/c++/cxx-api/CommandsEnum.h @@ -0,0 +1,80 @@ +#ifndef _COMMANDS_ENUM_H_ +#define _COMMANDS_ENUM_H_ + +enum ControllerEnum { + movementControllerID = '\001', + sensorsControllerID = '\002', + servoControllerID = '\003', + communicationControllerID = '\004', +}; + +enum SensorsEnum { + distance_sensor = '\001', //get value from single distance senceor + distance_sensor_all = '\002', //get value from all distance senceors + line_sensor = '\003', //get value from single line senceor + line_sensor_all = '\004' //get value from all line senceors +}; + +enum AreaType { + light = '\x00', // light area type + dark = '\x01', // dark area type +}; + +enum MoveEnum { + forward = '\001', //move forward: obsolete + left = '\002', //move left: obsolete + right = '\003', //move right: obsolete + back = '\004', //move back: obsolete + stop = '\005', //stop + forward_speed = '\006', //move forward with established speed + forward_time = '\007', //move forward while established time: obsolete + back_speed = '\x08', //move back with established speed: obsolete + track_set_speed = '\x09', //choose track and set passed speed + clockwise = '\x0A', //clockwise rotation with speed + track_all_set_speed = '\x0B', //set passed speed to every track +}; + +enum TrackIndex { + left_track = 0, //left track id + right_track = 1 //right track id +}; + +enum SensorManagerIndex { + line_sensor_index = 0, + distance_sensor_index = 1 +}; + +enum ServoIndex { + xy_plane = 1, //z axis + xz_plane = 2, //y axis +}; + +enum ServoCommands { + set_horizontal_angle = '\001', //set horizontal angle of servo: obsolete + set_vertical_angle = '\002', //set vertical angle of servo: obsolete + set_horiz_vertical_angles = '\003', //set horizontal and verticalse angles of servo: obsolete + get_coodrinates = '\004', //get current angels of horizontal and vertical servos: obsolete + set_angle = '\x05', //set axis angle + get_angle = '\x06', //get axis angle +}; + +enum CommunicationCommands { + startCommunicationCommand = 1, //starting communication command + stopCommunicationCommand = 2, //stopping communication command + refreshConnectionCommunicationCommand = 3, //refreshing connection timer communication command (since API v3) +}; + +/** + * @brief Describes trackPlatform API to working + * @see https://github.com/Lipotam/trackPlatform/wiki/Api + * @warning Each API must be described in @ConnectionController handler + * @warning If you add new version for API, check @ConnectionController::highestAPI field + */ +enum ApiVersion { + startBasicAPI = 1, //default API v1 + APIWithAnswer = 2, //API v2 + APIWithAutoDiconnect = 3, //API v3 + APIWithCRC = 4, //API v4 +}; + +#endif /* _COMMANDS_ENUM_H_ */ diff --git a/code/c++/cxx-api/CommunicationInfoStruct.h b/code/c++/cxx-api/CommunicationInfoStruct.h new file mode 100644 index 0000000..0380f67 --- /dev/null +++ b/code/c++/cxx-api/CommunicationInfoStruct.h @@ -0,0 +1,25 @@ +#ifndef _COMMUNICATION_INFO_STRUCT_H_ +#define _COMMUNICATION_INFO_STRUCT_H_ +#include +#include + +/** + * @brief Information to communicator. + * @attention You must fill info about required communication before send it to class constructor + */ +struct CommunicationInfoStruct +{ + struct + { + std::string rxPort; + std::string txPort; + uint32_t baudrate; + } SerialInfo; + struct + { + std::string ip; + uint16_t port; + } TCPIPInfo; +}; + +#endif /* _COMMUNICATION_INFO_STRUCT_H_ */ diff --git a/code/c++/cxx-api/ConnectionModes.h b/code/c++/cxx-api/ConnectionModes.h new file mode 100644 index 0000000..3da8463 --- /dev/null +++ b/code/c++/cxx-api/ConnectionModes.h @@ -0,0 +1,11 @@ +#ifndef _CONNECTION_MODES_H_ +#define _CONNECTION_MODES_H_ + +enum ConnectionModes +{ + USB, + bluetooth, + WiFi, +}; + +#endif /* _CONNECTION_MODES_H_ */ diff --git a/code/c++/cxx-api/CorruptedAnswerException.h b/code/c++/cxx-api/CorruptedAnswerException.h new file mode 100644 index 0000000..11ca20d --- /dev/null +++ b/code/c++/cxx-api/CorruptedAnswerException.h @@ -0,0 +1,13 @@ +#ifndef _CORRUPTED_ANSWER_EXCEPTION_H_ +#define _CORRUPTED_ANSWER_EXCEPTION_H_ +#include "TrackPlatformException.h" + +class CorruptedAnswerException : public TrackPlatformException +{ +public: + explicit CorruptedAnswerException() : TrackPlatformException() + { + } +}; + +#endif /* _CORRUPTED_ANSWER_EXCEPTION_H_ */ diff --git a/code/c++/cxx-api/Logger.cpp b/code/c++/cxx-api/Logger.cpp new file mode 100644 index 0000000..a23529a --- /dev/null +++ b/code/c++/cxx-api/Logger.cpp @@ -0,0 +1,27 @@ +#include "Logger.h" + +#ifndef LOGGER_ON + +void Logger::log(std::string s) +{ +} + +#else + +Logger* Logger::logger = new Logger(); + +Logger::Logger() : file(way, std::ios::out | std::ios::app) +{ +} + +void Logger::logOneString(std::string s) +{ + file << s << std::endl; +} + +void Logger::log(std::string s) +{ + logger->logOneString(s); +} + +#endif diff --git a/code/c++/cxx-api/Logger.h b/code/c++/cxx-api/Logger.h new file mode 100644 index 0000000..e663c00 --- /dev/null +++ b/code/c++/cxx-api/Logger.h @@ -0,0 +1,36 @@ +#ifndef _LOGGER_H_ +#define _LOGGER_H_ + +/** + * @brief If defined, log is on, else off + */ +// #define LOGGER_ON + +#ifndef LOGGER_ON +#include +class Logger +{ +public: + static void log(std::string s); +}; + +#else +#include +#include + +class Logger +{ + static Logger* logger; + + const std::string way = "logger.log"; + std::ofstream file; + + Logger(); + void logOneString(std::string s); + +public: + static void log(std::string s); +}; +#endif + +#endif /* _LOGGER_H_ */ diff --git a/code/c++/cxx-api/NoConnectionException.h b/code/c++/cxx-api/NoConnectionException.h new file mode 100644 index 0000000..4d03921 --- /dev/null +++ b/code/c++/cxx-api/NoConnectionException.h @@ -0,0 +1,14 @@ +#ifndef _NO_CONNECTION_EXCEPTION_H_ +#define _NO_CONNECTION_EXCEPTION_H_ + +#include "TrackPlatformException.h" + +class NoConnectionException : public TrackPlatformException +{ +public: + explicit NoConnectionException() : TrackPlatformException() + { + } +}; + +#endif /* _NO_CONNECTION_EXCEPTION_H_ */ diff --git a/code/c++/cxx-api/README.md b/code/c++/cxx-api/README.md new file mode 100644 index 0000000..8cd3c67 --- /dev/null +++ b/code/c++/cxx-api/README.md @@ -0,0 +1,7 @@ +# trackPlatform C++ API + +API для платформы trackPlatrorm для языка C++. +Зависимости: +* https://github.com/wjwwood/serial - кросс-платформенная библиотека для использования последовательных портов (лежит в папке `serial_support`) + +Made by AJIOB diff --git a/code/c++/cxx-api/SerialConnector.cpp b/code/c++/cxx-api/SerialConnector.cpp new file mode 100644 index 0000000..157a0c4 --- /dev/null +++ b/code/c++/cxx-api/SerialConnector.cpp @@ -0,0 +1,100 @@ +#include +#include "SerialConnector.h" +#include "trackPlatformAllExceptions.h" + +extern "C" { +#include "checksum.h" +} + +void SerialConnector::write(const std::string& s) +{ + writePort->write(s); + writePort->flush(); +} + +SerialConnector::SerialConnector(const std::string& rx, const std::string& tx, uint32_t baudRate) : + rxLocation(rx), txLocation(tx), baudRate(baudRate), readPort(new serial::Serial(rx, baudRate, serial::Timeout::simpleTimeout(timeoutInMs))), + writePort((rx == tx) ? readPort : new serial::Serial(tx, baudRate, serial::Timeout::simpleTimeout(timeoutInMs))) +{ + sendStartCommand(); +} + +SerialConnector::~SerialConnector() +{ + sendStopCommand(); + + SerialConnector::disconnect(); + if (readPort != writePort) + { + delete writePort; + } + delete readPort; +} + +std::string SerialConnector::read() +{ + if (buffer.empty()) + { + buffer += readPort->read(sizeof(uint8_t)); + } + if (buffer.empty()) + { + throw TimeoutException(); + } + const uint8_t len = buffer[0]; + const uint16_t substring_len = sizeof(len) + len + crc_length; + if ((substring_len) > buffer.length()) + { + buffer += readPort->read(std::max(substring_len - sizeof(len), readPort->available())); + } + + if ((substring_len) > buffer.length()) + { + throw TimeoutException(); + } + + std::string answer = buffer.substr(0, substring_len); + buffer.erase(0, substring_len); + + return answer; +} + +std::string SerialConnector::generatePackage(const std::string& command) +{ + std::string package = static_cast(command.length()) + command; + uint16_t crc = crc_modbus(reinterpret_cast(package.c_str()), package.length()); + for (size_t i = 0; i < crc_length; ++i) + { + package.push_back((reinterpret_cast(&crc))[i]); + } + return package; +} + +bool SerialConnector::isConnected() +{ + return (TrackPlatform_BasicConnector::isConnected() && readPort->isOpen() && writePort->isOpen()); +} + +void SerialConnector::connect() +{ + if (readPort && !readPort->isOpen()) + { + readPort->open(); + } + if (writePort && !writePort->isOpen()) + { + writePort->open(); + } +} + +void SerialConnector::disconnect() +{ + if (readPort && readPort->isOpen()) + { + readPort->close(); + } + if (writePort && writePort->isOpen()) + { + writePort->close(); + } +} diff --git a/code/c++/cxx-api/SerialConnector.h b/code/c++/cxx-api/SerialConnector.h new file mode 100644 index 0000000..1f36c50 --- /dev/null +++ b/code/c++/cxx-api/SerialConnector.h @@ -0,0 +1,34 @@ +#ifndef _BLUETOOTH_CONNECTOR_H_ +#define _BLUETOOTH_CONNECTOR_H_ + +#include "TrackPlatform_BasicConnector.h" +#include "serial/serial.h" + +class SerialConnector : public TrackPlatform_BasicConnector +{ + static const size_t messageMaxSize = 65535; + static const size_t timeoutInMs = 400; + + std::string rxLocation; + std::string txLocation; + uint32_t baudRate; + + serial::Serial* readPort; + serial::Serial* writePort; + + std::string buffer; + +protected: + void write(const std::string& s) override; + std::string read() override; + std::string generatePackage(const std::string& command) override; + +public: + SerialConnector(const std::string& rx, const std::string& tx, uint32_t baudRate); + ~SerialConnector() override; + bool isConnected() override; + void connect() override; + void disconnect() override; +}; + +#endif /* _BLUETOOTH_CONNECTOR_H_ */ diff --git a/code/c++/cxx-api/SocketException.h b/code/c++/cxx-api/SocketException.h new file mode 100644 index 0000000..211e00b --- /dev/null +++ b/code/c++/cxx-api/SocketException.h @@ -0,0 +1,13 @@ +#ifndef _SOCKET_EXCEPTION_H_ +#define _SOCKET_EXCEPTION_H_ +#include "TrackPlatformException.h" + +class SocketException : public TrackPlatformException +{ +public: + explicit SocketException(int errorCode) : TrackPlatformException(std::to_string(errorCode)) + { + } +}; + +#endif /* _SOCKET_EXCEPTION_H_ */ diff --git a/code/c++/cxx-api/SocketReceiveException.h b/code/c++/cxx-api/SocketReceiveException.h new file mode 100644 index 0000000..b614c29 --- /dev/null +++ b/code/c++/cxx-api/SocketReceiveException.h @@ -0,0 +1,14 @@ +#ifndef _SOCKET_RECEIVE_EXCEPTION_H_ +#define _SOCKET_RECEIVE_EXCEPTION_H_ +#include "SocketException.h" + +class SocketReceiveException : public SocketException +{ +public: + explicit SocketReceiveException(int errorCode) + : SocketException(errorCode) + { + } +}; + +#endif /* _SOCKET_RECEIVE_EXCEPTION_H_ */ diff --git a/code/c++/cxx-api/SocketSendException.h b/code/c++/cxx-api/SocketSendException.h new file mode 100644 index 0000000..4fd55a8 --- /dev/null +++ b/code/c++/cxx-api/SocketSendException.h @@ -0,0 +1,14 @@ +#ifndef _SOCKET_SEND_EXCETION_H_ +#define _SOCKET_SEND_EXCETION_H_ +#include "SocketException.h" + +class SocketSendException : public SocketException +{ +public: + explicit SocketSendException(int errorCode) + : SocketException(errorCode) + { + } +}; + +#endif /* _SOCKET_SEND_EXCETION_H_ */ diff --git a/code/c++/cxx-api/SocketShutdownException.h b/code/c++/cxx-api/SocketShutdownException.h new file mode 100644 index 0000000..67ee430 --- /dev/null +++ b/code/c++/cxx-api/SocketShutdownException.h @@ -0,0 +1,14 @@ +#ifndef _SOCKET_SHUTDOWN_EXCEPTION_H_ +#define _SOCKET_SHUTDOWN_EXCEPTION_H_ +#include "SocketException.h" + +class SocketShutdownException : public SocketException +{ +public: + explicit SocketShutdownException(int errorCode) + : SocketException(errorCode) + { + } +}; + +#endif /* _SOCKET_SHUTDOWN_EXCEPTION_H_ */ diff --git a/code/c++/cxx-api/TCPIP_Connector.cpp b/code/c++/cxx-api/TCPIP_Connector.cpp new file mode 100644 index 0000000..29cb50c --- /dev/null +++ b/code/c++/cxx-api/TCPIP_Connector.cpp @@ -0,0 +1,236 @@ +#if (defined(__linux__) || defined(__unix__)) + +#define SOCKET_ERROR (-1) +#define closesocket(...) close(__VA_ARGS__) + +/* shutdown() ports */ +#define SD_RECEIVE SHUT_RD +#define SD_SEND SHUT_WR +#define SD_BOTH SHUT_RDWR + +#define WSAGetLastError() errno + +#include +#include +#include +#include +#include +#include + +#endif /* (defined(__linux__) || defined(__unix__)) */ + +#include + +#include "trackPlatformAllExceptions.h" +#include "TCPIP_Connector.h" + +extern "C" { +#include "checksum.h" +} + +void TCPIP_Connector::write(const std::string& s) +{ + // Send an initial buffer (returns byte sended) +#ifdef _WIN32 + int iResult = send(connectedSocket, s.c_str(), static_cast(s.length()), 0); +#else /* _WIN32 */ + int iResult = send(connectedSocket, s.c_str(), s.length(), 0); +#endif /* _WIN32 */ + if (iResult == SOCKET_ERROR) { + throw SocketSendException(WSAGetLastError()); + } +} + +std::string TCPIP_Connector::read() +{ + char recvbuf[onePacketMaxSize]; + + int iResult; + + do { + // Check if something is already in buffer (and wait `microsecondsToWaitAnswer` if required) + timeval tval = { 0, microsecondsToWaitAnswer }; + +#ifdef _WIN32 + fd_set readSockets = { 1, { connectedSocket } }; + iResult = select(0, &readSockets, NULL, NULL, &tval); +#else /* _WIN32 */ + fd_set readSockets; + FD_ZERO(&readSockets); + FD_SET(connectedSocket, &readSockets); + iResult = select(connectedSocket + 1, &readSockets, NULL, NULL, &tval); +#endif /* _WIN32 */ + if (iResult == SOCKET_ERROR) + { + throw SocketException(WSAGetLastError()); + } + if (iResult == 0) + { + break; + } + + // Receive data until the server closes the connection + iResult = recv(connectedSocket, recvbuf, sizeof(recvbuf), 0); + if (iResult < 0) + { + throw SocketReceiveException(WSAGetLastError()); + } + + receivedBuffer += std::string(recvbuf, iResult); + } while (iResult > 0); + + uint8_t len = receivedBuffer[0]; + if ((len + sizeof(receivedBuffer[0])) > receivedBuffer.length()) + { + throw TimeoutException(); + } + + const uint16_t substring_len = sizeof(len) + len; + std::string answer = receivedBuffer.substr(0, substring_len); + receivedBuffer.erase(0, substring_len); + + //emulating receiving crc16 + uint16_t crc = crc_modbus(reinterpret_cast(answer.c_str()), answer.length()); + for (size_t i = 0; i < crc_length; ++i) + { + answer.push_back((reinterpret_cast(&crc))[i]); + } + return answer; +} + +bool TCPIP_Connector::connectSocket() +{ + if (isSocketConnected) { + return false; + } + + // Attempt to connect to the first address returned by + // the call to getaddrinfo + struct addrinfo* ptr = addressInfo; + + // Create a SOCKET for connecting to server + connectedSocket = socket(ptr->ai_family, ptr->ai_socktype, ptr->ai_protocol); + + if (connectedSocket == INVALID_SOCKET) { + throw SocketException(WSAGetLastError()); + } + + // Connect to server. +#ifdef _WIN32 + int iResult = ::connect(connectedSocket, addressInfo->ai_addr, static_cast(addressInfo->ai_addrlen)); +#else /* _WIN32 */ + int iResult = ::connect(connectedSocket, addressInfo->ai_addr, addressInfo->ai_addrlen); +#endif /* _WIN32 */ + if (iResult == SOCKET_ERROR) { + closeSocket(); + return false; + } + + isSocketConnected = true; + return true; +} + +bool TCPIP_Connector::disconnectSocket() +{ + if (!isSocketConnected) + { + return false; + } + + // shutdown the sending and recieving data by socket + int iResult = shutdown(connectedSocket, SD_BOTH); + if (iResult == SOCKET_ERROR) { + throw SocketShutdownException(WSAGetLastError()); + } + + closeSocket(); + isSocketConnected = false; + return true; +} + +void TCPIP_Connector::configureSocket() +{ + struct addrinfo hints; + + // Configure socket + memset(&hints, 0, sizeof(hints)); + hints.ai_family = AF_UNSPEC; /* AF_UNSPEC for IPv6 or IPv4 (automatically); AF_INET6 for IPv6; AF_INET for IPv4 */ + hints.ai_socktype = SOCK_STREAM; + hints.ai_protocol = IPPROTO_TCP; + + // Resolve the server address and port + int iResult = getaddrinfo(ip.c_str(), std::to_string(port).c_str(), &hints, &addressInfo); + if (iResult != 0) { + addressInfo = nullptr; + throw BadAddressOrPortException(iResult); + } +} + +void TCPIP_Connector::closeSocket() +{ + if (connectedSocket != INVALID_SOCKET) + { + closesocket(connectedSocket); + connectedSocket = INVALID_SOCKET; + } +} + +std::string TCPIP_Connector::generatePackage(const std::string& command) +{ + return (static_cast(command.length()) + command); +} + +bool TCPIP_Connector::isConnected() +{ + return (TrackPlatform_BasicConnector::isConnected() && isSocketConnected); +} + +void TCPIP_Connector::connect() +{ + if (connectSocket()) + { + sendStartCommand(); + } + else + { + throw NoConnectionException(); + } +} + +void TCPIP_Connector::disconnect() +{ + //if api is connected to arduino + if (isConnected()) + { + sendStopCommand(); + } + + disconnectSocket(); +} + +TCPIP_Connector::TCPIP_Connector(const std::string& ip, uint16_t port) + : ip(ip), port(port) +{ +#ifdef _WIN32 + // Initialize Winsock + int iResult = WSAStartup(MAKEWORD(2, 2), &wsaData); + if (iResult != 0) { + throw WSAStartupException(iResult); + } +#endif + + configureSocket(); + TCPIP_Connector::connect(); +} + +TCPIP_Connector::~TCPIP_Connector() +{ + TCPIP_Connector::disconnect(); + if (addressInfo) + { + freeaddrinfo(addressInfo); + } +#ifdef _WIN32 + WSACleanup(); +#endif +} \ No newline at end of file diff --git a/code/c++/cxx-api/TCPIP_Connector.h b/code/c++/cxx-api/TCPIP_Connector.h new file mode 100644 index 0000000..55a2162 --- /dev/null +++ b/code/c++/cxx-api/TCPIP_Connector.h @@ -0,0 +1,75 @@ +#ifndef _TCPIP_CONNECTOR_H_ +#define _TCPIP_CONNECTOR_H_ + +#if defined(_WIN32) + +/* WinAPI include */ +#ifndef WIN32_LEAN_AND_MEAN +#define WIN32_LEAN_AND_MEAN +#endif + +#include +#include +#include +#include + +#pragma comment(lib, "Ws2_32.lib") + +#endif /* _WIN32 */ + +#if (defined(__linux__) || defined(__unix__)) + +#define SOCKET int +#define INVALID_SOCKET (-1) + +#endif /* (defined(__linux__) || defined(__unix__)) */ + +#include "TrackPlatform_BasicConnector.h" + +class TCPIP_Connector : public TrackPlatform_BasicConnector +{ + std::string ip; + uint16_t port; + + std::string receivedBuffer; + + static const uint16_t onePacketMaxSize = 512; + static const int32_t microsecondsToWaitAnswer = 400 * 1000; + +#ifdef _WIN32 + WSADATA wsaData; +#endif /* _WIN32 */ + struct addrinfo *addressInfo = nullptr; + SOCKET connectedSocket = INVALID_SOCKET; + + bool isSocketConnected = false; + + void configureSocket(); + void closeSocket(); + +protected: + std::string generatePackage(const std::string& command) override; + void write(const std::string& s) override; + std::string read() override; + + bool connectSocket(); + bool disconnectSocket(); + +public: + /** + * @brief Create TCP/IP connector to trackPlatform + * @warning Only one object of that class in one moment of time is supported + * + * @param ip IP of trackPlatform Wi-Fi module + * @warning Supports only single IP, no masks + * @param port Port of TCP/IP server on trackPlatform + */ + TCPIP_Connector(const std::string& ip, uint16_t port); + virtual ~TCPIP_Connector(); + + bool isConnected() override; + void connect() override; + void disconnect() override; +}; + +#endif /* _TCPIP_CONNECTOR_H_ */ diff --git a/code/c++/cxx-api/TimeoutException.h b/code/c++/cxx-api/TimeoutException.h new file mode 100644 index 0000000..07a5a4a --- /dev/null +++ b/code/c++/cxx-api/TimeoutException.h @@ -0,0 +1,9 @@ +#pragma once + +class TimeoutException : public TrackPlatformException +{ +public: + explicit TimeoutException() : TrackPlatformException() + { + } +}; diff --git a/code/c++/cxx-api/TrackPlatformException.cpp b/code/c++/cxx-api/TrackPlatformException.cpp new file mode 100644 index 0000000..f6435e9 --- /dev/null +++ b/code/c++/cxx-api/TrackPlatformException.cpp @@ -0,0 +1,24 @@ +#include "TrackPlatformException.h" + +TrackPlatformException::TrackPlatformException() +{ +} + +#ifdef _WIN32 +TrackPlatformException::TrackPlatformException(const std::string& errorMessage) + : std::exception(errorMessage.c_str()) +{ +} + +#else /* _WIN32 */ +TrackPlatformException::TrackPlatformException(const std::string& errorMessage) + : errorText(errorMessage) +{ +} + +const char* TrackPlatformException::what() const noexcept +{ + return errorText.c_str(); +} + +#endif /* _WIN32 */ diff --git a/code/c++/cxx-api/TrackPlatformException.h b/code/c++/cxx-api/TrackPlatformException.h new file mode 100644 index 0000000..5bd7566 --- /dev/null +++ b/code/c++/cxx-api/TrackPlatformException.h @@ -0,0 +1,22 @@ +#ifndef _TRACK_PLATFORM_EXCEPTION_H_ +#define _TRACK_PLATFORM_EXCEPTION_H_ + +#include +#include + +class TrackPlatformException : public std::exception +{ +#ifndef _WIN32 + std::string errorText; +#endif /* _WIN32 */ + +public: + TrackPlatformException(); + explicit TrackPlatformException(const std::string& errorMessage); + +#ifndef _WIN32 + const char* what() const noexcept override; +#endif /* _WIN32 */ +}; + +#endif /* _TRACK_PLATFORM_EXCEPTION_H_ */ diff --git a/code/c++/cxx-api/TrackPlatform_BasicConnector.cpp b/code/c++/cxx-api/TrackPlatform_BasicConnector.cpp new file mode 100644 index 0000000..42f74c9 --- /dev/null +++ b/code/c++/cxx-api/TrackPlatform_BasicConnector.cpp @@ -0,0 +1,183 @@ +#include +#include + +#include "Logger.h" +#include "trackPlatformAllExceptions.h" +#include "CommandsEnum.h" + +#include "TrackPlatform_BasicConnector.h" + +extern "C" { +#include "checksum.h" +} + +const std::string TrackPlatform_BasicConnector::correctAnswer = "OK"; +const std::string TrackPlatform_BasicConnector::errorAnswer = "ERROR"; + +std::string TrackPlatform_BasicConnector::generatePackage(const std::string& command) +{ + return command; +} + +void TrackPlatform_BasicConnector::sendStartCommand() +{ + const std::string command = std::string() + static_cast(communicationControllerID) + static_cast(startCommunicationCommand) + static_cast(APIWithCRC); + isConnectedToArduino = true; + sendOneCommand(command); + autoConnector->start(); +} +void TrackPlatform_BasicConnector::sendStopCommand() +{ + if (!isConnected()) + { + throw NoConnectionException(); + } + autoConnector->stop(); + const std::string command = std::string() + static_cast(communicationControllerID) + static_cast(stopCommunicationCommand); + sendOneCommand(command); + isConnectedToArduino = false; +} + +void TrackPlatform_BasicConnector::sendRenewConnectionCommand() +{ + if (!isConnected()) + { + throw NoConnectionException(); + } + + const std::string command = std::string() + static_cast(communicationControllerID) + static_cast(refreshConnectionCommunicationCommand); + sendOneCommand(command); +} + +TrackPlatform_BasicConnector::TrackPlatform_BasicConnector() : + autoConnector(new AutoConnector([this]() +{ + this->sendRenewConnectionCommand(); +}, timeoutToAutoreconnectInMs)) +{ +} + +TrackPlatform_BasicConnector::~TrackPlatform_BasicConnector() +{ + readWriteAtomicMutex.try_lock(); + readWriteAtomicMutex.unlock(); +} + +std::string TrackPlatform_BasicConnector::sendOneCommand(const std::string& s, bool isWithAnswer) +{ + readWriteAtomicMutex.lock(); + + try + { + std::string answer = sendOneCommand_unsafe(s, isWithAnswer); + readWriteAtomicMutex.unlock(); + return answer; + } + catch(...) + { + readWriteAtomicMutex.unlock(); + throw; + } +} + +std::string TrackPlatform_BasicConnector::readOneAnswer() +{ + if (!isConnected()) + { + throw NoConnectionException(); + } + + std::string answer = read(); + uint8_t len = answer[0]; + if (answer.length() != (len + sizeof(len) + crc_length)) + { + Logger::log("Bad message length"); + throw CorruptedAnswerException(); + } + + if (crc_modbus(reinterpret_cast(answer.c_str()), answer.length()) != 0) + { + Logger::log("Bad crc value"); + throw CorruptedAnswerException(); + } + + answer.erase(0, sizeof(len)); + answer.erase(answer.length() - crc_length, crc_length); + + return answer; +} + +std::string TrackPlatform_BasicConnector::sendOneCommand_unsafe(const std::string& s, const bool isWithAnswer) +{ + if (!isConnected()) + { + throw NoConnectionException(); + } + const std::string package = generatePackage(s); + Logger::log("Send: " + package); + for (auto i = 0; i < timesToAutoreconnect; ++i) + { + if (i != 0) + { + std::this_thread::sleep_for(std::chrono::milliseconds(timeoutToNextConnectInMs)); + } + + Logger::log("Trying to send command. Attempt " + std::to_string(i + 1)); + write(package); + try { + std::string managedAnswer = readOneAnswer(); + if (managedAnswer == errorAnswer) + { + Logger::log("Error was getted (part 1)"); + continue; + } + if (managedAnswer != correctAnswer) + { + Logger::log("Command not parsed"); + continue; + } + + std::string answer; + + if (isWithAnswer) + { + answer = readOneAnswer(); + Logger::log("Read answer: " + answer); + } + + managedAnswer = readOneAnswer(); + if (managedAnswer == errorAnswer) + { + Logger::log("Error was getted (part 2)"); + continue; + } + if (managedAnswer != correctAnswer) + { + Logger::log("Command not executed"); + continue; + } + + Logger::log("Sending successfully"); + return answer; + } + catch (CorruptedAnswerException&) + { + //All is good, module not answered, try again + Logger::log("Answer is corrupted"); + } + catch (TimeoutException&) + { + //All is good, module not answered, try again + Logger::log("Timeout exception"); + } + } + + isConnectedToArduino = false; + Logger::log("Cannot connect to arduino"); + throw CannotConnectToArduinoException(); +} + +bool TrackPlatform_BasicConnector::isConnected() +{ + return isConnectedToArduino; +} diff --git a/code/c++/cxx-api/TrackPlatform_BasicConnector.h b/code/c++/cxx-api/TrackPlatform_BasicConnector.h new file mode 100644 index 0000000..e6b2db1 --- /dev/null +++ b/code/c++/cxx-api/TrackPlatform_BasicConnector.h @@ -0,0 +1,68 @@ +#ifndef _TRACKPLATFORM_BASICCONNECTOR_H_ +#define _TRACKPLATFORM_BASICCONNECTOR_H_ + +#include +#include +#include "AutoConnector.h" + +class TrackPlatform_BasicConnector +{ + bool isConnectedToArduino = false; + AutoConnector* autoConnector = nullptr; + +protected: + static const uint8_t timesToAutoreconnect = 3; + static const uint32_t timeoutToNextConnectInMs = 500; + static const uint32_t timeoutToAutoreconnectInMs = 4500; + static const std::string correctAnswer; + static const std::string errorAnswer; + static const uint8_t crc_length = 2; + + std::recursive_mutex readWriteAtomicMutex; + + virtual void write(const std::string& s) = 0; + virtual std::string read() = 0; + virtual std::string readOneAnswer(); + + /** + * @brief Send start connection command + * @warning Must be called in constructor after configuring and opening connection + */ + void sendStartCommand(); + /** + * @brief Send stop connection command + * @warning Must be called in destructor before closing and deleting connection + */ + void sendStopCommand(); + /** + * @brief Send renew connection command + * @warning Must be called periodically + */ + void sendRenewConnectionCommand(); + + virtual std::string generatePackage(const std::string& command); + + virtual std::string sendOneCommand_unsafe(const std::string& s, bool isWithAnswer); + +public: + TrackPlatform_BasicConnector(); + virtual ~TrackPlatform_BasicConnector(); + + /** + * @brief Send one command and read answer to it, if requires + * @warning By default returns one portion of data from rx, must be overriden if require + * @return Answer from command + */ + std::string sendOneCommand(const std::string& s, bool isWithAnswer = false); + virtual bool isConnected(); + /** + * @brief Manual connect if not already connected + */ + virtual void connect() = 0; + /** + * @brief Manual disconnect + */ + virtual void disconnect() = 0; +}; + +#endif /* _TRACKPLATFORM_BASICCONNECTOR_H_ */ diff --git a/code/c++/cxx-api/TrackPlatform_BasicManagement.cpp b/code/c++/cxx-api/TrackPlatform_BasicManagement.cpp new file mode 100644 index 0000000..92c72ab --- /dev/null +++ b/code/c++/cxx-api/TrackPlatform_BasicManagement.cpp @@ -0,0 +1,217 @@ +#include "TrackPlatform_BasicManagement.h" + +const double TrackPlatform_BasicManagement::minInputSpeed = -1; +const double TrackPlatform_BasicManagement::maxInputSpeed = 1; + +std::string TrackPlatform_BasicManagement::sendCommand(const ControllerEnum targetController, const std::string& additionalInfo, const bool isWaitAnswer) +{ + return connector->sendOneCommand(static_cast(targetController) + additionalInfo, isWaitAnswer); +} + +std::vector TrackPlatform_BasicManagement::parseStringToArray(std::string s) +{ + std::vector distancies; + size_t stringOldLen = 0; + size_t posToNextValue = 0; + try + { + do + { + + distancies.push_back(std::stoul(s, &posToNextValue)); + stringOldLen = s.length(); + s = s.substr(posToNextValue + sizeof delimiter); + + } while ((s != "") && (stringOldLen > s.length())); + } + catch (...) + { + return distancies; + } + + if (stringOldLen <= s.length()) + { + distancies.pop_back(); + } + return distancies; +} + +TrackPlatform_BasicConnector* TrackPlatform_BasicManagement::getConnector() const +{ + return connector; +} + +bool TrackPlatform_BasicManagement::sendMovement(const MoveEnum command, const double speed) +{ + if (speed < minInputSpeed || speed > maxInputSpeed) + { + return false; + } + + std::string toSend(1, command); + toSend += std::to_string(static_cast(speed * (maxSpeed - minSpeed) + minSpeed)); + sendCommand(movementControllerID, toSend); + + return true; +} + +TrackPlatform_BasicManagement::TrackPlatform_BasicManagement(TrackPlatform_BasicConnector* connector) + : connector(connector) +{ +} + +TrackPlatform_BasicManagement::~TrackPlatform_BasicManagement() +{ +} + +void TrackPlatform_BasicManagement::moveForward() +{ + moveForward(maxInputSpeed); +} + +bool TrackPlatform_BasicManagement::moveForward(double speed) +{ + return sendMovement(forward_speed, speed); +} + +void TrackPlatform_BasicManagement::moveForward(uint32_t timeInMSec) +{ + moveForward(maxInputSpeed); + std::this_thread::sleep_for(std::chrono::milliseconds(timeInMSec)); + moveStopAll(); +} + +void TrackPlatform_BasicManagement::moveBackward() +{ + moveForward(-maxInputSpeed); +} + +bool TrackPlatform_BasicManagement::moveBackward(double speed) +{ + return moveForward(-speed); +} + +bool TrackPlatform_BasicManagement::rotateClockwise(double speed) +{ + return sendMovement(clockwise, speed); +} + +bool TrackPlatform_BasicManagement::rotateAntiClockwise(double speed) +{ + return rotateClockwise(-speed); +} + +void TrackPlatform_BasicManagement::moveStopAll() +{ + std::string toSend(1, stop); + sendCommand(movementControllerID, toSend); +} + +bool TrackPlatform_BasicManagement::setTrackForwardSpeed(TrackIndex trackId, double speed) +{ + if (speed < -1 || speed > 1) + { + return false; + } + + std::string toSend(1, track_set_speed); + toSend += std::to_string(*reinterpret_cast(&trackId)); + toSend += delimiter; + toSend += std::to_string(static_cast(speed * (maxSpeed - minSpeed) + minSpeed)); + sendCommand(movementControllerID, toSend); + + return true; +} + +bool TrackPlatform_BasicManagement::setAllTrackForwardSpeed(double leftSpeed, double rightSpeed) +{ + if (leftSpeed < -1 || leftSpeed > 1 || rightSpeed < -1 || rightSpeed > 1) + { + return false; + } + + std::string toSend(1, track_all_set_speed); + toSend += std::to_string(static_cast(leftSpeed * (maxSpeed - minSpeed) + minSpeed)); + toSend += delimiter; + toSend += std::to_string(static_cast(rightSpeed * (maxSpeed - minSpeed) + minSpeed)); + sendCommand(movementControllerID, toSend); + + return true; +} + +uint32_t TrackPlatform_BasicManagement::sensorDistanceGetValue(uint8_t num) +{ + std::string toSend(1, distance_sensor); + toSend += std::to_string(num); + const std::string answer = sendCommand(sensorsControllerID, toSend, true); + return std::stoi(answer); +} + +std::vector TrackPlatform_BasicManagement::sensorDistanceGetAllValues() +{ + std::string toSend(1, distance_sensor_all); + const std::string answer = sendCommand(sensorsControllerID, toSend, true); + return parseStringToArray(answer); +} + +uint32_t TrackPlatform_BasicManagement::sensorLineGetValue(uint8_t num) +{ + std::string toSend(1, line_sensor); + toSend += std::to_string(num); + const std::string answer = sendCommand(sensorsControllerID, toSend, true); + return std::stoi(answer); +} + +std::vector TrackPlatform_BasicManagement::sensorLineGetAllValues() +{ + std::string toSend(1, line_sensor_all); + const std::string answer = sendCommand(sensorsControllerID, toSend, true); + return parseStringToArray(answer); +} + +void TrackPlatform_BasicManagement::servoSetHorizontalAngle(uint16_t angle) +{ + servoSetAngle(xy_plane, angle); +} + +void TrackPlatform_BasicManagement::servoSetVerticalAngle(uint16_t angle) +{ + servoSetAngle(xz_plane, angle); +} + +void TrackPlatform_BasicManagement::servoSetHorizontalVerticalAngle(uint16_t horizontalAngle, uint16_t verticalAngle) +{ + servoSetAngle(xy_plane, horizontalAngle); + servoSetAngle(xz_plane, verticalAngle); +} + +std::vector TrackPlatform_BasicManagement::servoGetAngles() +{ + std::vector answer; + answer.push_back(servoGetAngle(xy_plane)); + answer.push_back(servoGetAngle(xz_plane)); + return answer; +} + +bool TrackPlatform_BasicManagement::servoSetAngle(ServoIndex axisIndex, uint16_t angle) +{ + if (angle < minServoAngle || angle > maxServoAngle) + { + return false; + } + + std::string toSend(1, set_angle); + toSend += std::to_string(*reinterpret_cast(&axisIndex)); + toSend += delimiter; + toSend += std::to_string(angle); + sendCommand(servoControllerID, toSend); + return true; +} + +uint16_t TrackPlatform_BasicManagement::servoGetAngle(ServoIndex axisIndex) +{ + std::string toSend(1, get_angle); + toSend += std::to_string(*reinterpret_cast(&axisIndex)); + const std::string answer = sendCommand(servoControllerID, toSend, true); + return std::stoi(answer); +} diff --git a/code/c++/cxx-api/TrackPlatform_BasicManagement.h b/code/c++/cxx-api/TrackPlatform_BasicManagement.h new file mode 100644 index 0000000..676f34c --- /dev/null +++ b/code/c++/cxx-api/TrackPlatform_BasicManagement.h @@ -0,0 +1,77 @@ +#ifndef _TRACKPLATFORM_BASICMANAGEMENT_H_ +#define _TRACKPLATFORM_BASICMANAGEMENT_H_ + +#include +#include + +#include "TrackPlatform_BasicConnector.h" +#include "CommandsEnum.h" + +class TrackPlatform_BasicManagement +{ + TrackPlatform_BasicConnector* connector; + +protected: + static const uint8_t minSpeed = 0; + static const uint8_t maxSpeed = 255; + static const uint8_t minServoAngle = 0; + static const uint8_t maxServoAngle = 180; + static const char delimiter = ';'; + static const double minInputSpeed; + static const double maxInputSpeed; + + std::string sendCommand(const ControllerEnum targetController, const std::string& additionalInfo, const bool isWaitAnswer = false); + + static std::vector parseStringToArray(std::string s); + + TrackPlatform_BasicConnector* getConnector() const; + + /** + * \brief Send movement command to with connector + * \param command Command to send with speed + * \param speed Speed from @minSpeed to @maxSpeed interval + * \return true, if all is good, else false + */ + bool sendMovement(MoveEnum command, double speed); + +public: + TrackPlatform_BasicManagement(TrackPlatform_BasicConnector* connector); + virtual ~TrackPlatform_BasicManagement(); + + /* movement controller */ + void moveForward(); + //speed must be in [0,1] range + bool moveForward(double speed); + void moveForward(uint32_t timeInMSec); + + void moveBackward(); + //speed must be in [0,1] range + bool moveBackward(double speed); + + bool rotateClockwise(double speed = maxInputSpeed); + bool rotateAntiClockwise(double speed = maxInputSpeed); + + void moveStopAll(); + + //speed must be in [-1, 1] range + bool setTrackForwardSpeed(TrackIndex trackId, double speed); + //speed must be in [-1, 1] range + bool setAllTrackForwardSpeed(double leftSpeed, double rightSpeed); + + /* sensors controller */ + uint32_t sensorDistanceGetValue(uint8_t num); + std::vector sensorDistanceGetAllValues(); + uint32_t sensorLineGetValue(uint8_t num); + std::vector sensorLineGetAllValues(); + + /* servo controller */ + void servoSetHorizontalAngle(uint16_t angle); + void servoSetVerticalAngle(uint16_t angle); + void servoSetHorizontalVerticalAngle(uint16_t horizontalAngle, uint16_t verticalAngle); + std::vector servoGetAngles(); + //angle must be in [0, 180] range + bool servoSetAngle(ServoIndex axisIndex, uint16_t angle); + uint16_t servoGetAngle(ServoIndex axisIndex); +}; + +#endif /* _TRACKPLATFORM_BASICMANAGEMENT_H_ */ diff --git a/code/c++/cxx-api/TrackPlatform_Manager.cpp b/code/c++/cxx-api/TrackPlatform_Manager.cpp new file mode 100644 index 0000000..4b512e2 --- /dev/null +++ b/code/c++/cxx-api/TrackPlatform_Manager.cpp @@ -0,0 +1,39 @@ +#include "TrackPlatform_Manager.h" +#include "SerialConnector.h" +#include "TCPIP_Connector.h" + +TrackPlatform_BasicConnector* TrackPlatform_Manager::createConnectorByMode(ConnectionModes mode, const CommunicationInfoStruct& info) +{ + TrackPlatform_BasicConnector* res; + + //TODO: add more modes + switch (mode) + { + case USB: + case bluetooth: + res = new SerialConnector(info.SerialInfo.rxPort, info.SerialInfo.txPort, info.SerialInfo.baudrate); + break; + case WiFi: + res = new TCPIP_Connector(info.TCPIPInfo.ip, info.TCPIPInfo.port); + break; + default: + res = nullptr; + break; + } + + return res; +} + +TrackPlatform_Manager::TrackPlatform_Manager(ConnectionModes mode, const CommunicationInfoStruct& info) : + TrackPlatform_BasicManagement(createConnectorByMode(mode, info)) +{ +} + +TrackPlatform_Manager::~TrackPlatform_Manager() +{ + TrackPlatform_BasicConnector* connector = getConnector(); + if (connector) + { + delete connector; + } +} diff --git a/code/c++/cxx-api/TrackPlatform_Manager.h b/code/c++/cxx-api/TrackPlatform_Manager.h new file mode 100644 index 0000000..bc3f15c --- /dev/null +++ b/code/c++/cxx-api/TrackPlatform_Manager.h @@ -0,0 +1,18 @@ +#ifndef _TRACKPLATFORM_MANAGER_H_ +#define _TRACKPLATFORM_MANAGER_H_ + +#include "TrackPlatform_BasicManagement.h" +#include "ConnectionModes.h" +#include "CommunicationInfoStruct.h" +#include "AutoConnector.h" + +class TrackPlatform_Manager : public TrackPlatform_BasicManagement +{ + static TrackPlatform_BasicConnector* createConnectorByMode(ConnectionModes mode, const CommunicationInfoStruct& info); + +public: + TrackPlatform_Manager(ConnectionModes mode, const CommunicationInfoStruct& info); + ~TrackPlatform_Manager(); +}; + +#endif /* _TRACKPLATFORM_MANAGER_H_ */ diff --git a/code/c++/cxx-api/WSAStartupException.h b/code/c++/cxx-api/WSAStartupException.h new file mode 100644 index 0000000..3f108c4 --- /dev/null +++ b/code/c++/cxx-api/WSAStartupException.h @@ -0,0 +1,14 @@ +#ifndef _WSA_STARTUP_EXCEPTION_H_ +#define _WSA_STARTUP_EXCEPTION_H_ + +#include "TrackPlatformException.h" + +class WSAStartupException : public TrackPlatformException +{ +public: + explicit WSAStartupException(int errorCode) : TrackPlatformException(std::to_string(errorCode)) + { + } +}; + +#endif /* _WSA_STARTUP_EXCEPTION_H_ */ diff --git a/code/c++/cxx-api/cxx-api.sln b/code/c++/cxx-api/cxx-api.sln new file mode 100644 index 0000000..2012296 --- /dev/null +++ b/code/c++/cxx-api/cxx-api.sln @@ -0,0 +1,28 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio 15 +VisualStudioVersion = 15.0.26430.13 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "cxx-api", "cxx-api.vcxproj", "{32D3778A-E59E-4DBC-8D86-BD23B708CA12}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x64.ActiveCfg = Debug|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x64.Build.0 = Debug|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x86.ActiveCfg = Debug|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x86.Build.0 = Debug|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x64.ActiveCfg = Release|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x64.Build.0 = Release|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x86.ActiveCfg = Release|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/code/c++/cxx-api/cxx-api.vcxproj b/code/c++/cxx-api/cxx-api.vcxproj new file mode 100644 index 0000000..6178632 --- /dev/null +++ b/code/c++/cxx-api/cxx-api.vcxproj @@ -0,0 +1,200 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + 15.0 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12} + Win32Proj + cxxapi + + + + StaticLibrary + true + v141 + Unicode + + + StaticLibrary + false + v141 + true + Unicode + + + StaticLibrary + true + v141 + Unicode + + + StaticLibrary + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + $(ProjectDir)serial_support\include\;$(ProjectDir)libcrc\include\;$(IncludePath) + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + + + $(ProjectDir)serial_support\include\;$(ProjectDir)libcrc\include\;$(IncludePath) + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + + + $(ProjectDir)serial_support\include\;$(ProjectDir)libcrc\include\;$(IncludePath) + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + + + $(ProjectDir)serial_support\include\;$(ProjectDir)libcrc\include\;$(IncludePath) + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + + + + + + Level3 + Disabled + WIN32;_DEBUG;_LIB;%(PreprocessorDefinitions) + + + Windows + + + + + + + Level3 + Disabled + _DEBUG;_LIB;%(PreprocessorDefinitions) + + + Windows + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_LIB;%(PreprocessorDefinitions) + + + Windows + true + true + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_LIB;%(PreprocessorDefinitions) + + + Windows + true + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/code/c++/cxx-api/cxx-api.vcxproj.filters b/code/c++/cxx-api/cxx-api.vcxproj.filters new file mode 100644 index 0000000..f99e54d --- /dev/null +++ b/code/c++/cxx-api/cxx-api.vcxproj.filters @@ -0,0 +1,192 @@ + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + {de9cad78-f264-4652-87a0-7f8536f7ef0c} + + + {7f55ad7e-608f-469d-8efc-4fbaa0e120fd} + + + {a897fa9d-d634-41b6-a441-71b4a660fa92} + + + {09716c3b-089b-4880-b137-c4da5ccc81f8} + + + {619f9cf3-95aa-4cd8-9da7-8054ec8ca353} + + + {8cb6d371-6c98-4f8c-ace2-6e3059467355} + + + {c8707437-f967-4f30-b1b5-cde6082dca67} + + + {20cccc26-6e34-4b3e-8ed5-4d44cbf4c28e} + + + {42cc74a7-2d02-4a96-828e-2b504625d84d} + + + {cdbc6cec-ccb7-4c9c-a1a5-6fdbe56204dc} + + + {fda69c34-400a-4e92-b382-d41dca8e6dc8} + + + {008c4554-de8a-4ef6-97a6-8b56e109ec79} + + + + + Header Files + + + Header Files + + + serial_support\header + + + serial_support\header + + + serial_support\header + + + Header Files + + + Communication\header + + + Communication\header + + + Communication\header + + + exceptions\header + + + exceptions\header + + + exceptions\header + + + exceptions\header + + + exceptions\header + + + exceptions\header + + + exceptions + + + exceptions\header + + + Communication\header + + + Communication + + + Header Files + + + exceptions\header + + + exceptions\header + + + exceptions\header + + + Communication\header + + + libcrc\header + + + exceptions\header + + + + + Source Files + + + serial_support\source + + + serial_support\source + + + serial_support\source + + + Source Files + + + Communication\source + + + Communication\source + + + exceptions\source + + + Communication\source + + + Source Files + + + Communication\source + + + libcrc\source + + + libcrc\source + + + libcrc\source + + + libcrc\source + + + libcrc\source + + + libcrc\source + + + libcrc\source + + + libcrc\source + + + \ No newline at end of file diff --git a/code/c++/cxx-api/libcrc b/code/c++/cxx-api/libcrc new file mode 160000 index 0000000..32aacc5 --- /dev/null +++ b/code/c++/cxx-api/libcrc @@ -0,0 +1 @@ +Subproject commit 32aacc558ed599d8e5d38bc8d7dd850681e5c12e diff --git a/code/c++/cxx-api/makefile b/code/c++/cxx-api/makefile new file mode 100644 index 0000000..3d6bc88 --- /dev/null +++ b/code/c++/cxx-api/makefile @@ -0,0 +1,171 @@ +#Make file to compile source code for track platform cxx api library + +#Project Name +PROJECT_NAME = track-platform_cxx-api +#Build option +BUILD ?= BUILD_STATIC +#ANSI Colos +ANSI_COLOR_RED = \e[31m +ANSI_COLOR_GREEN = \e[32m +ANSI_COLOR_YELLOW = \e[33m +ANSI_COLOR_BLUE = \e[34m +ANSI_COLOR_MAGENTA = \e[35m +ANSI_COLOR_CYAN = \e[36m +ANSI_COLOR_RESET = \e[37m +################################Compiller flags############################################################### +#Opitmization Level +OPT_LEVEL = -O0 +#Warning options +WARNINGS = -Wall -Wpedantic #-Werror +# WARNINGS += -fsyntax-only # for syntax checking only, without comlipation +WARNINGS_WITHOUT = +#User Compiller flags +USER_FLAGS ?= +############################################################################################################## +# OS redefinition +OS = $(shell uname -s) +ifeq ($(OS), Linux) +OS = linux +endif + +#Build patch +BUILD_PATH = Output/$(OS) +OBJ_PATH = $(BUILD_PATH)/obj + +#Compiller flags +CFLAGS = $(OPT_LEVEL) +CFLAGS += -g0 +CFLAGS += $(WARNINGS) +CFLAGS += -I. +CFLAGS += $(USER_FLAGS) +CFLAGS += -std=c++11 +CFLAGS += -D$(BUILD) +# ifeq ($(BUILD), BUILD_STATIC) +# CFLAGS += -D$(BUILD_STATIC) +# endif + +CFLAGS += $(INCLUDES) +############################################################################################################## +#Code file path +SERIAL_PATH = serial_support +SERIAL_SOURCE_PATH = $(SERIAL_PATH)/src +SERIAL_SOURCE_IMPL_PATH = $(SERIAL_SOURCE_PATH)/impl +SERIAL_SOURCE_LIST_PORTS_PATH = $(SERIAL_SOURCE_IMPL_PATH)/list_ports +SERIAL_INCLUDE_PATH = $(SERIAL_PATH)/include +COMMUNICATION_PATH = . +COMMUNICATION_SOURCE_PATH = $(COMMUNICATION_PATH) +COMMUNICATION_INCLUDE_PATH = $(COMMUNICATION_PATH) +# PLATFORM_DEPENDENT_PATH = platform_dependent/$(OS) +# PLATFORM_DEPENDENT_SOURCE_PATH = $(PLATFORM_DEPENDENT_PATH) +# PLATFORM_DEPENDENT_INCLUDE_PATH = $(PLATFORM_DEPENDENT_PATH) +EXCEPTION_PATH = . +EXCEPTION_SOURCE_PATH = $(EXCEPTION_PATH) +EXCEPTION_INCLUDE_PATH = $(EXCEPTION_PATH) +OTHER_PATH = . +OTHER_SOURCE_PATH = $(OTHER_PATH) +OTHER_INCLUDE_PATH = $(OTHER_PATH) + +#Linker scrpit file +ARFLAGS = -cvq + +#Source file path + +SOURCES = +# Serial support +SOURCES += $(SERIAL_SOURCE_PATH)/serial.cc +SOURCES += $(SERIAL_SOURCE_IMPL_PATH)/unix.cc +SOURCES += $(SERIAL_SOURCE_LIST_PORTS_PATH)/list_ports_linux.cc +# Communication +SOURCES += $(COMMUNICATION_SOURCE_PATH)/TrackPlatform_BasicConnector.cpp +SOURCES += $(COMMUNICATION_SOURCE_PATH)/SerialConnector.cpp +SOURCES += $(COMMUNICATION_SOURCE_PATH)/TCPIP_Connector.cpp +# Platform-dependent sources +# Exceptions sources +SOURCES += $(EXCEPTION_SOURCE_PATH)/TrackPlatformException.cpp +# Other code (non grouped) +SOURCES += $(OTHER_SOURCE_PATH)/TrackPlatform_BasicManagement.cpp +SOURCES += $(OTHER_SOURCE_PATH)/TrackPlatform_Manager.cpp +SOURCES += $(OTHER_SOURCE_PATH)/Logger.cpp + +#Include file path +INCLUDES = +INCLUDES += -I$(SERIAL_INCLUDE_PATH) +# INCLUDES += -I$(COMMUNICATION_INCLUDE_PATH) +# INCLUDES += -I$(PLATFORM_DEPENDENT_INCLUDE_PATH) +# INCLUDES += -I$(EXCEPTION_INCLUDE_PATH) +# INCLUDES += -I$(OTHER_INCLUDE_PATH) + +############################################################################################################## +BUILD_PRINT = $(ANSI_COLOR_GREEN) Building:$(ANSI_COLOR_RESET) $@ +############################################################################################################## +#Output files +STATIC_LIB = $(BUILD_PATH)/$(PROJECT_NAME).a +DYNAMIC_LIB = $(BUILD_PATH)/$(PROJECT_NAME).so + +OBJECTS = $(addprefix $(OBJ_PATH)/, $(addsuffix .o, $(basename $(SOURCES)))) + +$(STATIC_LIB): $(OBJECTS) + @$(AR) $(ARFLAGS) $@ $(OBJECTS) + @echo -e "$(BUILD_PRINT)" + +$(DYNAMIC_LIB): $(OBJECTS) +# $(error Dynamic library is not supported yet) + @$(CXX) -shared -o $@ $(OBJECTS) + @echo -e "$(BUILD_PRINT)" + +$(OBJ_PATH)/%.o: %.cc + @mkdir -p $(dir $@) + +ifeq ($(BUILD), BUILD_DYNAMIC) + @$(CXX) -fPIC -c $(CFLAGS) $< -o $@ +else + @$(CXX) -c $(CFLAGS) $< -o $@ +endif + @echo -e "$(BUILD_PRINT)" + +$(OBJ_PATH)/%.o: %.cpp + @mkdir -p $(dir $@) + +ifeq ($(BUILD), BUILD_DYNAMIC) + @$(CXX) -fPIC -c $(CFLAGS) $< -o $@ +else + @$(CXX) -c $(CFLAGS) $< -o $@ +endif + @echo -e "$(BUILD_PRINT)" + +#Makefile parameters +.DEFAULT_GOAL := all + +all: build + +ifeq ($(BUILD), BUILD_STATIC) +build: $(STATIC_LIB) + +else +ifeq ($(BUILD), BUILD_DYNAMIC) +build: $(DYNAMIC_LIB) + +else +build: + @echo "That BUILD variable is not supported. Use `make help` to see supported variants of build variable" +endif +endif + +dynamic: + $(MAKE) BUILD=BUILD_DYNAMIC + +static: + $(MAKE) BUILD=BUILD_STATIC + +clean: + @rm -rf $(BUILD_PATH) + +set_def_color: + @echo -e "$(ANSI_COLOR_RESET)" + +help: + @echo "$(NEW_LINE)" + @echo "\tall : Builds static or dynamic library (static by default)" + @echo "\t\tIf you want to build static library(.a file), write `make` or `make static` or `make BUILD=BUILD_DYNAMIC`" + @echo "\t\tIf you want to build dynamic library(.so file), write `make dynamic` or `make BUILD=BUILD_DYNAMIC`" + @echo "$(NEW_LINE)" diff --git a/code/c++/cxx-api/serial_support b/code/c++/cxx-api/serial_support new file mode 160000 index 0000000..827c4a7 --- /dev/null +++ b/code/c++/cxx-api/serial_support @@ -0,0 +1 @@ +Subproject commit 827c4a784dd4fdd35dc391f37ef152eab7c9c9b2 diff --git a/code/c++/cxx-api/trackPlatformAllExceptions.h b/code/c++/cxx-api/trackPlatformAllExceptions.h new file mode 100644 index 0000000..52ce186 --- /dev/null +++ b/code/c++/cxx-api/trackPlatformAllExceptions.h @@ -0,0 +1,16 @@ +#ifndef _TRACK_PLATFORM_ALL_EXCEPTIONS_H_ +#define _TRACK_PLATFORM_ALL_EXCEPTIONS_H_ + +#include "TrackPlatformException.h" +#include "WSAStartupException.h" +#include "BadAddressOrPortException.h" +#include "SocketException.h" +#include "SocketShutdownException.h" +#include "SocketSendException.h" +#include "SocketReceiveException.h" +#include "CannotConnectToArduinoException.h" +#include "CorruptedAnswerException.h" +#include "NoConnectionException.h" +#include "TimeoutException.h" + +#endif /* _TRACK_PLATFORM_ALL_EXCEPTIONS_H_ */ diff --git a/code/c++/cxx-app/.gitignore b/code/c++/cxx-app/.gitignore new file mode 100644 index 0000000..1d434d3 --- /dev/null +++ b/code/c++/cxx-app/.gitignore @@ -0,0 +1,299 @@ +## Ignore Visual Studio temporary files, build results, and +## files generated by popular Visual Studio add-ons. +## +## Get latest from https://github.com/github/gitignore/blob/master/VisualStudio.gitignore + +# User-specific files +*.suo +*.user +*.userosscache +*.sln.docstates + +# User-specific files (MonoDevelop/Xamarin Studio) +*.userprefs + +# Build results +[Dd]ebug/ +[Dd]ebugPublic/ +[Rr]elease/ +[Rr]eleases/ +x64/ +x86/ +bld/ +[Bb]in/ +[Oo]bj/ +[Ll]og/ + +# Visual Studio 2015 cache/options directory +.vs/ +# Uncomment if you have tasks that create the project's static files in wwwroot +#wwwroot/ + +# MSTest test Results +[Tt]est[Rr]esult*/ +[Bb]uild[Ll]og.* + +# NUNIT +*.VisualState.xml +TestResult.xml + +# Build Results of an ATL Project +[Dd]ebugPS/ +[Rr]eleasePS/ +dlldata.c + +# Benchmark Results +BenchmarkDotNet.Artifacts/ + +# .NET Core +project.lock.json +project.fragment.lock.json +artifacts/ +**/Properties/launchSettings.json + +*_i.c +*_p.c +*_i.h +*.ilk +*.meta +*.obj +*.pch +*.pdb +*.pgc +*.pgd +*.rsp +*.sbr +*.tlb +*.tli +*.tlh +*.tmp +*.tmp_proj +*.log +*.vspscc +*.vssscc +.builds +*.pidb +*.svclog +*.scc + +# Chutzpah Test files +_Chutzpah* + +# Visual C++ cache files +ipch/ +*.aps +*.ncb +*.opendb +*.opensdf +*.sdf +*.cachefile +*.VC.db +*.VC.VC.opendb + +# Visual Studio profiler +*.psess +*.vsp +*.vspx +*.sap + +# TFS 2012 Local Workspace +$tf/ + +# Guidance Automation Toolkit +*.gpState + +# ReSharper is a .NET coding add-in +_ReSharper*/ +*.[Rr]e[Ss]harper +*.DotSettings.user + +# JustCode is a .NET coding add-in +.JustCode + +# TeamCity is a build add-in +_TeamCity* + +# DotCover is a Code Coverage Tool +*.dotCover + +# Visual Studio code coverage results +*.coverage +*.coveragexml + +# NCrunch +_NCrunch_* +.*crunch*.local.xml +nCrunchTemp_* + +# MightyMoose +*.mm.* +AutoTest.Net/ + +# Web workbench (sass) +.sass-cache/ + +# Installshield output folder +[Ee]xpress/ + +# DocProject is a documentation generator add-in +DocProject/buildhelp/ +DocProject/Help/*.HxT +DocProject/Help/*.HxC +DocProject/Help/*.hhc +DocProject/Help/*.hhk +DocProject/Help/*.hhp +DocProject/Help/Html2 +DocProject/Help/html + +# Click-Once directory +publish/ + +# Publish Web Output +*.[Pp]ublish.xml +*.azurePubxml +# TODO: Comment the next line if you want to checkin your web deploy settings +# but database connection strings (with potential passwords) will be unencrypted +*.pubxml +*.publishproj + +# Microsoft Azure Web App publish settings. Comment the next line if you want to +# checkin your Azure Web App publish settings, but sensitive information contained +# in these scripts will be unencrypted +PublishScripts/ + +# NuGet Packages +*.nupkg +# The packages folder can be ignored because of Package Restore +**/packages/* +# except build/, which is used as an MSBuild target. +!**/packages/build/ +# Uncomment if necessary however generally it will be regenerated when needed +#!**/packages/repositories.config +# NuGet v3's project.json files produces more ignorable files +*.nuget.props +*.nuget.targets + +# Microsoft Azure Build Output +csx/ +*.build.csdef + +# Microsoft Azure Emulator +ecf/ +rcf/ + +# Windows Store app package directories and files +AppPackages/ +BundleArtifacts/ +Package.StoreAssociation.xml +_pkginfo.txt +*.appx + +# Visual Studio cache files +# files ending in .cache can be ignored +*.[Cc]ache +# but keep track of directories ending in .cache +!*.[Cc]ache/ + +# Others +ClientBin/ +~$* +*~ +*.dbmdl +*.dbproj.schemaview +*.jfm +*.pfx +*.publishsettings +orleans.codegen.cs + +# Since there are multiple workflows, uncomment next line to ignore bower_components +# (https://github.com/github/gitignore/pull/1529#issuecomment-104372622) +#bower_components/ + +# RIA/Silverlight projects +Generated_Code/ + +# Backup & report files from converting an old project file +# to a newer Visual Studio version. Backup files are not needed, +# because we have git ;-) +_UpgradeReport_Files/ +Backup*/ +UpgradeLog*.XML +UpgradeLog*.htm + +# SQL Server files +*.mdf +*.ldf +*.ndf + +# Business Intelligence projects +*.rdl.data +*.bim.layout +*.bim_*.settings + +# Microsoft Fakes +FakesAssemblies/ + +# GhostDoc plugin setting file +*.GhostDoc.xml + +# Node.js Tools for Visual Studio +.ntvs_analysis.dat +node_modules/ + +# Typescript v1 declaration files +typings/ + +# Visual Studio 6 build log +*.plg + +# Visual Studio 6 workspace options file +*.opt + +# Visual Studio 6 auto-generated workspace file (contains which files were open etc.) +*.vbw + +# Visual Studio LightSwitch build output +**/*.HTMLClient/GeneratedArtifacts +**/*.DesktopClient/GeneratedArtifacts +**/*.DesktopClient/ModelManifest.xml +**/*.Server/GeneratedArtifacts +**/*.Server/ModelManifest.xml +_Pvt_Extensions + +# Paket dependency manager +.paket/paket.exe +paket-files/ + +# FAKE - F# Make +.fake/ + +# JetBrains Rider +.idea/ +*.sln.iml + +# CodeRush +.cr/ + +# Python Tools for Visual Studio (PTVS) +__pycache__/ +*.pyc + +# Cake - Uncomment if you are using it +# tools/** +# !tools/packages.config + +# Tabs Studio +*.tss + +# Telerik's JustMock configuration file +*.jmconfig + +# BizTalk build output +*.btp.cs +*.btm.cs +*.odx.cs +*.xsd.cs + +# AJIOB_Exclude +Output +Build* diff --git a/code/c++/cxx-app/cxx-app.sln b/code/c++/cxx-app/cxx-app.sln new file mode 100644 index 0000000..abd6f05 --- /dev/null +++ b/code/c++/cxx-app/cxx-app.sln @@ -0,0 +1,58 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio 15 +VisualStudioVersion = 15.0.27004.2010 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "cxx-app", "cxx-app.vcxproj", "{F92E7862-33C4-48B8-A055-3EE00352161F}" + ProjectSection(ProjectDependencies) = postProject + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA} = {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA} + {32D3778A-E59E-4DBC-8D86-BD23B708CA12} = {32D3778A-E59E-4DBC-8D86-BD23B708CA12} + EndProjectSection +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "cxx-api", "..\cxx-api\cxx-api.vcxproj", "{32D3778A-E59E-4DBC-8D86-BD23B708CA12}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "cxx-library", "..\cxx-library\cxx-library.vcxproj", "{57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}" + ProjectSection(ProjectDependencies) = postProject + {32D3778A-E59E-4DBC-8D86-BD23B708CA12} = {32D3778A-E59E-4DBC-8D86-BD23B708CA12} + EndProjectSection +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {F92E7862-33C4-48B8-A055-3EE00352161F}.Debug|x64.ActiveCfg = Debug|x64 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Debug|x64.Build.0 = Debug|x64 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Debug|x86.ActiveCfg = Debug|Win32 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Debug|x86.Build.0 = Debug|Win32 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Release|x64.ActiveCfg = Release|x64 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Release|x64.Build.0 = Release|x64 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Release|x86.ActiveCfg = Release|Win32 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Release|x86.Build.0 = Release|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x64.ActiveCfg = Debug|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x64.Build.0 = Debug|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x86.ActiveCfg = Debug|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x86.Build.0 = Debug|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x64.ActiveCfg = Release|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x64.Build.0 = Release|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x86.ActiveCfg = Release|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x86.Build.0 = Release|Win32 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Debug|x64.ActiveCfg = Debug|x64 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Debug|x64.Build.0 = Debug|x64 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Debug|x86.ActiveCfg = Debug|Win32 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Debug|x86.Build.0 = Debug|Win32 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Release|x64.ActiveCfg = Release|x64 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Release|x64.Build.0 = Release|x64 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Release|x86.ActiveCfg = Release|Win32 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection + GlobalSection(ExtensibilityGlobals) = postSolution + SolutionGuid = {212D1529-F640-4E3D-BDFD-1300BE6FF8CF} + EndGlobalSection +EndGlobal diff --git a/code/c++/trackPlatform/trackPlatform/trackPlatform.vcxproj b/code/c++/cxx-app/cxx-app.vcxproj similarity index 73% rename from code/c++/trackPlatform/trackPlatform/trackPlatform.vcxproj rename to code/c++/cxx-app/cxx-app.vcxproj index c5e576e..07045c9 100644 --- a/code/c++/trackPlatform/trackPlatform/trackPlatform.vcxproj +++ b/code/c++/cxx-app/cxx-app.vcxproj @@ -20,17 +20,16 @@ 15.0 - {DFA451D9-6F5A-4485-9CAD-27F7E3C32A90} + {F92E7862-33C4-48B8-A055-3EE00352161F} Win32Proj - trackPlatform - 10.0.14393.0 + cxxapp Application true v141 - MultiByte + Unicode Application @@ -72,15 +71,31 @@ true + $(SolutionDir)..\cxx-api;$(SolutionDir)..\cxx-library;$(SolutionDir)..\cxx-api\serial_support\include;$(IncludePath) + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Output\$(Configuration)-$(Platform)\;$(OutDir);$(LibraryPath) + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ true + $(SolutionDir)..\cxx-api;$(SolutionDir)..\cxx-library;$(SolutionDir)..\cxx-api\serial_support\include;$(IncludePath) + $(SolutionDir)Output\$(Configuration)-$(Platform)\;$(OutDir);$(LibraryPath) + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ false + $(SolutionDir)..\cxx-api;$(SolutionDir)..\cxx-library;$(SolutionDir)..\cxx-api\serial_support\include;$(IncludePath) + $(SolutionDir)Output\$(Configuration)-$(Platform)\;$(OutDir);$(LibraryPath) + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ false + $(SolutionDir)Output\$(Configuration)-$(Platform)\;$(OutDir);$(LibraryPath) + $(SolutionDir)..\cxx-api;$(SolutionDir)..\cxx-library;$(SolutionDir)..\cxx-api\serial_support\include;$(IncludePath) + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ @@ -89,9 +104,12 @@ Level3 Disabled WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + Console + cxx-api.lib;cxx-library.lib; @@ -101,9 +119,12 @@ Level3 Disabled _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + + Console + cxx-api.lib;cxx-library.lib; @@ -115,11 +136,14 @@ true true WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + Console true true + cxx-api.lib;cxx-library.lib; @@ -131,24 +155,19 @@ true true NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + + Console true true + cxx-api.lib;cxx-library.lib; - - - - - - - - diff --git a/code/c++/cxx-app/cxx-app.vcxproj.filters b/code/c++/cxx-app/cxx-app.vcxproj.filters new file mode 100644 index 0000000..0d8d9e4 --- /dev/null +++ b/code/c++/cxx-app/cxx-app.vcxproj.filters @@ -0,0 +1,22 @@ + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + + + Source Files + + + \ No newline at end of file diff --git a/code/c++/cxx-app/main.cpp b/code/c++/cxx-app/main.cpp new file mode 100644 index 0000000..2e07c30 --- /dev/null +++ b/code/c++/cxx-app/main.cpp @@ -0,0 +1,156 @@ +#include +#include + +#if defined(_WIN32) +#include +#else +#include +#define _getche getchar +#endif + +#include "TrackPlatform_Manager.h" +#include "SensorsViewer.h" +#include "ConsolePlatformConnector.h" + +int main(int argc, char* argv[]) +{ + TrackPlatform_Manager* trackPlatform = nullptr; + int errorCode = 0; + try + { + ConsolePlatformConnector platformConnector; + trackPlatform = platformConnector.connect(); + if (!trackPlatform) + { + return 2; + } + + std::cout << "Connected" << std::endl; + + bool isExit = false; + while (!isExit) + { + std::cout << "Input command, please (0 to help): "; + auto c = _getche(); + std::cout << std::endl; + + switch (c) + { + case '0': + std::cout << "0: help" << std::endl; + std::cout << "q: quit" << std::endl; + std::cout << "w: move forward" << std::endl; + std::cout << "s: move back" << std::endl; + std::cout << "a: turn left (anticlockwise)" << std::endl; + std::cout << "d: turn right (clockwise)" << std::endl; + std::cout << " : stop" << std::endl; + std::cout << "r: get all line values" << std::endl; + std::cout << "e: get fixed line value" << std::endl; + std::cout << "u: show line sensors" << std::endl; + std::cout << "t: get all distance values" << std::endl; + std::cout << "y: get fixed distance value" << std::endl; + std::cout << "i: show distance sensors" << std::endl; + std::cout << "g: set horisontal servo angle in degree" << std::endl; + std::cout << "h: set vertical servo angle in degree" << std::endl; + break; + case 'q': + isExit = true; + break; + case 'w': + trackPlatform->moveForward(); + break; + case 's': + trackPlatform->moveBackward(); + break; + case 'a': + trackPlatform->rotateAntiClockwise(); + break; + case 'd': + trackPlatform->rotateClockwise(); + break; + case ' ': + trackPlatform->moveStopAll(); + break; + case 'r': + { + auto arr = trackPlatform->sensorLineGetAllValues(); + for (auto a : arr) + { + std::cout << a << std::endl; + } + break; + } + case 'e': + { + std::cout << "Input num: "; + int a; + std::cin >> a; + std::cout << "Value: " << trackPlatform->sensorLineGetValue(a) << std::endl; + break; + } + case 'u': + { + SensorsViewer sv; + auto arr = trackPlatform->sensorLineGetAllValues(); + sv.setData(arr, LINE_SENSORS); + std::cout << std::endl; + sv.show(); + } + case 't': + { + auto arr = trackPlatform->sensorDistanceGetAllValues(); + for (auto a : arr) + { + std::cout << a << std::endl; + } + break; + } + case 'y': + { + std::cout << "Input num: "; + int a; + std::cin >> a; + std::cout << "Value: " << trackPlatform->sensorDistanceGetValue(a) << std::endl; + break; + } + case 'i': + { + SensorsViewer sv; + auto arr = trackPlatform->sensorDistanceGetAllValues(); + sv.setData(arr, DISTANCE_SENSORS); + std::cout << std::endl; + sv.show(); + } + case 'g': + { + std::cout << "Input num: "; + int a; + std::cin >> a; + trackPlatform->servoSetHorizontalAngle(a); + break; + } + case 'h': + { + std::cout << "Input num: "; + int a; + std::cin >> a; + trackPlatform->servoSetVerticalAngle(a); + break; + } + default: break; + } + } + } + catch (...) + { + std::cout << "Exception was catched" << std::endl; + errorCode = 1; + } + + if (trackPlatform) + { + delete trackPlatform; + } + return errorCode; +} + diff --git a/code/c++/cxx-app/makefile b/code/c++/cxx-app/makefile new file mode 100644 index 0000000..ce7d227 --- /dev/null +++ b/code/c++/cxx-app/makefile @@ -0,0 +1,164 @@ +#Make file to compile source code for track platform cxx api library + +#Project Name +PROJECT_NAME = track-platform_cxx-app +#Build option +BUILD ?= BUILD_STATIC +#ANSI Colos +ANSI_COLOR_RED = \e[31m +ANSI_COLOR_GREEN = \e[32m +ANSI_COLOR_YELLOW = \e[33m +ANSI_COLOR_BLUE = \e[34m +ANSI_COLOR_MAGENTA = \e[35m +ANSI_COLOR_CYAN = \e[36m +ANSI_COLOR_RESET = \e[37m +################################Compiller flags############################################################### +#Opitmization Level +OPT_LEVEL = -O0 +#Warning options +WARNINGS = -Wall -Wpedantic #-Werror +# WARNINGS += -fsyntax-only # for syntax checking only, without comlipation +WARNINGS_WITHOUT = +#User Compiller flags +USER_FLAGS ?= +############################################################################################################## +# OS redefinition +OS = $(shell uname -s) +ifeq ($(OS), Linux) +OS = linux +endif + +#Build patch +BUILD_PATH = Output/$(OS) +OBJ_PATH = $(BUILD_PATH)/obj + +#Compiller flags +CFLAGS = $(OPT_LEVEL) +CFLAGS += -g0 +CFLAGS += $(WARNINGS) +CFLAGS += -I. +CFLAGS += $(USER_FLAGS) +CFLAGS += -std=c++11 +CFLAGS += -D$(BUILD) +# ifeq ($(BUILD), BUILD_STATIC) +# CFLAGS += -D$(BUILD_STATIC) +# endif + +CFLAGS += $(INCLUDES) +############################################################################################################## +#Code file path +OTHER_PATH = . +OTHER_SOURCE_PATH = $(OTHER_PATH) +OTHER_INCLUDE_PATH = $(OTHER_PATH) + +#library path +API_PATH = ../cxx-api +API_INCLUDE_PATH = $(API_PATH) +API_BUILD_PATH = $(API_PATH)/$(BUILD_PATH) + +CXX_LIB_PATH = ../cxx-library +CXX_LIB_INCLUDE_PATH = $(CXX_LIB_PATH) +CXX_LIB_BUILD_PATH = $(CXX_LIB_PATH)/$(BUILD_PATH) + +ifeq ($(BUILD), BUILD_STATIC) +API_NAME = track-platform_cxx-api.a +CXX_LIB_NAME = track-platform_cxx-library.a +else +ifeq ($(BUILD), BUILD_DYNAMIC) +API_NAME = track-platform_cxx-api.so +CXX_LIB_NAME = track-platform_cxx-library.so +endif +endif + +API_FULL_PATH = $(API_BUILD_PATH)/$(API_NAME) +CXX_LIB_FULL_PATH = $(CXX_LIB_BUILD_PATH)/$(CXX_LIB_NAME) + +#Linker scrpit file +ARFLAGS = + +#Source file path + +SOURCES = +# Other code (non grouped) +SOURCES += $(OTHER_SOURCE_PATH)/main.cpp + +#Include file path +INCLUDES = +INCLUDES += -I$(API_INCLUDE_PATH) +INCLUDES += -I$(CXX_LIB_INCLUDE_PATH) +# INCLUDES += -I$(OTHER_INCLUDE_PATH) + +############################################################################################################## +BUILD_PRINT = $(ANSI_COLOR_GREEN) Building:$(ANSI_COLOR_RESET) $@ +############################################################################################################## +#Output files +BIN = $(BUILD_PATH)/$(PROJECT_NAME) + +OBJECTS = $(addprefix $(OBJ_PATH)/, $(addsuffix .o, $(basename $(SOURCES)))) + +STATIC_LIB: $(OBJECTS) api library + @$(CXX) -o $(BIN) $(OBJECTS) $(API_FULL_PATH) $(CXX_LIB_FULL_PATH) + @echo -e "$(BUILD_PRINT)" + +DYNAMIC_LIB: $(OBJECTS) api librarylibrary + $(error Dynamic library is not supported yet) + # @$(CXX) -shared -o $(BIN) $(OBJECTS) + @echo -e "$(BUILD_PRINT)" + +$(OBJ_PATH)/%.o: %.cc + @mkdir -p $(dir $@) + @$(CXX) -c $(CFLAGS) $< -o $@ + @echo -e "$(BUILD_PRINT)" + +$(OBJ_PATH)/%.o: %.cpp + @mkdir -p $(dir $@) + @$(CXX) -c $(CFLAGS) $< -o $@ + @echo -e "$(BUILD_PRINT)" + +#Makefile parameters +.DEFAULT_GOAL := all + +all: build + +ifeq ($(BUILD), BUILD_STATIC) +build: STATIC_LIB + +else +ifeq ($(BUILD), BUILD_DYNAMIC) +build: DYNAMIC_LIB + +else +build: + @echo "That BUILD variable is not supported. Use `make help` to see supported variants of build variable" +endif +endif + +dynamic: + $(MAKE) BUILD=BUILD_DYNAMIC + +static: + $(MAKE) BUILD=BUILD_STATIC + +api: + $(MAKE) -C $(API_PATH) BUILD=$(BUILD) + +library: + $(MAKE) -C $(CXX_LIB_PATH) BUILD=$(BUILD) + +clean: + @rm -rf $(BUILD_PATH) + $(MAKE) -C $(API_PATH) $@ + $(MAKE) -C $(CXX_LIB_PATH) $@ + +run: + @$(BIN) + +set_def_color: + @echo -e "$(ANSI_COLOR_RESET)" + +help: + @echo "$(NEW_LINE)" + @echo "\tall : Builds static or dynamic library (static by default)" + @echo "\t\tIf you want to build static library(.a file), write `make` or `make static` or `make BUILD=BUILD_DYNAMIC`" + @echo "\t\tIf you want to build dynamic library(.so file), write `make dynamic` or `make BUILD=BUILD_DYNAMIC`" + @echo "$(NEW_LINE)" diff --git a/code/c++/cxx-gamepad-app/.gitignore b/code/c++/cxx-gamepad-app/.gitignore new file mode 100644 index 0000000..1d434d3 --- /dev/null +++ b/code/c++/cxx-gamepad-app/.gitignore @@ -0,0 +1,299 @@ +## Ignore Visual Studio temporary files, build results, and +## files generated by popular Visual Studio add-ons. +## +## Get latest from https://github.com/github/gitignore/blob/master/VisualStudio.gitignore + +# User-specific files +*.suo +*.user +*.userosscache +*.sln.docstates + +# User-specific files (MonoDevelop/Xamarin Studio) +*.userprefs + +# Build results +[Dd]ebug/ +[Dd]ebugPublic/ +[Rr]elease/ +[Rr]eleases/ +x64/ +x86/ +bld/ +[Bb]in/ +[Oo]bj/ +[Ll]og/ + +# Visual Studio 2015 cache/options directory +.vs/ +# Uncomment if you have tasks that create the project's static files in wwwroot +#wwwroot/ + +# MSTest test Results +[Tt]est[Rr]esult*/ +[Bb]uild[Ll]og.* + +# NUNIT +*.VisualState.xml +TestResult.xml + +# Build Results of an ATL Project +[Dd]ebugPS/ +[Rr]eleasePS/ +dlldata.c + +# Benchmark Results +BenchmarkDotNet.Artifacts/ + +# .NET Core +project.lock.json +project.fragment.lock.json +artifacts/ +**/Properties/launchSettings.json + +*_i.c +*_p.c +*_i.h +*.ilk +*.meta +*.obj +*.pch +*.pdb +*.pgc +*.pgd +*.rsp +*.sbr +*.tlb +*.tli +*.tlh +*.tmp +*.tmp_proj +*.log +*.vspscc +*.vssscc +.builds +*.pidb +*.svclog +*.scc + +# Chutzpah Test files +_Chutzpah* + +# Visual C++ cache files +ipch/ +*.aps +*.ncb +*.opendb +*.opensdf +*.sdf +*.cachefile +*.VC.db +*.VC.VC.opendb + +# Visual Studio profiler +*.psess +*.vsp +*.vspx +*.sap + +# TFS 2012 Local Workspace +$tf/ + +# Guidance Automation Toolkit +*.gpState + +# ReSharper is a .NET coding add-in +_ReSharper*/ +*.[Rr]e[Ss]harper +*.DotSettings.user + +# JustCode is a .NET coding add-in +.JustCode + +# TeamCity is a build add-in +_TeamCity* + +# DotCover is a Code Coverage Tool +*.dotCover + +# Visual Studio code coverage results +*.coverage +*.coveragexml + +# NCrunch +_NCrunch_* +.*crunch*.local.xml +nCrunchTemp_* + +# MightyMoose +*.mm.* +AutoTest.Net/ + +# Web workbench (sass) +.sass-cache/ + +# Installshield output folder +[Ee]xpress/ + +# DocProject is a documentation generator add-in +DocProject/buildhelp/ +DocProject/Help/*.HxT +DocProject/Help/*.HxC +DocProject/Help/*.hhc +DocProject/Help/*.hhk +DocProject/Help/*.hhp +DocProject/Help/Html2 +DocProject/Help/html + +# Click-Once directory +publish/ + +# Publish Web Output +*.[Pp]ublish.xml +*.azurePubxml +# TODO: Comment the next line if you want to checkin your web deploy settings +# but database connection strings (with potential passwords) will be unencrypted +*.pubxml +*.publishproj + +# Microsoft Azure Web App publish settings. Comment the next line if you want to +# checkin your Azure Web App publish settings, but sensitive information contained +# in these scripts will be unencrypted +PublishScripts/ + +# NuGet Packages +*.nupkg +# The packages folder can be ignored because of Package Restore +**/packages/* +# except build/, which is used as an MSBuild target. +!**/packages/build/ +# Uncomment if necessary however generally it will be regenerated when needed +#!**/packages/repositories.config +# NuGet v3's project.json files produces more ignorable files +*.nuget.props +*.nuget.targets + +# Microsoft Azure Build Output +csx/ +*.build.csdef + +# Microsoft Azure Emulator +ecf/ +rcf/ + +# Windows Store app package directories and files +AppPackages/ +BundleArtifacts/ +Package.StoreAssociation.xml +_pkginfo.txt +*.appx + +# Visual Studio cache files +# files ending in .cache can be ignored +*.[Cc]ache +# but keep track of directories ending in .cache +!*.[Cc]ache/ + +# Others +ClientBin/ +~$* +*~ +*.dbmdl +*.dbproj.schemaview +*.jfm +*.pfx +*.publishsettings +orleans.codegen.cs + +# Since there are multiple workflows, uncomment next line to ignore bower_components +# (https://github.com/github/gitignore/pull/1529#issuecomment-104372622) +#bower_components/ + +# RIA/Silverlight projects +Generated_Code/ + +# Backup & report files from converting an old project file +# to a newer Visual Studio version. Backup files are not needed, +# because we have git ;-) +_UpgradeReport_Files/ +Backup*/ +UpgradeLog*.XML +UpgradeLog*.htm + +# SQL Server files +*.mdf +*.ldf +*.ndf + +# Business Intelligence projects +*.rdl.data +*.bim.layout +*.bim_*.settings + +# Microsoft Fakes +FakesAssemblies/ + +# GhostDoc plugin setting file +*.GhostDoc.xml + +# Node.js Tools for Visual Studio +.ntvs_analysis.dat +node_modules/ + +# Typescript v1 declaration files +typings/ + +# Visual Studio 6 build log +*.plg + +# Visual Studio 6 workspace options file +*.opt + +# Visual Studio 6 auto-generated workspace file (contains which files were open etc.) +*.vbw + +# Visual Studio LightSwitch build output +**/*.HTMLClient/GeneratedArtifacts +**/*.DesktopClient/GeneratedArtifacts +**/*.DesktopClient/ModelManifest.xml +**/*.Server/GeneratedArtifacts +**/*.Server/ModelManifest.xml +_Pvt_Extensions + +# Paket dependency manager +.paket/paket.exe +paket-files/ + +# FAKE - F# Make +.fake/ + +# JetBrains Rider +.idea/ +*.sln.iml + +# CodeRush +.cr/ + +# Python Tools for Visual Studio (PTVS) +__pycache__/ +*.pyc + +# Cake - Uncomment if you are using it +# tools/** +# !tools/packages.config + +# Tabs Studio +*.tss + +# Telerik's JustMock configuration file +*.jmconfig + +# BizTalk build output +*.btp.cs +*.btm.cs +*.odx.cs +*.xsd.cs + +# AJIOB_Exclude +Output +Build* diff --git a/code/c++/cxx-gamepad-app/GamepadConfig.cpp b/code/c++/cxx-gamepad-app/GamepadConfig.cpp new file mode 100644 index 0000000..d952bb5 --- /dev/null +++ b/code/c++/cxx-gamepad-app/GamepadConfig.cpp @@ -0,0 +1,52 @@ +#include "GamepadConfig.h" + +GamepadConfig::GamepadConfig() : + buttonsBinding { + GamepadCommands::none, /* 0 */ + GamepadCommands::distanceSensorRefresh, /* 1 - A */ + GamepadCommands::exit, /* 2 - B */ + GamepadCommands::lineSensorRefresh, /* 3 - X */ + GamepadCommands::none, /* 4 - Y */ + GamepadCommands::none, /* 5 */ + GamepadCommands::none, /* 6 */ + GamepadCommands::none, /* 7 */ + GamepadCommands::none, /* 8 */ + GamepadCommands::none, /* 9 */ + GamepadCommands::distanceSensorRefresh, /* 10 - 3 on defender */ + GamepadCommands::lineSensorRefresh, /* 11 - 2 on defender */ + GamepadCommands::exit, /* 12 - 4 on defender */ + GamepadCommands::none, /* 13 - 1 on defender */ + }, + sticksBinding { + GamepadCommands::moveRobotX, /* 0 - left X */ + GamepadCommands::moveRobotY, /* 1 - left Y */ + GamepadCommands::moveCameraX, /* 2 - right X */ + GamepadCommands::moveCameraY, /* 3 - right Y */ + GamepadCommands::none, /* 4 */ + GamepadCommands::none, /* 5 */ + } +{ +} + +GamepadCommands GamepadConfig::button(int index) const +{ + return ((index >= 0) && (index < maxButtons)) ? buttonsBinding[index] : GamepadCommands::none; +} + +GamepadCommands GamepadConfig::stick(int index) const +{ + return ((index >= 0) && (index < maxSticks)) ? sticksBinding[index] : GamepadCommands::none; +} + +int GamepadConfig::getStickId(GamepadCommands command) const +{ + for (auto i = 0; i < maxSticks; ++i) + { + if (sticksBinding[i] == command) + { + return i; + } + } + + return badIndex; +} diff --git a/code/c++/cxx-gamepad-app/GamepadConfig.h b/code/c++/cxx-gamepad-app/GamepadConfig.h new file mode 100644 index 0000000..997ae4e --- /dev/null +++ b/code/c++/cxx-gamepad-app/GamepadConfig.h @@ -0,0 +1,50 @@ +#ifndef _GAMEPAD_CONFIG_H_ +#define _GAMEPAD_CONFIG_H_ + +enum class GamepadCommands +{ + none, + + /* App management */ + exit, + + /* Movement */ + moveRobotX, + moveRobotY, + moveCameraX, + moveCameraY, + + /* Sensors */ + lineSensorRefresh, + distanceSensorRefresh, +}; + +class GamepadConfig +{ + static const short int maxButtons = 14; + static const short int maxSticks = 6; + + GamepadCommands buttonsBinding[maxButtons]; + GamepadCommands sticksBinding[maxSticks]; +public: + GamepadConfig(); + + /** + * @return Button mapping command or @GamepadCommands::none, if not exists + */ + GamepadCommands button(int index) const; + /** + * @return Button mapping command or @GamepadCommands::none, if not exists + */ + GamepadCommands stick(int index) const; + + /** + * Convert command to stick id that binds with that command + * @return Binding key index or @badIndex, if not exists + */ + int getStickId(GamepadCommands command) const; + + static const int badIndex = -1; +}; + +#endif /* _GAMEPAD_CONFIG_H_ */ diff --git a/code/c++/cxx-gamepad-app/GamepadManager.cpp b/code/c++/cxx-gamepad-app/GamepadManager.cpp new file mode 100644 index 0000000..07ebc12 --- /dev/null +++ b/code/c++/cxx-gamepad-app/GamepadManager.cpp @@ -0,0 +1,115 @@ +#include +#include "TrackPlatform_Manager.h" +#include "gamepad/Gamepad.h" +#include "gamepad_callbacks.h" + +#include "GamepadManager.h" + +const double GamepadManager::forwardMaxSpeed = 0.6; +const double GamepadManager::rotateMaxSpeed = 0.6; + +GamepadManager::GamepadManager(TrackPlatform_Manager* trackPlatform) : GamepadManager(trackPlatform, new SensorsViewer, true) +{ +} + +GamepadManager::GamepadManager(TrackPlatform_Manager* trackPlatform, SensorsViewer* sensorsViewer) : GamepadManager(trackPlatform, sensorsViewer, false) +{ +} + +GamepadManager::GamepadManager(TrackPlatform_Manager* trackPlatform, SensorsViewer* sensorsViewer, bool isFreeViewer) : trackPlatform(trackPlatform), sensorsViewer(sensorsViewer), runnedThread(nullptr), isFreeViewer(isFreeViewer) +{ + Gamepad_buttonDownFunc(onButtonDown, (void *)this); + Gamepad_buttonUpFunc(onButtonUp, (void *)this); + Gamepad_axisMoveFunc(onAxisMoved, (void *)this); + Gamepad_init(); +} + +GamepadManager::~GamepadManager() +{ + stop(); + join(); + if (runnedThread) + { + delete runnedThread; + } + Gamepad_shutdown(); + if (sensorsViewer && isFreeViewer) + { + delete sensorsViewer; + } +} + +void GamepadManager::run() +{ + isRequireToRun = true; + + runnedThread = runnedThread ? runnedThread : new std::thread([this]() + { + while (this->isRequireToRun) + { + Gamepad_detectDevices(); + Gamepad_processEvents(); + } + }); +} + +void GamepadManager::stop() +{ + isRequireToRun = false; +} + +void GamepadManager::join() +{ + if (!runnedThread) + { + return; + } + + if (runnedThread->joinable()) + { + runnedThread->join(); + } + delete runnedThread; + runnedThread = nullptr; +} + +const GamepadConfig& GamepadManager::getConfig() const +{ + return config; +} + +TrackPlatform_Manager* GamepadManager::getTrackPlatformManager() const +{ + return trackPlatform; +} + +SensorsViewer* GamepadManager::getSensorsViewer() const +{ + return sensorsViewer; +} + +bool GamepadManager::convertAndSendMovement(double xValue, double yValue) +{ + if (!trackPlatform || (xValue > 1) || (xValue < -1) || (yValue > 1) || (yValue < -1)) + { + return false; + } + + double leftTrackSpeed = yValue * forwardMaxSpeed + xValue * rotateMaxSpeed; + double rightTrackSpeed = yValue * forwardMaxSpeed - xValue * rotateMaxSpeed; + + //calibrating values + auto catibrator = [](double current, double min, double max) -> double + { + return ((current > max) ? max : ((current < min) ? min : current)); + }; + leftTrackSpeed = catibrator(leftTrackSpeed, -1, 1); + rightTrackSpeed = catibrator(rightTrackSpeed, -1, 1); + + if (!trackPlatform->setAllTrackForwardSpeed(leftTrackSpeed, rightTrackSpeed)) + { + return false; + } + + return true; +} diff --git a/code/c++/cxx-gamepad-app/GamepadManager.h b/code/c++/cxx-gamepad-app/GamepadManager.h new file mode 100644 index 0000000..5dadcde --- /dev/null +++ b/code/c++/cxx-gamepad-app/GamepadManager.h @@ -0,0 +1,78 @@ +#ifndef _GAMEPAD_MANAGER_H_ +#define _GAMEPAD_MANAGER_H_ + +#include +#include +#include "TrackPlatform_Manager.h" +#include "GamepadConfig.h" +#include "SensorsViewer.h" + +class GamepadManager +{ + TrackPlatform_Manager* trackPlatform = nullptr; + SensorsViewer* sensorsViewer = nullptr; + /** + * @brief mutex is locked when handler thread is running, else not locked + */ + std::atomic_bool isRequireToRun = {false}; + /** + * @brief Handler thread pointer + */ + std::thread * runnedThread = nullptr; + + GamepadConfig config; + + /** + * @brief Max speed to move forward. Sould be in interval [0; 1] + */ + static const double forwardMaxSpeed; + /** + * @brief Max speed to rotate. Sould be in interval [0; 1] + */ + static const double rotateMaxSpeed; + + bool isFreeViewer = false; + + GamepadManager(TrackPlatform_Manager* trackPlatform, SensorsViewer* sensorsViewer, bool isFreeViewer); + +public: + GamepadManager(TrackPlatform_Manager* trackPlatform); + GamepadManager(TrackPlatform_Manager* trackPlatform, SensorsViewer* sensorsViewer); + ~GamepadManager(); + /** + * @brief Run gamepad handler thread + */ + void run(); + /** + * @brief Stop gamepad handler thread + */ + void stop(); + /** + * @brief Wait while handler thread not stopped + */ + void join(); + /** + * @brief Get current gamepad config + * @return Current gamepad configuration + */ + const GamepadConfig& getConfig() const; + /** + * @brief Get current trackPlatform manager + * @return Current trackPlatform manager + */ + TrackPlatform_Manager* getTrackPlatformManager() const; + /** + * @brief Get current SensorsViewer + * @return Current SensorsViewer + */ + SensorsViewer* getSensorsViewer() const; + /** + * @brief Convert gamepad x and y values to movement speed of tracks and send it to device + * @param xValue X axis value (must be in interval [-1; 1]) + * @param yValue Y axis value (must be in interval [-1; 1]) + * @return true, if all were successed, else false + */ + bool convertAndSendMovement(double xValue, double yValue); +}; + +#endif /* _GAMEPAD_MANAGER_H_ */ diff --git a/code/c++/cxx-gamepad-app/cxx-gamepad-app.sln b/code/c++/cxx-gamepad-app/cxx-gamepad-app.sln new file mode 100644 index 0000000..357ea26 --- /dev/null +++ b/code/c++/cxx-gamepad-app/cxx-gamepad-app.sln @@ -0,0 +1,63 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Visual Studio 15 +VisualStudioVersion = 15.0.26430.16 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "cxx-gamepad-app", "cxx-gamepad-app.vcxproj", "{F92E7862-33C4-48B8-A055-3EE00352161F}" + ProjectSection(ProjectDependencies) = postProject + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA} = {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA} + {32D3778A-E59E-4DBC-8D86-BD23B708CA12} = {32D3778A-E59E-4DBC-8D86-BD23B708CA12} + {4579D2EA-39EB-4766-9EB6-497500F379D6} = {4579D2EA-39EB-4766-9EB6-497500F379D6} + EndProjectSection +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "cxx-api", "..\cxx-api\cxx-api.vcxproj", "{32D3778A-E59E-4DBC-8D86-BD23B708CA12}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "libstem_gamepad", "gamepad_support\msvc\libstem_gamepad\libstem_gamepad.vcxproj", "{4579D2EA-39EB-4766-9EB6-497500F379D6}" +EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "cxx-library", "..\cxx-library\cxx-library.vcxproj", "{57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|x64 = Debug|x64 + Debug|x86 = Debug|x86 + Release|x64 = Release|x64 + Release|x86 = Release|x86 + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {F92E7862-33C4-48B8-A055-3EE00352161F}.Debug|x64.ActiveCfg = Debug|x64 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Debug|x64.Build.0 = Debug|x64 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Debug|x86.ActiveCfg = Debug|Win32 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Debug|x86.Build.0 = Debug|Win32 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Release|x64.ActiveCfg = Release|x64 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Release|x64.Build.0 = Release|x64 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Release|x86.ActiveCfg = Release|Win32 + {F92E7862-33C4-48B8-A055-3EE00352161F}.Release|x86.Build.0 = Release|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x64.ActiveCfg = Debug|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x64.Build.0 = Debug|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x86.ActiveCfg = Debug|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Debug|x86.Build.0 = Debug|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x64.ActiveCfg = Release|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x64.Build.0 = Release|x64 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x86.ActiveCfg = Release|Win32 + {32D3778A-E59E-4DBC-8D86-BD23B708CA12}.Release|x86.Build.0 = Release|Win32 + {4579D2EA-39EB-4766-9EB6-497500F379D6}.Debug|x64.ActiveCfg = Debug|x64 + {4579D2EA-39EB-4766-9EB6-497500F379D6}.Debug|x64.Build.0 = Debug|x64 + {4579D2EA-39EB-4766-9EB6-497500F379D6}.Debug|x86.ActiveCfg = Debug|Win32 + {4579D2EA-39EB-4766-9EB6-497500F379D6}.Debug|x86.Build.0 = Debug|Win32 + {4579D2EA-39EB-4766-9EB6-497500F379D6}.Release|x64.ActiveCfg = Release|x64 + {4579D2EA-39EB-4766-9EB6-497500F379D6}.Release|x64.Build.0 = Release|x64 + {4579D2EA-39EB-4766-9EB6-497500F379D6}.Release|x86.ActiveCfg = Release|Win32 + {4579D2EA-39EB-4766-9EB6-497500F379D6}.Release|x86.Build.0 = Release|Win32 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Debug|x64.ActiveCfg = Debug|x64 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Debug|x64.Build.0 = Debug|x64 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Debug|x86.ActiveCfg = Debug|Win32 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Debug|x86.Build.0 = Debug|Win32 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Release|x64.ActiveCfg = Release|x64 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Release|x64.Build.0 = Release|x64 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Release|x86.ActiveCfg = Release|Win32 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA}.Release|x86.Build.0 = Release|Win32 + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/code/c++/cxx-gamepad-app/cxx-gamepad-app.vcxproj b/code/c++/cxx-gamepad-app/cxx-gamepad-app.vcxproj new file mode 100644 index 0000000..cb8c578 --- /dev/null +++ b/code/c++/cxx-gamepad-app/cxx-gamepad-app.vcxproj @@ -0,0 +1,174 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + 15.0 + {F92E7862-33C4-48B8-A055-3EE00352161F} + Win32Proj + cxxapp + + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + Application + true + v141 + Unicode + + + Application + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + + + true + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + + + false + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + + + false + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + + + + + + Level3 + Disabled + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + $(SolutionDir)..\cxx-library;$(SolutionDir)..\cxx-api;$(SolutionDir)..\cxx-api\serial_support\include;$(SolutionDir)gamepad_support\source + + + Console + cxx-library.lib;cxx-api.lib;libstem_gamepad.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + $(OutDir);$(SolutionDir)$(Configuration)\ + + + + + + + Level3 + Disabled + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + $(SolutionDir)..\cxx-library;$(SolutionDir)..\cxx-api;$(SolutionDir)..\cxx-api\serial_support\include;$(SolutionDir)gamepad_support\source + + + Console + cxx-library.lib;cxx-api.lib;libstem_gamepad.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + $(OutDir);$(SolutionDir)$(Platform)\$(Configuration)\ + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + $(SolutionDir)..\cxx-library;$(SolutionDir)..\cxx-api;$(SolutionDir)..\cxx-api\serial_support\include;$(SolutionDir)gamepad_support\source + + + Console + true + true + cxx-library.lib;cxx-api.lib;libstem_gamepad.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + $(OutDir);$(SolutionDir)$(Configuration)\ + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + $(SolutionDir)..\cxx-library;$(SolutionDir)..\cxx-api;$(SolutionDir)..\cxx-api\serial_support\include;$(SolutionDir)gamepad_support\source + + + Console + true + true + cxx-library.lib;cxx-api.lib;libstem_gamepad.lib;kernel32.lib;user32.lib;gdi32.lib;winspool.lib;comdlg32.lib;advapi32.lib;shell32.lib;ole32.lib;oleaut32.lib;uuid.lib;odbc32.lib;odbccp32.lib;%(AdditionalDependencies) + $(OutDir);$(SolutionDir)$(Platform)\$(Configuration)\ + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/code/c++/trackPlatform/trackPlatform/trackPlatform.vcxproj.filters b/code/c++/cxx-gamepad-app/cxx-gamepad-app.vcxproj.filters similarity index 53% rename from code/c++/trackPlatform/trackPlatform/trackPlatform.vcxproj.filters rename to code/c++/cxx-gamepad-app/cxx-gamepad-app.vcxproj.filters index 4829d1d..be33393 100644 --- a/code/c++/trackPlatform/trackPlatform/trackPlatform.vcxproj.filters +++ b/code/c++/cxx-gamepad-app/cxx-gamepad-app.vcxproj.filters @@ -1,42 +1,42 @@ - - - - - {4FC737F1-C7A5-4376-A066-2A32D752A2FF} - cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx - - - {93995380-89BD-4b04-88EB-625FBE52EBFB} - h;hh;hpp;hxx;hm;inl;inc;xsd - - - {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} - rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms - - - - - Файлы исходного кода - - - Файлы исходного кода - - - Файлы исходного кода - - - Файлы ресурсов - - - - - Заголовочные файлы - - - Заголовочные файлы - - - Заголовочные файлы - - + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + + + Source Files + + + Source Files + + + Source Files + + + Source Files + + + + + Header Files + + + Header Files + + + Header Files + + \ No newline at end of file diff --git a/code/c++/cxx-gamepad-app/gamepad_callbacks.cpp b/code/c++/cxx-gamepad-app/gamepad_callbacks.cpp new file mode 100644 index 0000000..5f551ed --- /dev/null +++ b/code/c++/cxx-gamepad-app/gamepad_callbacks.cpp @@ -0,0 +1,54 @@ +#include "GamepadManager.h" +#include "gamepad_callbacks.h" + +void onButtonDown(Gamepad_device* device, unsigned buttonID, double timestamp, void* context) +{ + GamepadManager* manager = static_cast(context); + switch (manager->getConfig().button(buttonID)) + { + case GamepadCommands::exit: { + manager->stop(); + break; + } + case GamepadCommands::lineSensorRefresh: { + auto values = manager->getTrackPlatformManager()->sensorLineGetAllValues(); + manager->getSensorsViewer()->setData(values, LINE_SENSORS); + manager->getSensorsViewer()->show(); + break; + } + case GamepadCommands::distanceSensorRefresh: { + auto values = manager->getTrackPlatformManager()->sensorDistanceGetAllValues(); + manager->getSensorsViewer()->setData(values, DISTANCE_SENSORS); + manager->getSensorsViewer()->show(); + break; + } + default: break; + } +} + +void onButtonUp(Gamepad_device* device, unsigned buttonID, double timestamp, void* context) +{ +} + +void onAxisMoved(Gamepad_device* device, unsigned axisID, float value, float lastValue, double timestamp, void* context) +{ + GamepadManager* manager = static_cast(context); + switch (manager->getConfig().stick(axisID)) + { + case GamepadCommands::moveRobotX: + case GamepadCommands::moveRobotY: { + auto config = manager->getConfig(); + manager->convertAndSendMovement(device->axisStates[config.getStickId(GamepadCommands::moveRobotX)], device->axisStates[config.getStickId(GamepadCommands::moveRobotY)]); + break; + } + case GamepadCommands::moveCameraX: { + manager->getTrackPlatformManager()->servoSetHorizontalAngle(static_cast((-value + 1) * 90)); + break; + } + case GamepadCommands::moveCameraY: { + manager->getTrackPlatformManager()->servoSetVerticalAngle(static_cast((value + 1) * 90)); + break; + } + default: break; + } +} diff --git a/code/c++/cxx-gamepad-app/gamepad_callbacks.h b/code/c++/cxx-gamepad-app/gamepad_callbacks.h new file mode 100644 index 0000000..ccd09fb --- /dev/null +++ b/code/c++/cxx-gamepad-app/gamepad_callbacks.h @@ -0,0 +1,22 @@ +#ifndef _GAMEPAD_CALLBACKS_H_ +#define _GAMEPAD_CALLBACKS_H_ + +#include "gamepad/Gamepad.h" + +/** +* @brief Checks changes of buttons +* @param context Pointer to @GamepadManager variable. Used to call events +*/ +void onButtonDown(struct Gamepad_device * device, unsigned int buttonID, double timestamp, void * context); +/** + * @brief Checks is exit key was released + * @param context Pointer to @GamepadManager variable. Sets to true, if exit key changed its pressing [pressed -> released], else sets false + */ +void onButtonUp(struct Gamepad_device * device, unsigned int buttonID, double timestamp, void * context); +/** +* @brief Checks changes of axes positions +* @param context Pointer to @GamepadManager variable. Used to call events +*/ +void onAxisMoved(struct Gamepad_device * device, unsigned int axisID, float value, float lastValue, double timestamp, void * context); + +#endif /* _GAMEPAD_CALLBACKS_H_ */ diff --git a/code/c++/cxx-gamepad-app/gamepad_support b/code/c++/cxx-gamepad-app/gamepad_support new file mode 160000 index 0000000..a5fac63 --- /dev/null +++ b/code/c++/cxx-gamepad-app/gamepad_support @@ -0,0 +1 @@ +Subproject commit a5fac6306214cd1b0d56680b2c2d947ff215c61d diff --git a/code/c++/cxx-gamepad-app/main.cpp b/code/c++/cxx-gamepad-app/main.cpp new file mode 100644 index 0000000..709fed7 --- /dev/null +++ b/code/c++/cxx-gamepad-app/main.cpp @@ -0,0 +1,46 @@ +#include +#include + +#include "GamepadManager.h" +#include "ConnectionModes.h" +#include "TrackPlatform_Manager.h" +#include "Logger.h" +#include "ConsolePlatformConnector.h" + +int main(int argc, char* argv[]) +{ + TrackPlatform_Manager* trackPlatform = nullptr; + Logger::log("App is running"); + + int retCode = 0; + + try + { + ConsolePlatformConnector platformConnector; + trackPlatform = platformConnector.connect(); + if (!trackPlatform) + { + return 2; + } + + std::cout << "Connected" << std::endl; + + GamepadManager manager(trackPlatform); + manager.run(); + manager.join(); + } + catch (...) + { + std::cout << "Exception was catched" << std::endl; + Logger::log("Exception was catched"); + retCode = 1; + } + + if (trackPlatform) + { + delete trackPlatform; + } + Logger::log("App is closed"); + return retCode; +} + diff --git a/code/c++/cxx-gamepad-app/makefile b/code/c++/cxx-gamepad-app/makefile new file mode 100644 index 0000000..d2bfeea --- /dev/null +++ b/code/c++/cxx-gamepad-app/makefile @@ -0,0 +1,191 @@ +#Make file to compile source code for track platform cxx api library + +#Project Name +PROJECT_NAME = track-platform_cxx-gamepad-app +#Build option +BUILD ?= BUILD_STATIC +#ANSI Colos +ANSI_COLOR_RED = \e[31m +ANSI_COLOR_GREEN = \e[32m +ANSI_COLOR_YELLOW = \e[33m +ANSI_COLOR_BLUE = \e[34m +ANSI_COLOR_MAGENTA = \e[35m +ANSI_COLOR_CYAN = \e[36m +ANSI_COLOR_RESET = \e[37m +################################Compiller flags############################################################### +#Opitmization Level +OPT_LEVEL = -O0 +#Warning options +WARNINGS = -Wall -Wpedantic #-Werror +# WARNINGS += -fsyntax-only # for syntax checking only, without comlipation +WARNINGS_WITHOUT = +#User Compiller flags +USER_FLAGS ?= +############################################################################################################## +# OS and platform redefinition +OS = $(shell uname -s) +OS_PLATFORM = $(shell uname -m) + +ifeq ($(OS), Linux) +OS = linux +endif +ifeq ($(OS_PLATFORM), x86_64) +OS_PLATFORM = 64 +endif +ifeq ($(OS_PLATFORM), i386) +OS_PLATFORM = 32 +endif + +#Build patch +BUILD_PATH = Output/$(OS) +OBJ_PATH = $(BUILD_PATH)/obj + +#Compiller flags +CFLAGS = $(OPT_LEVEL) +CFLAGS += -g0 +CFLAGS += $(WARNINGS) +CFLAGS += -I. +CFLAGS += $(USER_FLAGS) +CFLAGS += -std=c++11 +CFLAGS += -D$(BUILD) +# ifeq ($(BUILD), BUILD_STATIC) +# CFLAGS += -D$(BUILD_STATIC) +# endif + +CFLAGS += $(INCLUDES) +############################################################################################################## +#Code file path +OTHER_PATH = . +OTHER_SOURCE_PATH = $(OTHER_PATH) +OTHER_INCLUDE_PATH = $(OTHER_PATH) + +#library path +API_PATH = ../cxx-api +API_INCLUDE_PATH = $(API_PATH) +API_BUILD_PATH = $(API_PATH)/$(BUILD_PATH) +LIBRARY_PATH = ../cxx-library +LIBRARY_INCLUDE_PATH = $(LIBRARY_PATH) +LIBRARY_BUILD_PATH = $(LIBRARY_PATH)/$(BUILD_PATH) + +ifeq ($(BUILD), BUILD_STATIC) +API_NAME = track-platform_cxx-api.a +LIBRARY_NAME = track-platform_cxx-library.a +else +ifeq ($(BUILD), BUILD_DYNAMIC) +API_NAME = track-platform_cxx-api.so +LIBRARY_NAME = track-platform_cxx-library.so +endif +endif + +API_FULL_PATH = $(API_BUILD_PATH)/$(API_NAME) +LIBRARY_FULL_PATH = $(LIBRARY_BUILD_PATH)/$(LIBRARY_NAME) + +# gamepad library path +GAMEPAD_LIB_PATH = gamepad_support +GAMEPAD_LIB_INCLUDE_PATH = $(GAMEPAD_LIB_PATH)/build/include +GAMEPAD_LIB_BUILD_PATH = $(GAMEPAD_LIB_PATH)/build/library/release-$(OS)$(OS_PLATFORM) +GAMEPAD_LIB_NAME = libstem_gamepad.a +GAMEPAD_LIB_FULL_PATH = $(GAMEPAD_LIB_BUILD_PATH)/$(GAMEPAD_LIB_NAME) + +# Linker scrpit file +LFLAGS = -lpthread + +#Source file path + +SOURCES = +# Other code (non grouped) +SOURCES += $(OTHER_SOURCE_PATH)/gamepad_callbacks.cpp +SOURCES += $(OTHER_SOURCE_PATH)/GamepadConfig.cpp +SOURCES += $(OTHER_SOURCE_PATH)/GamepadManager.cpp +SOURCES += $(OTHER_SOURCE_PATH)/main.cpp + +#Include file path +INCLUDES = +INCLUDES += -I$(API_INCLUDE_PATH) +INCLUDES += -I$(LIBRARY_INCLUDE_PATH) +INCLUDES += -I$(GAMEPAD_LIB_INCLUDE_PATH) +# INCLUDES += -I$(OTHER_INCLUDE_PATH) + +############################################################################################################## +BUILD_PRINT = $(ANSI_COLOR_GREEN) Building:$(ANSI_COLOR_RESET) $@ +############################################################################################################## +#Output files +BIN = $(BUILD_PATH)/$(PROJECT_NAME) + +OBJECTS = $(addprefix $(OBJ_PATH)/, $(addsuffix .o, $(basename $(SOURCES)))) + +STATIC_LIB: $(OBJECTS) api library gamepad + @$(CXX) -o $(BIN) $(OBJECTS) $(API_FULL_PATH) $(LIBRARY_FULL_PATH) $(GAMEPAD_LIB_FULL_PATH) $(LFLAGS) + @echo -e "$(BUILD_PRINT)" + +DYNAMIC_LIB: $(OBJECTS) api library gamepad + $(error Dynamic library is not supported yet) + # @$(CXX) -shared -o $(BIN) $(OBJECTS) + @echo -e "$(BUILD_PRINT)" + +$(OBJ_PATH)/%.o: %.cc + @mkdir -p $(dir $@) + @$(CXX) -c $(CFLAGS) $< -o $@ + @echo -e "$(BUILD_PRINT)" + +$(OBJ_PATH)/%.o: %.cpp + @mkdir -p $(dir $@) + @$(CXX) -c $(CFLAGS) $< -o $@ + @echo -e "$(BUILD_PRINT)" + +#Makefile parameters +.DEFAULT_GOAL := all + +all: preprocessor build + +ifeq ($(BUILD), BUILD_STATIC) +build: STATIC_LIB + +else +ifeq ($(BUILD), BUILD_DYNAMIC) +build: DYNAMIC_LIB + +else +build: + @echo "That BUILD variable is not supported. Use `make help` to see supported variants of build variable" +endif +endif + +dynamic: + $(MAKE) BUILD=BUILD_DYNAMIC + +static: + $(MAKE) BUILD=BUILD_STATIC + +api: + $(MAKE) -C $(API_PATH) BUILD=$(BUILD) + +library: + $(MAKE) -C $(LIBRARY_PATH) BUILD=$(BUILD) + +gamepad_include: + $(MAKE) -C $(GAMEPAD_LIB_PATH) include + +gamepad: + $(MAKE) -C $(GAMEPAD_LIB_PATH) library + +preprocessor: gamepad_include + +clean: + @rm -rf $(BUILD_PATH) + $(MAKE) -C $(API_PATH) $@ + $(MAKE) -C $(LIBRARY_PATH) $@ + $(MAKE) -C $(GAMEPAD_LIB_PATH) $@ + +run: + @$(BIN) + +set_def_color: + @echo -e "$(ANSI_COLOR_RESET)" + +help: + @echo "$(NEW_LINE)" + @echo "\tall : Builds static or dynamic library (static by default)" + @echo "\t\tIf you want to build static library(.a file), write `make` or `make static` or `make BUILD=BUILD_DYNAMIC`" + @echo "\t\tIf you want to build dynamic library(.so file), write `make dynamic` or `make BUILD=BUILD_DYNAMIC`" + @echo "$(NEW_LINE)" diff --git a/code/c++/cxx-library/ConsolePlatformConnector.cpp b/code/c++/cxx-library/ConsolePlatformConnector.cpp new file mode 100644 index 0000000..6812558 --- /dev/null +++ b/code/c++/cxx-library/ConsolePlatformConnector.cpp @@ -0,0 +1,63 @@ +#include "ConsolePlatformConnector.h" + +TrackPlatform_Manager* ConsolePlatformConnector::connect() +{ + int answer = 0; + + std::cout << "Connect by:" << std::endl; + std::cout << "\t1) USB" << std::endl; + std::cout << "\t2) Bluetooth" << std::endl; + std::cout << "\t3) WiFi" << std::endl; + std::cin >> answer; + + switch (answer) + { + case 1: + case 2: + return connectBySerial(); + case 3: + return connectByTcpIp(); + default: + std::cout << "No connector at number " << answer << std::endl; + return nullptr; + } +} + +TrackPlatform_Manager* ConsolePlatformConnector::connectBySerial() +{ + std::string rtx = "COM13"; + uint32_t baudrate = 9600U; + + std::cout << "port" << std::endl; + std::cin >> rtx; + std::cout << "baudrate" << std::endl; + std::cin >> baudrate; + + std::cout << "rx = " << rtx << " tx = " << rtx << " baudrate = " << baudrate << std::endl; + + CommunicationInfoStruct info; + + info.SerialInfo.rxPort = rtx; + info.SerialInfo.txPort = rtx; + info.SerialInfo.baudrate = baudrate; + return new TrackPlatform_Manager(bluetooth, info); +} + +TrackPlatform_Manager* ConsolePlatformConnector::connectByTcpIp() +{ + std::string ip = "192.168.4.1"; + uint16_t port = 333; + + std::cout << "server ip" << std::endl; + std::cin >> ip; + std::cout << "port" << std::endl; + std::cin >> port; + + std::cout << "ip = " << ip << " port = " << port << std::endl; + + CommunicationInfoStruct info; + + info.TCPIPInfo.ip = ip; + info.TCPIPInfo.port = port; + return new TrackPlatform_Manager(WiFi, info); +} diff --git a/code/c++/cxx-library/ConsolePlatformConnector.h b/code/c++/cxx-library/ConsolePlatformConnector.h new file mode 100644 index 0000000..b64c30e --- /dev/null +++ b/code/c++/cxx-library/ConsolePlatformConnector.h @@ -0,0 +1,12 @@ +#pragma once +#include "TrackPlatform_Manager.h" + +class ConsolePlatformConnector +{ +public: + TrackPlatform_Manager* connect(); + +private: + TrackPlatform_Manager* connectBySerial(); + TrackPlatform_Manager* connectByTcpIp(); +}; diff --git a/code/c++/cxx-library/SensorsViewer.cpp b/code/c++/cxx-library/SensorsViewer.cpp new file mode 100644 index 0000000..f50d5b6 --- /dev/null +++ b/code/c++/cxx-library/SensorsViewer.cpp @@ -0,0 +1,78 @@ +#include +#include +#include + +#include "SensorsViewer.h" + +void SensorsViewer::showDistanceInfo() +{ + if (!distanceSensors.empty()) { + //configuration + const short prefixSymbolNum = 1; + const short betweenSymbolNum = 1; + const short oneNumMinSize = 4; + const char delimiter = ' '; + std::ostream& os = std::cout; + + const short isParityOn = static_cast(distanceSensors.size() % 2); + const short stringNums = static_cast(distanceSensors.size() / 2); + os << "Distance sensors:" << std::endl; + const auto printChar = [](std::ostream& s, char c, short num) -> std::ostream& + { + while (num > 0) + { + s << c; + num--; + } + return s; + }; + if (isParityOn) + { + printChar(os, delimiter, prefixSymbolNum + stringNums + oneNumMinSize / 2) << + distanceSensors[stringNums] << std::endl; + } + for (short i = 0; i < stringNums; ++i) + { + printChar(os, delimiter, prefixSymbolNum + stringNums - i - 1) << + std::setw(oneNumMinSize) << distanceSensors[stringNums - i - 1]; + printChar(os, delimiter, i * 2 + betweenSymbolNum) << std::setw(oneNumMinSize) << + distanceSensors[stringNums + i + isParityOn] << std::endl; + } + } +} + +void SensorsViewer::showLineInfo() +{ + if (!lineSensors.empty()) { + std::cout << "Line sensors:" << std::endl; + std::cout << "|"; + for (unsigned int i = 0; i < lineSensors.size(); i++) { + std::cout << (lineSensors[i] ? "@@@" : " "); + } + std::cout << "|" << std::endl; + } +} + +void SensorsViewer::setData(const std::vector& d, SensorType t) { + if (t == LINE_SENSORS) { + lineSensors = d; + } + else { + distanceSensors = d; + } +} + +void SensorsViewer::show() { + if (system("clear")) system("cls"); + showDistanceInfo(); + showLineInfo(); +} +void SensorsViewer::show(SensorType type) { + if (type == LINE_SENSORS) { + showLineInfo(); + } + else { + if (system("clear")) system("cls"); + showDistanceInfo(); + } +} diff --git a/code/c++/cxx-library/SensorsViewer.h b/code/c++/cxx-library/SensorsViewer.h new file mode 100644 index 0000000..8e47efc --- /dev/null +++ b/code/c++/cxx-library/SensorsViewer.h @@ -0,0 +1,21 @@ +#pragma once + +#include + +enum SensorType { + LINE_SENSORS, DISTANCE_SENSORS +}; + +class SensorsViewer { +protected: + std::vector lineSensors; + std::vector distanceSensors; + + virtual void showDistanceInfo(); + virtual void showLineInfo(); + +public: + void setData(const std::vector& d, SensorType t); + void show(); + void show(SensorType type); +}; diff --git a/code/c++/cxx-library/cxx-library.vcxproj b/code/c++/cxx-library/cxx-library.vcxproj new file mode 100644 index 0000000..f68c737 --- /dev/null +++ b/code/c++/cxx-library/cxx-library.vcxproj @@ -0,0 +1,160 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + + + + + + + + + 15.0 + {57E5EF7C-AF4E-45BA-A941-33A8C2D08DEA} + Win32Proj + cxxlibrary + 8.1 + + + + StaticLibrary + true + v141 + Unicode + + + StaticLibrary + false + v141 + true + Unicode + + + StaticLibrary + true + v141 + Unicode + + + StaticLibrary + false + v141 + true + Unicode + + + + + + + + + + + + + + + + + + + + + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + $(ProjectDir)..\cxx-api\;$(IncludePath) + + + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + $(ProjectDir)..\cxx-api\;$(IncludePath) + + + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + $(ProjectDir)..\cxx-api\;$(IncludePath) + + + $(SolutionDir)Output\$(Configuration)-$(Platform)\ + $(SolutionDir)Build\$(ProjectName)\$(Configuration)-$(Platform)\ + $(ProjectDir)..\cxx-api\;$(IncludePath) + + + + + + Level3 + Disabled + _DEBUG;_LIB;%(PreprocessorDefinitions) + + + Windows + + + + + + + Level3 + Disabled + WIN32;_DEBUG;_LIB;%(PreprocessorDefinitions) + + + Windows + + + + + Level3 + + + MaxSpeed + true + true + WIN32;NDEBUG;_LIB;%(PreprocessorDefinitions) + + + Windows + true + true + + + + + Level3 + + + MaxSpeed + true + true + NDEBUG;_LIB;%(PreprocessorDefinitions) + + + Windows + true + true + + + + + + \ No newline at end of file diff --git a/code/c++/cxx-library/cxx-library.vcxproj.filters b/code/c++/cxx-library/cxx-library.vcxproj.filters new file mode 100644 index 0000000..2d95522 --- /dev/null +++ b/code/c++/cxx-library/cxx-library.vcxproj.filters @@ -0,0 +1,33 @@ + + + + + {4FC737F1-C7A5-4376-A066-2A32D752A2FF} + cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx + + + {93995380-89BD-4b04-88EB-625FBE52EBFB} + h;hh;hpp;hxx;hm;inl;inc;xsd + + + {67DA6AB6-F800-4c08-8B7A-83BB121AAD01} + rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms + + + + + Source Files + + + Source Files + + + + + Header Files + + + Header Files + + + \ No newline at end of file diff --git a/code/c++/cxx-library/makefile b/code/c++/cxx-library/makefile new file mode 100644 index 0000000..db0cec3 --- /dev/null +++ b/code/c++/cxx-library/makefile @@ -0,0 +1,140 @@ +#Make file to compile source code for track platform cxx api library + +#Project Name +PROJECT_NAME = track-platform_cxx-library +#Build option +BUILD ?= BUILD_STATIC +#ANSI Colos +ANSI_COLOR_RED = \e[31m +ANSI_COLOR_GREEN = \e[32m +ANSI_COLOR_YELLOW = \e[33m +ANSI_COLOR_BLUE = \e[34m +ANSI_COLOR_MAGENTA = \e[35m +ANSI_COLOR_CYAN = \e[36m +ANSI_COLOR_RESET = \e[37m +################################Compiller flags############################################################### +#Opitmization Level +OPT_LEVEL = -O0 +#Warning options +WARNINGS = -Wall -Wpedantic #-Werror +# WARNINGS += -fsyntax-only # for syntax checking only, without comlipation +WARNINGS_WITHOUT = +#User Compiller flags +USER_FLAGS ?= +############################################################################################################## +# OS redefinition +OS = $(shell uname -s) +ifeq ($(OS), Linux) +OS = linux +endif + +#Build patch +BUILD_PATH = Output/$(OS) +OBJ_PATH = $(BUILD_PATH)/obj + +#Compiller flags +CFLAGS = $(OPT_LEVEL) +CFLAGS += -g0 +CFLAGS += $(WARNINGS) +CFLAGS += -I. +CFLAGS += $(USER_FLAGS) +CFLAGS += -std=c++11 +CFLAGS += -D$(BUILD) +# ifeq ($(BUILD), BUILD_STATIC) +# CFLAGS += -D$(BUILD_STATIC) +# endif + +CFLAGS += $(INCLUDES) +############################################################################################################## +#Code file path +OTHER_PATH = . +OTHER_SOURCE_PATH = $(OTHER_PATH) +OTHER_INCLUDE_PATH = $(OTHER_PATH) + +#Linker scrpit file +ARFLAGS = -cvq + +#Source file path + +SOURCES = +# Other code (non grouped) +SOURCES += $(OTHER_SOURCE_PATH)/SensorsViewer.cpp + +#Include file path +INCLUDES = +# INCLUDES += -I$(OTHER_INCLUDE_PATH) + +############################################################################################################## +BUILD_PRINT = $(ANSI_COLOR_GREEN) Building:$(ANSI_COLOR_RESET) $@ +############################################################################################################## +#Output files +STATIC_LIB = $(BUILD_PATH)/$(PROJECT_NAME).a +DYNAMIC_LIB = $(BUILD_PATH)/$(PROJECT_NAME).so + +OBJECTS = $(addprefix $(OBJ_PATH)/, $(addsuffix .o, $(basename $(SOURCES)))) + +$(STATIC_LIB): $(OBJECTS) + @$(AR) $(ARFLAGS) $@ $(OBJECTS) + @echo -e "$(BUILD_PRINT)" + +$(DYNAMIC_LIB): $(OBJECTS) +# $(error Dynamic library is not supported yet) + @$(CXX) -shared -o $@ $(OBJECTS) + @echo -e "$(BUILD_PRINT)" + +$(OBJ_PATH)/%.o: %.cc + @mkdir -p $(dir $@) + +ifeq ($(BUILD), BUILD_DYNAMIC) + @$(CXX) -fPIC -c $(CFLAGS) $< -o $@ +else + @$(CXX) -c $(CFLAGS) $< -o $@ +endif + @echo -e "$(BUILD_PRINT)" + +$(OBJ_PATH)/%.o: %.cpp + @mkdir -p $(dir $@) + +ifeq ($(BUILD), BUILD_DYNAMIC) + @$(CXX) -fPIC -c $(CFLAGS) $< -o $@ +else + @$(CXX) -c $(CFLAGS) $< -o $@ +endif + @echo -e "$(BUILD_PRINT)" + +#Makefile parameters +.DEFAULT_GOAL := all + +all: build + +ifeq ($(BUILD), BUILD_STATIC) +build: $(STATIC_LIB) + +else +ifeq ($(BUILD), BUILD_DYNAMIC) +build: $(DYNAMIC_LIB) + +else +build: + @echo "That BUILD variable is not supported. Use `make help` to see supported variants of build variable" +endif +endif + +dynamic: + $(MAKE) BUILD=BUILD_DYNAMIC + +static: + $(MAKE) BUILD=BUILD_STATIC + +clean: + @rm -rf $(BUILD_PATH) + +set_def_color: + @echo -e "$(ANSI_COLOR_RESET)" + +help: + @echo "$(NEW_LINE)" + @echo "\tall : Builds static or dynamic library (static by default)" + @echo "\t\tIf you want to build static library(.a file), write `make` or `make static` or `make BUILD=BUILD_DYNAMIC`" + @echo "\t\tIf you want to build dynamic library(.so file), write `make dynamic` or `make BUILD=BUILD_DYNAMIC`" + @echo "$(NEW_LINE)" diff --git a/code/c++/trackPlatform/trackPlatform.sln b/code/c++/trackPlatform/trackPlatform.sln deleted file mode 100644 index 04be704..0000000 --- a/code/c++/trackPlatform/trackPlatform.sln +++ /dev/null @@ -1,28 +0,0 @@ - -Microsoft Visual Studio Solution File, Format Version 12.00 -# Visual Studio 15 -VisualStudioVersion = 15.0.26228.9 -MinimumVisualStudioVersion = 10.0.40219.1 -Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "trackPlatform", "trackPlatform\trackPlatform.vcxproj", "{DFA451D9-6F5A-4485-9CAD-27F7E3C32A90}" -EndProject -Global - GlobalSection(SolutionConfigurationPlatforms) = preSolution - Debug|x64 = Debug|x64 - Debug|x86 = Debug|x86 - Release|x64 = Release|x64 - Release|x86 = Release|x86 - EndGlobalSection - GlobalSection(ProjectConfigurationPlatforms) = postSolution - {DFA451D9-6F5A-4485-9CAD-27F7E3C32A90}.Debug|x64.ActiveCfg = Debug|x64 - {DFA451D9-6F5A-4485-9CAD-27F7E3C32A90}.Debug|x64.Build.0 = Debug|x64 - {DFA451D9-6F5A-4485-9CAD-27F7E3C32A90}.Debug|x86.ActiveCfg = Debug|Win32 - {DFA451D9-6F5A-4485-9CAD-27F7E3C32A90}.Debug|x86.Build.0 = Debug|Win32 - {DFA451D9-6F5A-4485-9CAD-27F7E3C32A90}.Release|x64.ActiveCfg = Release|x64 - {DFA451D9-6F5A-4485-9CAD-27F7E3C32A90}.Release|x64.Build.0 = Release|x64 - {DFA451D9-6F5A-4485-9CAD-27F7E3C32A90}.Release|x86.ActiveCfg = Release|Win32 - {DFA451D9-6F5A-4485-9CAD-27F7E3C32A90}.Release|x86.Build.0 = Release|Win32 - EndGlobalSection - GlobalSection(SolutionProperties) = preSolution - HideSolutionNode = FALSE - EndGlobalSection -EndGlobal diff --git a/code/c++/trackPlatform/trackPlatform/ComPort.cpp b/code/c++/trackPlatform/trackPlatform/ComPort.cpp deleted file mode 100644 index 811e8b4..0000000 --- a/code/c++/trackPlatform/trackPlatform/ComPort.cpp +++ /dev/null @@ -1,92 +0,0 @@ -#include "ComPort.h" - - - -ComPort::ComPort() -{ - -} - - -DWORD WINAPI readProc(LPVOID p) { - while (true) { - if (ReadFile(hCom, pbuf, 1, &bytesRead, 0) && bytesRead > 0) { - printf("msg-%s-end %d\n", pbuf, bytesRead); - } - if (bytesRead>0) - { - WriteFile(hCom, pbuf++, 1, &bWritten, NULL); - counter++; - if (counter == 10) { - SetEvent(hEvent); - buf[counter] = '\0'; - counter = 0; - pbuf = buf; - } - } - } -} - - -VOID WINAPI ComPort::writeProc(PVOID* p) { - -} - - -bool ComPort::init(char* portName) { - this->portName = portName; - hCom = CreateFile(strcat("\\\\.\\", portName), GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL); - - if (hCom == INVALID_HANDLE_VALUE) { - printf(" %s\n", portName); - return false; - } - - GetCommState(hCom, &dcb); - dcb.BaudRate = CBR_9600; - dcb.ByteSize = 8; - dcb.Parity = NOPARITY; - dcb.StopBits = ONESTOPBIT; - fSuccess = SetCommState(hCom, &dcb); - - if (!fSuccess) { - printf(" SetCommState !\n"); - return false; - } - printf("%s \n", portName); - GetCommState(hCom, &dcb); - printf(" %s %d\n", portName, dcb.BaudRate); - - return true; -} - -void ComPort::send() { - -} - -string ComPort::read() { - -} - -void ComPort::createReadThread() { - readThread = CreateThread(NULL, 0, readProc,54 - &dwParam, 0, &dwThreadReadId); -} - -void ComPort::createWriteThread() { - writeThread = CreateThread(NULL, 0, writeProc, - &dwParam, 0, &dwThreadWriteId); -} - -void ComPort::initThreads() { - this->createReadThread(); - this->createWriteThread(); -} - -void ComPort::closePort() { - CloseHandle(hCom); -} - -ComPort::~ComPort() -{ -} diff --git a/code/c++/trackPlatform/trackPlatform/ComPort.h b/code/c++/trackPlatform/trackPlatform/ComPort.h deleted file mode 100644 index 1599046..0000000 --- a/code/c++/trackPlatform/trackPlatform/ComPort.h +++ /dev/null @@ -1,33 +0,0 @@ -#pragma once -#include -#include -#include -#include -#include -using namespace std; - -class ComPort -{ -private: - char* portName; - DCB dcb; - BOOL fSuccess; - HANDLE readThread; - HANDLE writeThread; - DWORD dwParam, dwThreadReadId, dwThreadWriteId; - -public: - HANDLE hCom; - ComPort(); - bool init(char* portName); - void send(); - string read(); - void createReadThread(); - void createWriteThread(); - void initThreads(); - //DWORD WINAPI readProc(LPVOID); - DWORD WINAPI writeProc(LPVOID); - void closePort(); - ~ComPort(); -}; - diff --git a/code/c++/trackPlatform/trackPlatform/Commands.cpp b/code/c++/trackPlatform/trackPlatform/Commands.cpp deleted file mode 100644 index 8dcee1a..0000000 --- a/code/c++/trackPlatform/trackPlatform/Commands.cpp +++ /dev/null @@ -1,12 +0,0 @@ -#include "Commands.h" - - - -Commands::Commands() -{ -} - - -Commands::~Commands() -{ -} diff --git a/code/c++/trackPlatform/trackPlatform/Commands.h b/code/c++/trackPlatform/trackPlatform/Commands.h deleted file mode 100644 index 694a703..0000000 --- a/code/c++/trackPlatform/trackPlatform/Commands.h +++ /dev/null @@ -1,8 +0,0 @@ -#pragma once -class Commands -{ -public: - Commands(); - ~Commands(); -}; - diff --git a/code/c++/trackPlatform/trackPlatform/Menu.cpp b/code/c++/trackPlatform/trackPlatform/Menu.cpp deleted file mode 100644 index 5cf3bf6..0000000 --- a/code/c++/trackPlatform/trackPlatform/Menu.cpp +++ /dev/null @@ -1,27 +0,0 @@ -#include "Menu.h" - - - -Menu::Menu() -{ -} - -void Menu::show() { - cout << "Menu:" << endl; - cout << "1 - Move forward" << endl; - cout << "2 - Turn left" << endl; - cout << "3 - Turn right" << endl; - cout << "4 - Move back" << endl; - cout << "0 - Exit" << endl; -} - -int Menu::choose() { - int chooseMenuItem; - cin >> chooseMenuItem; - return chooseMenuItem; -} - - -Menu::~Menu() -{ -} diff --git a/code/c++/trackPlatform/trackPlatform/Menu.h b/code/c++/trackPlatform/trackPlatform/Menu.h deleted file mode 100644 index 1878db9..0000000 --- a/code/c++/trackPlatform/trackPlatform/Menu.h +++ /dev/null @@ -1,13 +0,0 @@ -#pragma once -#include -using namespace std; - -class Menu -{ -public: - Menu(); - void show(); - int choose(); - ~Menu(); -}; - diff --git a/code/c++/trackPlatform/trackPlatform/main.cpp b/code/c++/trackPlatform/trackPlatform/main.cpp deleted file mode 100644 index 1f6b9d7..0000000 --- a/code/c++/trackPlatform/trackPlatform/main.cpp +++ /dev/null @@ -1,42 +0,0 @@ -#include -#include -#include -#include -#include "ComPort.h" -#include "Commands.h" -#include "Menu.h" -#include -#include -using namespace std; - -char buf[128]; -char* pbuf = buf; -int counter = 0; - -ComPort comPort; -HANDLE hEvent; -DWORD bytesRead, bWritten; - -HANDLE hThread; - - - -int main() { - setlocale(LC_ALL, "Russian"); - - char* portName; - cout << "Input port name: "; - cin >> portName; - - if (!comPort.init(portName)) { - return 0; - } - - comPort.initThreads(); - - hEvent = CreateEvent(NULL, FALSE, FALSE, NULL); - - - comPort.closePort(); - return 0; -} \ No newline at end of file diff --git a/docs/Arduino api v4/Diagrams/Classes.png b/docs/Arduino api v4/Diagrams/Classes.png new file mode 100644 index 0000000..f2e9932 Binary files /dev/null and b/docs/Arduino api v4/Diagrams/Classes.png differ diff --git a/docs/Arduino api v4/Diagrams/Components&Deployment.png b/docs/Arduino api v4/Diagrams/Components&Deployment.png new file mode 100644 index 0000000..782fe9c Binary files /dev/null and b/docs/Arduino api v4/Diagrams/Components&Deployment.png differ diff --git a/docs/Arduino api v4/Diagrams/ConnectToPlatformActivity.png b/docs/Arduino api v4/Diagrams/ConnectToPlatformActivity.png new file mode 100644 index 0000000..758df95 Binary files /dev/null and b/docs/Arduino api v4/Diagrams/ConnectToPlatformActivity.png differ diff --git a/docs/Arduino api v4/Diagrams/ConnectToPlatformSequence.png b/docs/Arduino api v4/Diagrams/ConnectToPlatformSequence.png new file mode 100644 index 0000000..6322173 Binary files /dev/null and b/docs/Arduino api v4/Diagrams/ConnectToPlatformSequence.png differ diff --git a/docs/Arduino api v4/Diagrams/GetLineInfoActivity.png b/docs/Arduino api v4/Diagrams/GetLineInfoActivity.png new file mode 100644 index 0000000..ed1d693 Binary files /dev/null and b/docs/Arduino api v4/Diagrams/GetLineInfoActivity.png differ diff --git a/docs/Arduino api v4/Diagrams/GetLineInfoSequence.png b/docs/Arduino api v4/Diagrams/GetLineInfoSequence.png new file mode 100644 index 0000000..dad657c Binary files /dev/null and b/docs/Arduino api v4/Diagrams/GetLineInfoSequence.png differ diff --git a/docs/Arduino api v4/Diagrams/GetMessageActivity.png b/docs/Arduino api v4/Diagrams/GetMessageActivity.png new file mode 100644 index 0000000..8694037 Binary files /dev/null and b/docs/Arduino api v4/Diagrams/GetMessageActivity.png differ diff --git a/docs/Arduino api v4/Diagrams/GetMessageSequence.png b/docs/Arduino api v4/Diagrams/GetMessageSequence.png new file mode 100644 index 0000000..65bf320 Binary files /dev/null and b/docs/Arduino api v4/Diagrams/GetMessageSequence.png differ diff --git a/docs/Arduino api v4/Diagrams/mainStates.png b/docs/Arduino api v4/Diagrams/mainStates.png new file mode 100644 index 0000000..c19430b Binary files /dev/null and b/docs/Arduino api v4/Diagrams/mainStates.png differ diff --git a/docs/Arduino api v4/Diagrams/useCases.png b/docs/Arduino api v4/Diagrams/useCases.png new file mode 100644 index 0000000..d81bdf3 Binary files /dev/null and b/docs/Arduino api v4/Diagrams/useCases.png differ diff --git a/docs/Arduino api v4/FlowOfEvents.md b/docs/Arduino api v4/FlowOfEvents.md new file mode 100644 index 0000000..71137f8 --- /dev/null +++ b/docs/Arduino api v4/FlowOfEvents.md @@ -0,0 +1,162 @@ +# Поток событий + +## Подключение к платформе + +Данный вариант использования позволяет внешнему интерфейсу подключаться к платформе для дальнейшего управления ей +Предусловие: платформа находится в состоянии "Ожидание подключения" +Основной поток событий: +1. Вариант использования начинается, когда платформа получает команду подключения +2. Платформа переходит в состояние "Попытка подключения" +2. Платформа проверяет корректность параметров в команде. При обнаружении некорректных параметров выполняется альтернативный поток E1. +2. Платформа переходит в состояние "Ожидание команды" +3. Вариант использования завершается + +Альтернативный поток событий E1: +1. Альтернативный поток событий E1 начинается. +1. Платформа запоминает, что произошла ошибка выполнения команды. +2. Платформа переходит в состояние "Ожидание подключения" +5. Альтернативный поток событий E1 завершается. + +## Отключение от платформы + +Данный вариант использования позволяет внешнему интерфейсу принудительно отключаться от платформы +Предусловие: платформа находится в состоянии "Ожидание команды" +Основной поток событий: +1. Вариант использования начинается, когда была принята и распознана команда отключения от платформы +2. Платформа переходит в состояние "Исполнение команды" +2. Платформа проверяет корректность параметров в команде. При обнаружении некорректных параметров выполняется альтернативный поток E1. +2. Платформа переходит в состояние "Ожидание подключения" +3. Вариант использования завершается + +Альтернативный поток событий E1: +1. Альтернативный поток событий E1 начинается. +1. Платформа запоминает, что произошла ошибка выполнения команды. +2. Платформа переходит в состояние "Ожидание команды" +5. Альтернативный поток событий E1 завершается. + +## Управление движением + +Данный вариант использования позволяет внешнему интерфейсу управлять движением платформы через драйвер двигателя. +Предусловие: платформа находится в состоянии "Ожидание команды" +Основной поток событий: +1. Вариант использования начинается, когда была принята и распознана команда управления движением +2. Платформа переходит в состояние "Исполнение команды" +2. Платформа проверяет корректность параметров в команде. При обнаружении некорректных параметров выполняется альтернативный поток E1. +3. Платформа конвертирует параметры команды в вид, принимаемый драйвером двигателя +3. Платформа отправляет данные драйверу двигателя +5. Вариант использования завершается + +Альтернативный поток событий E1: +1. Альтернативный поток событий E1 начинается. +1. Платформа запоминает, что произошла ошибка выполнения команды. +5. Альтернативный поток событий E1 завершается. + +Постусловия: +Платформа переходит в состояние "Ожидание команды" + +## Взаимодействие с поворотной платформой + +Данный вариант использования позволяет внешнему интерфейсу взаимодействовать с поворотной платформой +Предусловие: платформа находится в состоянии "Ожидание команды" +Основной поток событий: +1. Вариант использования начинается, когда была принята и распознана команда работы с поворотной платформой +2. Платформа переходит в состояние "Исполнение команды" +2. Платформа проверяет корректность параметров в команде. При обнаружении некорректных параметров выполняется альтернативный поток E1. +3. Платформа определяет тип взаимодействия с поворотной платформой +4. Платформа взаимодействует с поворотной платформой в соответствии с вариантом использования требуемого типа взаимодействия +5. Вариант использования завершается + +Альтернативный поток событий E1: +1. Альтернативный поток событий E1 начинается. +1. Платформа запоминает, что произошла ошибка выполнения команды. +5. Альтернативный поток событий E1 завершается. + +Постусловия: +Платформа переходит в состояние "Ожидание команды" + +## Изменение текущего положение поворотной платформы + +Данный вариант использования позволяет внешнему интерфейсу измененять текущее положение поворотной платформы +Предусловие: платформа распознала команду работы с поворотной платформой +Основной поток событий: +1. Вариант использования начинается, когда распознана команда изменения текущего положение поворотной платформы +3. Платформа конвертирует параметры команды в вид, требуемый поворотной платформе для установки текущего положения +4. Платформа отправляет данные о требуемом положении сервоприводам +5. Вариант использования завершается + +## Получение информации о текущем положении поворотной платформы + +Данный вариант использования позволяет внешнему интерфейсу получать информацию о текущем положении поворотной платформы +Основной поток событий: +1. Вариант использования начинается, когда распознана команда получения информации о текущем положении поворотной платформы +3. Платформа получает информацию о текущем положении поворотной платформы +3. Платформа конвертирует полученную информацию в соответствии с протоколом общения с вненшими интерфейсами +4. Платформа генерирует ответ на основе сконвертированной информации +5. Вариант использования завершается + +## Получение информации с датчиков линии + +Данный вариант использования позволяет внешнему интерфейсу получать информацию с датчиков линии платформы. +Предусловие: платформа находится в состоянии "Ожидание команды" +Основной поток событий: +1. Вариант использования начинается, когда была принята и распознана команда получения информации с датчиков линии +2. Платформа переходит в состояние "Исполнение команды" +2. Платформа проверяет корректность параметров в команде. При обнаружении некорректных параметров выполняется альтернативный поток E1. +3. Платформа конвертирует параметры команды в вид, принимаемый переходной платой датчиков линии +3. Платформа отправляет данные переходной плате датчиков линии +3. Платформа получает информацию с переходной платы датчиков линии +3. Платформа конвертирует информацию с переходной платы датчиков линии в соответствии с протоколом общения с вненшими интерфейсами: 0 - под датчиком светлая область, 1 - под датчиком темная область +4. Платформа генерирует ответ на основе сконвертированной информации +5. Вариант использования завершается + +Альтернативный поток событий E1: +1. Альтернативный поток событий E1 начинается. +1. Платформа запоминает, что произошла ошибка выполнения команды. +5. Альтернативный поток событий E1 завершается. + +Постусловия: +Платформа переходит в состояние "Ожидание команды" + +## Получение информации с датчиков расстояния + +Данный вариант использования позволяет внешнему интерфейсу получать информацию с датчиков расстояния платформы. +Предусловие: платформа находится в состоянии "Ожидание команды" +Основной поток событий: +1. Вариант использования начинается, когда была принята и распознана команда получения информации с датчиков расстояния +2. Платформа переходит в состояние "Исполнение команды" +2. Платформа проверяет корректность параметров в команде. При обнаружении некорректных параметров выполняется альтернативный поток E1. +3. Платформа конвертирует параметры команды в вид, принимаемый переходной платой датчиков расстояния +3. Платформа отправляет данные переходной плате датчиков расстояния +3. Платформа получает информацию с переходной платы датчиков расстояния +3. Платформа конвертирует информацию с переходной платы датчиков расстояния в общепринятые единицы измерения расстояния (сантиметры) +4. Платформа генерирует ответ на основе сконвертированной информации +5. Вариант использования завершается + +Альтернативный поток событий E1: +1. Альтернативный поток событий E1 начинается. +1. Платформа запоминает, что произошла ошибка выполнения команды. +5. Альтернативный поток событий E1 завершается. + +Постусловия: +Платформа переходит в состояние "Ожидание команды" + +## Получение сообщения и его проверка на соответствие команде + +Данный вариант использования позволяет внешнему интерфейсу получать сообщения и выделять полезную информацию +Предусловие: платформа находится в состояниях "Ожидание команды" или "Ожидание подключения" +Основной поток событий: +1. Вариант использования начинается, когда была принято сообщение +2. Платформа проверяет, является ли принятое сообщение командой. Если нет, выполняется альтернативный поток E1. +2. Платформа проверяет, повреждена ли принятая команда. Если да, выполняется альтернативный поток E1. +4. Платформа возвращает [утвердительный ответ](Requirements.md#service_answers), используя внешний интерфейс, от которого было получено сообщение. +3. Платформа проверяет, поддерживается ли данная команда в данном состоянии платформы и распознает ее тип. Если нет, выполняется альтернативный поток E1. +4. Платформа отправляет команду на выполнение в соответствии с ее типом. +4. Платформа проверяет наличие ошибок при выполнении команды. Если они присутствуют - выполняется альтернативный поток событий E1. +4. Платформа проверяет наличие ответа при выполнении команды. Если он присутствует, платформа возвращает ответ, используя внешний интерфейс, от которого было получено сообщение. +4. Платформа возвращает [утвердительный ответ](Requirements.md#service_answers), используя внешний интерфейс, от которого было получено сообщение. +5. Вариант использования завершается + +Альтернативный поток событий E1: +1. Альтернативный поток событий E1 начинается. +1. Платформа возвращает [отрицательный ответ](Requirements.md#service_answers), используя внешний интерфейс, от которого было получено сообщение. +5. Альтернативный поток событий E1 завершается diff --git a/docs/Arduino api v4/Glossary.md b/docs/Arduino api v4/Glossary.md new file mode 100644 index 0000000..1f9d7d5 --- /dev/null +++ b/docs/Arduino api v4/Glossary.md @@ -0,0 +1,14 @@ +# Глоссарий + +**Платформа** - аппаратно-программная платформа +**Прошивка** - программное обеспечение, которое загружается на микроконтроллер и управляет его работой. +**API** - интерфейс взаимодействия с плаформой. +**Протокол** - набор правил для взаимодействия с платформой. +**Внешние интерфейсы** - набор способов для общения с платформой (USB, Bluetooth). +**Внешнее устройство** - устройство управления платформой, которое взаимодействует с ней по одному из внешний интерфейсов. +**Драйвер двигателя** - программно управляемая плата для взаимодействия с гусеницами платформы. +**Переходная плата** - плата для установление коммуникации с модулями. +**Поворотная платформа, сервоприводы** - платформа для размещения какого-либо датчика либо веб-камеры. Умеет вращаться, текущее положение устанавливается программно. +**Команда** - сообщение, сформированное по протоколу +**Сообщение** - любая информация, пришедшая на платформу по внешним интерфейсам + diff --git a/docs/Arduino api v4/Requirements.md b/docs/Arduino api v4/Requirements.md new file mode 100644 index 0000000..b201fa6 --- /dev/null +++ b/docs/Arduino api v4/Requirements.md @@ -0,0 +1,304 @@ +# Требования к проекту +--- + +# Содержание +1) [Версия документа](#doc_version) +1) [Список изменений](#revisions) +1) [Введение](#intro) +2) [Аналоги](#analogues) +2) [Требования пользователя](#user_requires) + 1) [Программные интерфейсы](#program_interfaces) + 1) [Протокол взаимодействия](#protocol) + 1) [Список поддерживаемых команд](#supported_commands) + 2) [Внешние аппаратные интерфейсы](#external_hardware_interfaces) + 3) [Характеристики пользователей](#user_description) + 4) [Предположения и зависимости](#dependencies) +3) [Системные требования](#system_requires) + 1) [Функциональные требования](#functional_requires) + 2) [Нефункциональные требования](#nonfunctional_requires) + 1) [Атрибуты качаства](#quality_attributes) + 1) [Ограничения](#limitations) + + + +# Версия документа + +1.6 + + + +# Список изменений + +- Версия 1.6 (2017.12.05) + В списке поддерживаемых команд поправлены принимаемые параметры в подразделе "Гусеницы" для команды с идентификатором `09`. Добавлена команда с идентификатором `0B`. Добавлены идентификаторы гусениц +- Версия 1.5 (2017.11.21) + В списке поддерживаемых команд поправлены принимаемые параметры в подразделе "Гусеницы" и возвращаемые значения в подразделе "Сервоприводы" +- Версия 1.4 (2017.10.29) + В фунциональных требованиях поправлены формулировки требований к отключению +- Версия 1.3 (2017.10.29) + В фунциональных требованиях объединено взаимодействие с поворотной платформой в один общий пункт +- Версия 1.2 (2017.10.28) + В фунциональных требованиях уточнена работа по протоколу +- Версия 1.1 (2017.10.19) + В фунциональных требованиях добавлено подтребование по получению информации о текущем положении + сервоприводов в соответствии со [списком поддерживаемых команд](#supported_commands) +- Версия 1.0 (2017.10.10) + Написана основная версия + + + +# Введение + + +Название проекта: trackPlatform. +Вид проекта: аппаратно-программная платформа (далее - аппаратная платформа, платформа). +Данный проект предназначен для помощи студентам и разработчикам, работающим с программным +обеспечением (далее - ПО), которое не связано программированием микроконтроллеров, +использовать микроконтроллеры +и их возможности для выполнения поставленных задач. Цель данного проекта - написать программное +обеспечение для микроконтроллера (далее - прошивку) и предоставить программисту интерфейсы для +взаимодействия с hardware-уровнем (уровнем микроконтроллеров) и использованием его возможностей с +помощью отправки команд микроконтроллеру. +Сама аппаратная платформа должна уметь: +- передавать информацию с датчиков расстояния и линии в режиме реального времени; +- перемещаться в пространстве в двух плоскостях, используя гусеницы (т.е. устройство + не должно уметь летать); +- управлять поворотной платформой, установленной на корпусе (вращение относительно двух осей); +- принимать команды для их последующей обработки и ответа на них, если требуется. + + + +# Аналоги + +Данный проект имеет аналог: свою предыдущую версию. Предыдущая версия проекта не имеет +четкой структуры и для добавления новых функций в систему требуется переписывать +большое количество имеющегося кода. Требуется по возможности устранить данные недостатки +системы. +Также в данной реализации требуется убрать поддержку редко используемых команд. + + + +# Требования пользователя + + + +## Программные интерфейсы + +Данное устройство должно взаимодействовать только с API (библиотекой для взаимодействия +с данной аппаратной платформой), написанных на разных языках +программирования, используя свою прошивку. Сами API могут быть использованы в различных +приложениях, например: +- управление платформой с помощью смартфона; +- системы исследования местности. + +Взаимодействие с API должно проводиться как с использованием проводных (через USB-кабель), + так и беспроводных (через Bluetooth) систем связи (подробнее см. [тут](#external_hardware_interfaces)). + API может быть реализовано самим + разработчиком, так и сторонними. Обе стороны (API и платформа) обязаны безукоризеннно + следовать [протоколу](#protocol). + + + +### Протокол взаимодействия +Для взаимодействия с платформой требуется реализовать протокол, который будет принимать команды и отвечать на них. +Формат любой посылки (на прием или передачу): +*<размер данных> <данные> <контрольная сумма>* + +| Элемент команды | Размер | Описание | +| :---------------- | :--------------------------------------- | :--------------------------------------- | +| Размер данных | 1 байт | Размер данных в байтах (пересылается в двоичном виде) | +| Данные | До 255 байт включительно (ограничено возможностями поля "Размер данных") | Пересылаемые данные | +| Контрольная сумма | 2 байта | Контрольная сумма, рассчитанная по алгоритму CRC-16 IBM (полином версии 0x8005) | + +Формат данных команды (отправляется из приложения через API на устройство): +*<контроллер> <команда контролера> <параметры команды (если требуется командой)>* + +| Элемент команды | Описание | +| :------------------ | :--------------------------------------- | +| Контроллер | выбор контроллера (контроллер движения, датчиков, сервопривода или связи) | +| Команда контроллера | команда контроллеру (например: движение вперед) | +| Параметры команды | необязательный параметр, обычно одно или несколько чисел в виде строки (а не в двоичном виде), разделяемые символом-разделителем и которые прилагаются к команде | + +Формат данных ответа полностью зависит от команды, на которую платформа будет отправлять ответ. + +Ответы также могут быть управляющими (синхронизирующими). Существует два вида управляющих ответов: +- OK +- ERROR + +Первый - утвердительный, второй - отрицательный. +При полном приеме команды от приложения будет сформирован ответ: +утвердительный - при принятии команды без повреждений, отрицательный - в случаях +повреждения посылки либо принятии команды с несоответствующим форматом. +При посылке отрицательного ответа на команду платформа переходит в режим ожидания команды. +Также по завершению выполнения команды будет возвращен один из управляющих ответов. +Только после этого настоятельно рекомендуется посылать следующую команду. + +Если некоторый промежуток времени (определяется заводскими настройками) на платформу не будет подана какая-либо из команд, определенных протоколом, произойдет сброс соединения по таймауту. + + + +### Список поддерживаемых команд + +Ниже приведен список контроллеров с их HEX-идентификаторами (в скобках) и их поддерживаемые команды: +- Гусеницы (01) + +| Команда (ее HEX-идентификатор) | Параметры | +|:---|:---| +| Установка скорости обоих гусениц (0B) | 1. Скорость движения в промежутке [-255, 255] для левой гусеницы; 2. Скорость движения в промежутке [-255, 255] для правой гусеницы | +| Установка скорости какой-то конкретной гусеницы (09) | 1. [Идентификатор гусеницы](#track_type); 2. Скорость движения в промежутке [-255, 255] | +| Движение вперед (06) | 1. Скорость движения в промежутке [-255, 255] | +| Поворот по часовой стрелке (0A) | 1. Скорость поворота в промежутке [-255, 255] | +| Полная остановка (05) | - | + + + +| Расположение гусеницы относительно направления движения вперед | Идентификатор | +|:---|:---| +| Левая | 0 | +| Правая | 1 | + +- Сервоприводы (03) + +| Команда (ее HEX-идентификатор) | Параметры | Возвращаемое значение | +| :--------------------------------------- | :--------------------------------------- | :--------------------------------------- | +| Установить угол для определенной оси (05) | 1. [Идентификатор оси](#axis_type); 2. Угол отклонения от от левого крайнего положения в градусах (промежуток [0, 180]) | - | +| Получить текущий угол отклонения от левого края (06) | 1. [Идентификатор оси](#axis_type) | Угол отклонения от левого края в градусах (промежуток [0, 180]) | + + + +| Плоскость | Идентификатор | +| :-------- | :------------ | +| xy | 1 | +| xz | 2 | + +- Датчики (02) + +| Команда (ее HEX-идентификатор) | Параметры | Возвращаемое значение | +| :--------------------------------------- | :--------------------------------------- | :--------------------------------------- | +| Получить информацию с датчиков расстояния (01) | 1. Идентификатор датчика (номер датчика с 1) | Расстояние до препятствия в сантиметрах | +| Получить информацию со всех датчиков расстояния одновременно (02) | - | Расстояние до препятствия каждого датчика в сантиметрах (от меньшего номера датчика к большему) | +| Получить информацию с датчиков линии (03) | 1. Идентификатор датчика (номер датчика с 1) | [Информация о типе области](#area_type) | +| Получить информацию со всех датчиков линии одновременно (04) | - | [Информация о типе области](#area_type) каждого датчика (от меньшего номера датчика к большему) | + + + +| Информация о типе области | Идентификатор | +| :------------------------ | :------------ | +| Светлая | 0 | +| Темная | 1 | + +- Системные команды (04) + +| Команда (ее HEX-идентификатор) | Параметры | +| :--------------------------------------- | :--------------------------------------- | +| Подключение (01) | 1. Версия используемого API (в бинарном виде, для этой версии HEX-представление: 04) | +| Отключение (02) | - | +| Поддержка соединения, "пустая" команда (03) | - | + + + + + +## Внешние аппаратные интерфейсы + +Для общения с платформой могут быть использованы следующие способы соединения с платформой: + +1. USB; +2. Bluetooth; + +Требуется реализовать поддержку каждого из них. + + + +## Характеристики пользователей + +Данное решение предназначено для студентов технических специальностей (будущих разработчиков ПО) + и разработчиков, которые знакомы с последовательными протоколами передачи данных + (например, RS-232) и их видами и которые понимают как они функционируют. + + + + +## Предположения и зависимости + +На требования к данной платформе и протоколу для взаимодействия с ней могут повлиять: + +- добавление новых интерфейсов связи или данных (например, Wi-Fi, SD карты); +- изменение требований к ПО; +- добавление других видов датчиков для платформы (например, компаса); + + + +# Системные требования + + + + +## Функциональные требования + + +1. возможность подключения к платформе; +2. возможность принудительного отключения от платформы; +3. автоматическое отключение от платформы по истечению определенного промежутка времени; +4. управление гусеничной платформой (управление движением): + - движение вперед; + - движение назад; + - разворот по направлению движения часовой стрелки; + - разворот против направления движения часовой стрелки; +5. взаимодействие с поворотной платформой: + - управление поворотной платформой: + - поворот в плоскости xy; + - поворот в плоскости xz; + - получение информации о текущем состоянии сервоприводов: + - получение текущего угла отклонения в плоскости xy; + - получение текущего угла отклонения в плоскости xz; +6. получение корректной информации с датчиков линии (с "заводской" калибровкой датчиков + в виде констант); +7. получение корректной информации с датчиков расстояния (с "заводской" калибровкой датчиков + в виде констант); + + + +## Нефункциональные требования + + + +### Атрибуты качества + + +Данные требования должны быть учтены при проектировании и написании текущей прошивки: + +1. Масштабируемость: + - оставить возможность одновременной поддержки нескольких версий API (версия API определяется по команде подключения); + - добавить возможность дальнейшего расширения функционала: + - возможность изменения конфигурации платформы без перепрошивки модуля (пинов, настроек модулей); + - увеличение числа имеющихся датчиков (до 255 штук) без изменения API; + - добавление новых видов датчиков с дополнением API; +2. Надежность: + - платформа должна выполнять только те команды, которые дошли полностью и без повреждений: + - должно быть обеспечено протоколом передачи сообщений: длина сообщения и контрольная сумма. + + + +### Ограничения + +Разработка должна вестить на аппаратной платформе, на которой была реализована предыдущая версия прошивки: + +| Оборудование | Количество | +| :--------------------------------------- | :--------- | +| Arduino Mega R3 | 1 шт. | +| Arduino Mega Sensor Shield v2.0 | 1 шт. | +| Датчики линии TCRT5000 | 5 шт. | +| Переходная плата для датчиков линии | 1 шт. | +| Датчики расстояния GP2Y0A21YK0F | 5 шт. | +| Переходная плата для датчиков расстояния | 1 шт. | +| Bluetooth HC-05 с переходной платой FC-114 | 1 шт. | +| Сервопривод SG-90 | 2 шт. | +| Драйвер двигателя L298N | 1 шт. | + diff --git a/docs/Arduino api v4/TestCases.md b/docs/Arduino api v4/TestCases.md new file mode 100644 index 0000000..a7c4425 --- /dev/null +++ b/docs/Arduino api v4/TestCases.md @@ -0,0 +1,235 @@ +#### Возможность подключения к платформе + +1. 1 + +2. Возможность подключения к платформе + +3. Произведите следующие шаги: + + 1. Включите платформу + + 2. Дождитесь загрузки платформы (на изображении ниже светодиод 1 должен отключиться (перестать моргать), а светодиод 2 должен гореть) + + ![mega_loaded](TestPlan_images/mega_sensor_shield_loaded.jpg) + + 3. Запустите приложение и попробуйте подключиться к платформе + +4. В приложении появится надпись "Connected" + +5. В левом верхнем углу появилась надпись "Connected" + +6. Прошел + +#### Возможность принудительного отключения от платформы + +1. 2 +2. Возможность принудительного отключения от платформы по завершению работы с ней +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выйдите из приложения, через которое подключались (нажмите кнопку "Quit") + 3. Попробуйте заново подключиться к платформе +4. В приложении, с помощью которого производилось подключение второй раз, появится надпись "Connected" +5. При нажатии кнопки "Exit" приложение завершилось. При втором открытии приложения надпись "Connected" появилась. +6. Прошел + +#### Автоматическое отключение от платформы по истечению определенного промежутка времени + +1. 3 +2. Автоматическое отключение от платформы по истечению определенного промежутка времени +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Аварийно завершить работу приложения, через которое производилось подключение, либо принудительно разорвать соединение (выдернуть USB-провод или отключить Bluetooth-соединение) + 3. Подождите 10 секунд + 4. Попробуйте заново подключиться к платформе +4. В приложении, с помощью которого производилось подключение второй раз, появится надпись "Connected" +5. Соединение установилось +6. Прошел + +#### Движение вперед + +1. 4 +2. Проверка движения платформы вперед +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "move forward". Если требуется, укажите скорость +4. Платформа должна поехать вперед с заданной скоростью +5. Платформа поехала вперед +6. Прошел + +#### Движение назад + +1. 5 +2. Проверка движения платформы назад +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "move back". Если требуется, укажите скорость +4. Платформа должна поехать назад с заданной скоростью +5. Платформа поезала назад +6. Прошел + +#### Разворот по направлению движения часовой стрелки + +1. 6 +2. Проверка возможности поворота платформы по часовой стрелке +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "turn right (clockwise)". Если требуется, укажите скорость +4. Платформа должна начать поворачиваться с заданной скоростью по часовой стрелке +5. Платформа повернулась по часовой стрелке +6. Прошел + +#### Разворот против направления движения часовой стрелки + +1. 7 +2. Проверка возможности поворота платформы против часовой стрелки +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "turn left (anticlockwise)". Если требуется, укажите скорость +4. Платформа должна начать поворачиваться с заданной скоростью против часовой стрелки +5. Платформа повернулась против часовой стрелки +6. Прошел + +#### Поворот сервоприводов в плоскости xy + +1. 8 +2. Проверка возможности поворота сервоприводов в плоскости xy +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set horisontal servo angle in degree". Укажите корректный угол в градусах (от 0 до 180) +4. Платформа должна установить сервоприводы на указанный угол +5. Сервопривод был установлен на указанные угол xy +6. Прошел + +#### Поворот сервоприводов в плоскости xz + +1. 9 +2. Проверка возможности поворота сервоприводов в плоскости xz +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set vertical servo angle in degree". Укажите корректный угол в градусах (от 0 до 180) +4. Платформа должна установить сервоприводы на указанный угол +5. Сервопривод был установлен на указанный угол в плоскости xz +6. Прошел + +#### Получение текущего угла отклонения в сервоприводов в плоскости xy + +1. 10 +2. Получение текущего угла отклонения в сервоприводов в плоскости xy +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set horisontal servo angle in degree". Укажите корректный угол в градусах (от 0 до 180) + 3. Выберите в приложении "get horisontal servo angle in degree" +4. В приложении должно появится значение, которое было введено в пункте 3.2 +5. На экрне появился угол отклонения сервопривода в плоскости xy +6. Прошел + +#### Получение текущего угла отклонения в сервоприводов в плоскости xz + +1. 11 +2. Получение текущего угла отклонения в сервоприводов в плоскости xz +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set vertical servo angle in degree". Укажите корректный угол в градусах (от 0 до 180) + 3. Выберите в приложении "get vertical servo angle in degree" +4. В приложении должно появится значение, которое было введено в пункте 3.2 +5. На экрне появился угол отклонения сервопривода в плоскости xz +6. Прошел + +#### Некорректный поворот сервоприводов в плоскости xy + +1. 12 +2. Проверка возможности поворота сервоприводов в плоскости xy +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set horisontal servo angle in degree". Укажите некорректный угол в градусах (больше 180) +4. Платформа не должна изменить текущий угол сервоприводов +5. Положение сервопривода не изменилось +6. Прошел + +#### Некорректный поворот сервоприводов в плоскости xz + +1. 13 +2. Проверка возможности поворота сервоприводов в плоскости xz +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set vertical servo angle in degree". Укажите некорректный угол в градусах (больше 180) +4. Платформа не должна изменить текущий угол сервоприводов +5. Положение сервопривода не изменилось +6. Прошел + +#### Получение информации с датчиков линии. Белый лист + +1. 14 +2. Получение информации с датчиков линии. Проверка корректного определения белого цвета +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Положите под платформу лист белой бумаги + 3. Выберите в приложении "get fixed line value". Укажите номер датчика в диапазоне от 1 до 5 +4. В приложении должно появится 0 +5. У одного из датчиков появилось значение 1 +6. Не прошел + +#### Получение информации с датчиков линии. Черный лист + +1. 15 +2. Получение информации с датчиков линии. Проверка корректного определения черного цвета +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Положите под платформу лист черной бумаги + 3. Выберите в приложении "get fixed line value". Укажите номер датчика в диапазоне от 1 до 5 +4. В приложении должно появится 1 +5. У одного из датчиков появилось значение 0 +6. Не прошел + +#### Получение информации с датчиков расстояния + +1. 16 +2. Получение информации с датчиков расстояния +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Подставьте перед центральным датчиком расстояния какой-нибудь непрозрачный предмет, например книгу, на расстоянии приблизительно 15 сантиметров + 3. Выберите в приложении "get fixed distance value". Укажите номер датчика 3 +4. В приложении должно появится значение от 10 до 19 +5. Были получены значения 21 и более +6. Не прошел + +#### Проверка времени жизни от батареи + +1. 17 +2. Проверка времени жизни от батареи. +3. Произведите следующие шаги: + 1. Зарядите аккомуляторную батарею платформы до 100% + 2. Подключитесь к платформе + 3. Повзаимодействуйте с платформой 5 минут +4. Платформа все еще должна работать +5. Платформа реагировала на взаимодействие +6. Прошел + +#### Проверка времени реакции на любую команду + +1. 18 +2. Проверка времени реакции на любую команду. Она должна составлять не более 1 секунды +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выполните любую команду +4. Платформа должна среагировать (вернуть ответ или совершить действие) быстрее, чем за 1 секунду +5. Платформа реагирует на команды +6. Прошел + +### Выводы + +Пункты 14-16 не прошли. + + +| Атрибут качества | Результат(в %) | +| ------------------------------ | -------------- | +| Функциональная полнота | 81 | +| Функциональная корректность | 81 | +| Временная характеристика | 100 | +| Доступность | 100 | +| Защита от ошибок пользователей | 100 | +| Модульность | - | +| Устанавливаемость | - | +| Заменяемость | 81 | + +Видно, что из-за проблем с датчиками линии и расстояния продукт не обладает следующеми атрибутами качества: функциональная полнота, функциональная корректность, заменяемость. \ No newline at end of file diff --git a/docs/Arduino api v4/TestPlan.md b/docs/Arduino api v4/TestPlan.md new file mode 100644 index 0000000..13f9509 --- /dev/null +++ b/docs/Arduino api v4/TestPlan.md @@ -0,0 +1,289 @@ +# План тестирования + +### Введение + +Данный план описывает тестирование всей системы. + +Требования, предъявляемые к тестировщику: + +* умение управлять смартфоном или персональным компьютером (далее, ПК) +* умение подключать смартфон или ПК к другому устройству по интерфейсу Bluetooth или USB +* понимание механизма работы портов последовательного обмена информацией (COM-портов, Serial-портов) + +Цель данного тестирования: проверка работоспособности системы в реальных условиях. + +### Объекты тестирования + +* Прошивка для микроконтроллера ATmega 2560, который расположен на Arduino Mega 2560 R3 +* Корректная работа всей платформы +* API, предоставляемое прошивкой для управление периферийными устройствами микроконтроллера + +Атрибуты качества платформы по ISO 25010: + +* функциональность + * функциональная полнота: платформа должна выполнять все возложенные на нее функции (см. [Функциональные требования](Requirements.md#functional_requires)) + * функциональная корректность: платформа должна выполнять все возложенные на нее функции корректно (см. [Функциональные требования](Requirements.md#functional_requires)) +* производительность + * временная характеристика: платформа должна реагировать на каждую команду не более 1 секунды +* практичность + * защита от ошибок пользователей: платформа должна работать только согласно [протоколу](Requirements.md#protocol) и проверять аргументы каждой команды +* надежность + * доступность: платформа должна работать от аккомуляторной батареи не менее 5 минут +* сопровождаемость + * модульность: все периферийные модули должны взаимодействовать с протоколом через специальный модуль взаимодействия, протокол взаимодействия должен знать каждый модуль взаимодействия, все должно быть организовано через специальный класс +* мобильность + * устанавливаемость: прошивка должна корректно устанавливаться и работать на любой Arduino Mega с аналогичной оригинальной платформе периферией + * заменяемость: прошивка должна в полной мере заменить свою предыдущую версию + +### Риски + +Без корректной работы протокола невозможна работа всей платформы в целом + +### Аспекты тестирования + +* возможность подключения к платформе; +* возможность принудительного отключения от платформы; +* автоматическое отключение от платформы по истечению определенного промежутка времени; +* управление гусеничной платформой (управление движением): + - движение вперед; + - движение назад; + - разворот по направлению движения часовой стрелки; + - разворот против направления движения часовой стрелки; +* взаимодействие с поворотной платформой: + - управление поворотной платформой: + - поворот в плоскости xy; + - поворот в плоскости xz; + - получение информации о текущем состоянии сервоприводов: + - получение текущего угла отклонения в плоскости xy; + - получение текущего угла отклонения в плоскости xz; +* получение корректной информации с датчиков линии (с "заводской" калибровкой датчиков в виде констант); +* получение корректной информации с датчиков расстояния (с "заводской" калибровкой датчиков в виде констант); +* время жизни от батареи должно быть не менее 5 минут (с учетом полностью заряженной батареи в начале теста); +* реакция на любую команду должна составлять не более 1 секунды; + +### Функции, не подлежащие тестированию + +Не требуется тестирование атрибута качества "Защита от ошибок пользователей" для всех пунктов меню, поскольку он выполняется на уровне API языка высокого уровня. + +Атрибут качества "Устанавливаемость" предполагает наличие еще одной платформы, а она отсуствует вообще. + +Атрибут качества "Модульность" должен выполняться на этапе проектирования исходных кодов прошивки, поэтому также не будет протестирован вообще. + +### Подходы к тестированию + +Для тестирования можно использовать как приложение для ПК, так и приложение для смартфона. + +При тестировании через ПК-версию приложения рекомендуется использовать версию приложения для клавиатуры, т.к. она предоставляет полные возможности API в отличии от версии для геймпада + +### Представление результатов + +Предоставление результатов требуется описать в следующем виде: + +1. Идентификатор +2. Назначение / название +3. Сценарий +4. Ожидаемый результат +5. Фактический результат (заполняется на этапе тестирования) +6. Оценка (заполняется на этапе тестирования) + +Далее приведены сами тестовые сценарии + +#### Возможность подключения к платформе + +1. 1 + +2. Возможность подключения к платформе + +3. Произведите следующие шаги: + + 1. Включите платформу + + 2. Дождитесь загрузки платформы (на изображении ниже светодиод 1 должен отключиться (перестать моргать), а светодиод 2 должен гореть) + + ![mega_loaded](TestPlan_images/mega_sensor_shield_loaded.jpg) + + 3. Запустите приложение и попробуйте подключиться к платформе + +4. В приложении появится надпись "Connected" + +#### Возможность принудительного отключения от платформы + +1. 2 +2. Возможность принудительного отключения от платформы по завершению работы с ней +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выйдите из приложения, через которое подключались (нажмите кнопку "Quit") + 3. Попробуйте заново подключиться к платформе +4. В приложении, с помощью которого производилось подключение второй раз, появится надпись "Connected" + +#### Автоматическое отключение от платформы по истечению определенного промежутка времени + +1. 3 +2. Автоматическое отключение от платформы по истечению определенного промежутка времени +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Аварийно завершить работу приложения, через которое производилось подключение, либо принудительно разорвать соединение (выдернуть USB-провод или отключить Bluetooth-соединение) + 3. Подождите 10 секунд + 4. Попробуйте заново подключиться к платформе +4. В приложении, с помощью которого производилось подключение второй раз, появится надпись "Connected" + +#### Движение вперед + +1. 4 +2. Проверка движения платформы вперед +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "move forward". Если требуется, укажите скорость +4. Платформа должна поехать вперед с заданной скоростью + +#### Движение назад + +1. 5 +2. Проверка движения платформы назад +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "move back". Если требуется, укажите скорость +4. Платформа должна поехать назад с заданной скоростью + +#### Разворот по направлению движения часовой стрелки + +1. 6 +2. Проверка возможности поворота платформы по часовой стрелке +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "turn right (clockwise)". Если требуется, укажите скорость +4. Платформа должна начать поворачиваться с заданной скоростью по часовой стрелке + +#### Разворот против направления движения часовой стрелки + +1. 7 +2. Проверка возможности поворота платформы против часовой стрелки +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "turn left (anticlockwise)". Если требуется, укажите скорость +4. Платформа должна начать поворачиваться с заданной скоростью против часовой стрелки + +#### Поворот сервоприводов в плоскости xy + +1. 8 +2. Проверка возможности поворота сервоприводов в плоскости xy +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set horisontal servo angle in degree". Укажите корректный угол в градусах (от 0 до 180) +4. Платформа должна установить сервоприводы на указанный угол + +#### Поворот сервоприводов в плоскости xz + +1. 9 +2. Проверка возможности поворота сервоприводов в плоскости xz +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set vertical servo angle in degree". Укажите корректный угол в градусах (от 0 до 180) +4. Платформа должна установить сервоприводы на указанный угол + +#### Получение текущего угла отклонения в сервоприводов в плоскости xy + +1. 10 +2. Получение текущего угла отклонения в сервоприводов в плоскости xy +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set horisontal servo angle in degree". Укажите корректный угол в градусах (от 0 до 180) + 3. Выберите в приложении "get horisontal servo angle in degree" +4. В приложении должно появится значение, которое было введено в пункте 3.2 + +#### Получение текущего угла отклонения в сервоприводов в плоскости xz + +1. 11 +2. Получение текущего угла отклонения в сервоприводов в плоскости xz +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set vertical servo angle in degree". Укажите корректный угол в градусах (от 0 до 180) + 3. Выберите в приложении "get vertical servo angle in degree" +4. В приложении должно появится значение, которое было введено в пункте 3.2 + +#### Некорректный поворот сервоприводов в плоскости xy + +1. 12 +2. Проверка возможности поворота сервоприводов в плоскости xy +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set horisontal servo angle in degree". Укажите некорректный угол в градусах (больше 180) +4. Платформа не должна изменить текущий угол сервоприводов + +#### Некорректный поворот сервоприводов в плоскости xz + +1. 13 +2. Проверка возможности поворота сервоприводов в плоскости xz +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выберите в приложении "set vertical servo angle in degree". Укажите некорректный угол в градусах (больше 180) +4. Платформа не должна изменить текущий угол сервоприводов + +#### Получение информации с датчиков линии. Белый лист + +1. 14 +2. Получение информации с датчиков линии. Проверка корректного определения белого цвета +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Положите под платформу лист белой бумаги + 3. Выберите в приложении "get fixed line value". Укажите номер датчика в диапазоне от 1 до 5 +4. В приложении должно появится 0 + +#### Получение информации с датчиков линии. Черный лист + +1. 15 +2. Получение информации с датчиков линии. Проверка корректного определения черного цвета +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Положите под платформу лист черной бумаги + 3. Выберите в приложении "get fixed line value". Укажите номер датчика в диапазоне от 1 до 5 +4. В приложении должно появится 1 + +#### Получение информации с датчиков расстояния + +1. 16 +2. Получение информации с датчиков расстояния +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Подставьте перед центральным датчиком расстояния какой-нибудь непрозрачный предмет, например книгу, на расстоянии приблизительно 15 сантиметров + 3. Выберите в приложении "get fixed distance value". Укажите номер датчика 3 +4. В приложении должно появится значение от 10 до 19 + +#### Проверка времени жизни от батареи + +1. 17 +2. Проверка времени жизни от батареи. +3. Произведите следующие шаги: + 1. Зарядите аккомуляторную батарею платформы до 100% + 2. Подключитесь к платформе + 3. Повзаимодействуйте с платформой 5 минут +4. Платформа все еще должна работать + +#### Проверка времени реакции на любую команду + +1. 18 +2. Проверка времени реакции на любую команду. Она должна составлять не более 1 секунды +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Выполните любую команду +4. Платформа должна среагировать (вернуть ответ или совершить действие) быстрее, чем за 1 секунду + +### Выводы + +В вышеописанных тестовых сценариях проверяется выполнение атрибутов качества. Зависимость представлена ниже: + +| Атрибут качества | В каких тестовых сценариях проверяется | +| ------------------------------ | -------------------------------------- | +| Функциональная полнота | 1-16 | +| Функциональная корректность | 1-16 | +| Временная характеристика | 18 | +| Доступность | 17 | +| Защита от ошибок пользователей | 12-13 | +| Модульность | - | +| Устанавливаемость | - | +| Заменяемость | 1-16 | + +Если не выполняется один из тестовых сценариев, то, соответственно, не выполняется и соответствующий атрибут качества. Продукт будет обладать требуемыми атрибутами качества только при выполнении всех тестовых сценариев. + +Функциональные и нефункциональные требования из [SRS](Requirements.md) проверяются в тестовых сценариях 1-16. + diff --git a/docs/Arduino api v4/TestPlan_images/mega_sensor_shield_loaded.jpg b/docs/Arduino api v4/TestPlan_images/mega_sensor_shield_loaded.jpg new file mode 100644 index 0000000..d0e4d2f Binary files /dev/null and b/docs/Arduino api v4/TestPlan_images/mega_sensor_shield_loaded.jpg differ diff --git a/documentation/diagrams/activity_diagrams/api_change_activity_diagram.svg b/documentation/diagrams/activity_diagrams/api_change_activity_diagram.svg new file mode 100644 index 0000000..8272215 --- /dev/null +++ b/documentation/diagrams/activity_diagrams/api_change_activity_diagram.svg @@ -0,0 +1,2 @@ + +
Изменение API
Изменение API
Пользователь
Пользователь
Выбор другого API
Выбор другого API
Вывод об ошибке
Вывод об ошибке
SettingsActitivy
SettingsActitivy
Запрос на проверку соединения
Запрос на проверку соединения
ConnectionThread
ConnectionThread
Проверка соединения
Проверка соединения
Отправка команды отключения
Отправка команды отключения
Отключение
Отключение
Подключение с новым API
Подключение с новым API
Получение ответа
Получение ответа
Ожидание ответа
Ожидание ответа
[соединение есть]
[соединение есть]
Изменение GUI
Изменение GUI
[нет соединения]
[нет соединения]
Аппаратная платформа
Аппаратная платформа
Ответ на подключение
Ответ на подключение
\ No newline at end of file diff --git a/documentation/diagrams/activity_diagrams/change_language_activity_diagram.svg b/documentation/diagrams/activity_diagrams/change_language_activity_diagram.svg new file mode 100644 index 0000000..b221553 --- /dev/null +++ b/documentation/diagrams/activity_diagrams/change_language_activity_diagram.svg @@ -0,0 +1,2 @@ + +
Выбор языка
Выбор языка
GUI
GUI
Выбор другого языка
Выбор другого языка
Вывод GUI с другим языком
Вывод GUI с другим языком
SettingsActivity
SettingsActivity
Запрос на изменение языка
Запрос на изменение языка
Обновление GUI
Обновление GUI
Language
Language
Изменение языка
Изменение языка
\ No newline at end of file diff --git a/documentation/diagrams/activity_diagrams/motion_activity_activity_diagram.svg b/documentation/diagrams/activity_diagrams/motion_activity_activity_diagram.svg new file mode 100644 index 0000000..cfdbc10 --- /dev/null +++ b/documentation/diagrams/activity_diagrams/motion_activity_activity_diagram.svg @@ -0,0 +1,2 @@ + +
Управление гусеницами платформы
Управление гусеницами платформы
Пользователь
Пользователь
Нажатие кнопки вперед
Нажатие кнопки вперед
Вывод об ошибке
Вывод об ошибке
MotionActivity
MotionActivity
ConnectionThread
ConnectionThread
[соединение есть]
[соединение есть]
Отправка команды
Отправка команды
Проверка соединения
Проверка соединения
[нет соединения]
[нет соединения]
Аппаратная платформа
Аппаратная платформа
Движение вперед
Движение вперед
\ No newline at end of file diff --git a/documentation/diagrams/activity_diagrams/sensors_activity_activity_diagram.svg b/documentation/diagrams/activity_diagrams/sensors_activity_activity_diagram.svg new file mode 100644 index 0000000..c06b2ca --- /dev/null +++ b/documentation/diagrams/activity_diagrams/sensors_activity_activity_diagram.svg @@ -0,0 +1,2 @@ + +
Получение информации с датчиков
Получение информации с датчиков
GUI
GUI
Нажатие кнопки получения информации
Нажатие кнопки получения информации
Вывод об ошибке
Вывод об ошибке
Отображение информации
Отображение информации
SensorsActivity
SensorsActivity
ConnectionThread
ConnectionThread
[соединение есть]
[соединение есть]
Отправка команды на получение информации
Отправка команды на получение информации
Получение информации с датчиков
Получение информации с датчиков
Проверка соединения
Проверка соединения
[нет соединения]
[нет соединения]
Аппаратная платформа
Аппаратная платформа
Получение информации с датчиков
Получение информации с датчиков
Отправка информации с датчиков
Отправка информации с датчиков
\ No newline at end of file diff --git a/documentation/diagrams/activity_diagrams/servo_activity_activity_diagram.svg b/documentation/diagrams/activity_diagrams/servo_activity_activity_diagram.svg new file mode 100644 index 0000000..f62009c --- /dev/null +++ b/documentation/diagrams/activity_diagrams/servo_activity_activity_diagram.svg @@ -0,0 +1,2 @@ + +
Управление сервоприводами платформы
Управление сервоприводами платформы
Пользователь
Пользователь
Нажатие кнопки
Нажатие кнопки
Вывод об ошибке
Вывод об ошибке
ServoActivity
ServoActivity
ConnectionThread
ConnectionThread
[соединение есть]
[соединение есть]
Отправка команды
Отправка команды
Проверка соединения
Проверка соединения
[нет соединения]
[нет соединения]
Аппаратная платформа
Аппаратная платформа
Изменение положения сервоприводов
Изменение положения сервоприводов
\ No newline at end of file diff --git a/documentation/diagrams/class_diagram.svg b/documentation/diagrams/class_diagram.svg new file mode 100644 index 0000000..0d4f1a6 --- /dev/null +++ b/documentation/diagrams/class_diagram.svg @@ -0,0 +1,3 @@ + + +
class diagram
class diagram
MainActivity- motionButton: Button- servoButton: Button- sensorsButton: Button- settingsButton: Button- exitButton: Button+ languageWrapper: LanguageWrapper# onCreate(Bundle)+ getIntent(): IntentMotionActivity+ servoController: ServoController- languageWrapper: LanguageWrapper# onCreate(Bundle)+ getIntent(): IntentSensorsActivity+ sensorsController: SensorsController- languageWrapper: LanguageWrapper# onCreate(Bundle)+ getIntent(): IntentServoActivity- languageWrapper: LanguageWrapper- servoController: ServoController# onCreate(Bundle)+ getIntent(): IntentSettingsActivity- languageWrapper: LanguageWrapper# onCreate(Bundle)+ getIntent(): IntentBluetoothConnector- bluetoothConnector: BluetoothConnector- bluetoothSocket: BluetoothSocket- BluetoothConnectro()+ getInstance(): BluetoothConnector+ connect()+ disconnect()+ isConnected(): booleanListResourceBundle+ getContents(): Object[][]LanguageWrapper- language: ResourceBundle- settings: Settings+ getViewString(viewName: String): StringRussianLanguage+ getContents(): Object[][]EnglishLanguage+ getContents(): Object[][]API1+ getContents(): Object[][]API2+ getContents(): Object[][]API3+ getContents(): Object[][]
Extends
Extends
Extends
Extends
APIWrapper- api: ResourceBundle- settings: Settings+ getCommand(commandName: String): String
Use
Use
Use
Use
Settings- api: String- settings: Settings+ getInstance(): Settings+ getCurrentAPI(): String+ getCurrentLanguage(): String+ setAPI(api: String)+ setLanguage(language: String)«interface»Constants+ API1: String+ API2: String+ API3: String+ RussianLanguage: String+ EnglishLanguage: StringSensorsController- apiWrapper: APIWrapper- bluetoothConnector: BluetoothConnector+ getInfoFromDistanceSensor(num: int): int+ getInfoFromLineSensor(num: int): intServoController- bluetoothConnector: BluetoothConnector+ up(): + down(): + left(): + rifth(): SettingsController- bluetoothConnector: BluetoothConnector+ setAPI(api: String)MotionController- bluetoothConnector: BluetoothConnector+ moveForward()+ moveBack()+ moveLeft()+ moveRight()InterfaceAPI+getMoveForward()
Use
Use
\ No newline at end of file diff --git a/documentation/diagrams/component_diagram.svg b/documentation/diagrams/component_diagram.svg new file mode 100644 index 0000000..b0f07c0 --- /dev/null +++ b/documentation/diagrams/component_diagram.svg @@ -0,0 +1,2 @@ + +
diagram
diagram
activities
activities
<<source>>MainActivity.java<<source>>MotionActivity.java<<source>>ServoActivity.java<<source>>SensorsActivity.java<<source>>SettingsActivity.java
connectors
connectors
<<source>>BluetoothConnector
constants
constants
<<source>>Constants
controllers
controllers
<<source>>MotionController.java<<source>>ServoController.java<<source>>SensorsController.java<<source>>SettingsController.java
api_resources
api_resources
<<source>>API1.java<<source>>API2.java<<source>>API3.java
language_resources
language_resources
<<source>>RussianLanguage.java<<source>>EnglishLanguage.java
settings
settings
<<source>>Settings.java
wrappers
wrappers
<<source>>APIWrapper<<source>>LanguageWrapper<<document>>build.gradle<<executable>>application2.0.apk
res
res
layout
layout
values
values
<<document>>strings.xml<<document>>styles.xml<<document>>colors.xml<<document>>activity_main.xml<<document>>activity_motion.xml<<document>>activity_servo.xml<<document>>activity_settings.xml<<document>>activity_sensors.xml
\ No newline at end of file diff --git a/documentation/diagrams/deployment_diagram.svg b/documentation/diagrams/deployment_diagram.svg new file mode 100644 index 0000000..8bef24e --- /dev/null +++ b/documentation/diagrams/deployment_diagram.svg @@ -0,0 +1,2 @@ + +
<<device>>
Arduino Mega
[Not supported by viewer]
<<device>>
Телефон
[Not supported by viewer]
application2.0.apk
[Not supported by viewer]
bluetooth
bluetooth
trackPlatform.hex
<u>trackPlatform.hex</u>
hex файл - файл прошивки.
<div>hex файл - файл прошивки.</div>
Скомпилированное приложение
Скомпилированное приложение
\ No newline at end of file diff --git a/documentation/diagrams/sequenct_diagrams/change_lenguage_sequence_diagram.svg b/documentation/diagrams/sequenct_diagrams/change_lenguage_sequence_diagram.svg new file mode 100644 index 0000000..c5a6178 --- /dev/null +++ b/documentation/diagrams/sequenct_diagrams/change_lenguage_sequence_diagram.svg @@ -0,0 +1,2 @@ + +
:Language
:Language
:Пользователь
:Пользователь
:Spinnder
:Spinnder
:SettingsActivity
:SettingsActivity
Выбор другого языка
Выбор другого языка
setOnItemSelectedListener()
<span>setOnItemSelectedListener()</span>
changeLanguage()
changeLanguage()
Выбор языка
Выбор языка
\ No newline at end of file diff --git a/documentation/diagrams/sequenct_diagrams/choose_api_sequence_diagram.svg b/documentation/diagrams/sequenct_diagrams/choose_api_sequence_diagram.svg new file mode 100644 index 0000000..0414779 --- /dev/null +++ b/documentation/diagrams/sequenct_diagrams/choose_api_sequence_diagram.svg @@ -0,0 +1,2 @@ + +
:ConnectionThread
:ConnectionThread
:Пользователь
:Пользователь
:Аппаратная платформа
:Аппаратная платформа
:Spinnder
:Spinnder
:SettingsActivity
:SettingsActivity
:BluetoothSocket
:BluetoothSocket
Выбор другого API
Выбор другого API
setOnItemSelectedListener()
setOnItemSelectedListener()
changeAPI(api)
changeAPI(api)
isConnected()
isConnected()
isConnected
isConnected
alt
alt
[isConnected = false]
[isConnected = false]
[else]
[else]
onProgressUpdate()
<span>onProgressUpdate()</span>
Вывод об ошибке
<span>Вывод об ошибке</span>
whiteUTF(DISCONNECT)
whiteUTF(DISCONNECT)
whiteUTF(DISCONNECT)
whiteUTF(DISCONNECT)
Проверка команды
Проверка команды
ОК
ОК
Выбор API
Выбор API
whiteUTF(CONNECT_API1)
whiteUTF(CONNECT_API1)
whiteUTF(CONNECT_API1)
whiteUTF(CONNECT_API1)
Проверка команды
Проверка команды
OK
OK
onProgressUpdate()
onProgressUpdate()
Отображение выбранного пункта
Отображение выбранного пункта
Отключение
Отключение
ОК
ОК
ОК
ОК
Подключение с новым API
Подключение с новым API
ОК
ОК
\ No newline at end of file diff --git a/documentation/diagrams/sequenct_diagrams/motion_activity_sequence_diagram.svg b/documentation/diagrams/sequenct_diagrams/motion_activity_sequence_diagram.svg new file mode 100644 index 0000000..ccc2670 --- /dev/null +++ b/documentation/diagrams/sequenct_diagrams/motion_activity_sequence_diagram.svg @@ -0,0 +1,3 @@ + + +
:ConnectionThread
:ConnectionThread
:Пользователь
:Пользователь
:Аппаратная платформа
:Аппаратная платформа
:Button
:Button
:MotionActivity
:MotionActivity
:BluetoothSocket
:BluetoothSocket
Нажатие на кнопку
Нажатие на кнопку
onClickListener()
onClickListener()
moveForward()
moveForward()
isConnected()
isConnected()
isConnected
isConnected
alt
alt
[isConnected = false]
[isConnected = false]
[else]
[else]
onProgressUpdate()
<span>onProgressUpdate()</span>
Вывод об ошибке
<span>Вывод об ошибке</span>
whiteUTF(FORWARD)
whiteUTF(FORWARD)
whiteUTF(FORWARD)
whiteUTF(FORWARD)
Проверка команды
Проверка команды
ОК
ОК
Управление гусеницами
Управление гусеницами
Движение вперед
Движение вперед
ОК
ОК
\ No newline at end of file diff --git a/documentation/diagrams/sequenct_diagrams/sensors_activity_sequence_diagram.svg b/documentation/diagrams/sequenct_diagrams/sensors_activity_sequence_diagram.svg new file mode 100644 index 0000000..5f7fa78 --- /dev/null +++ b/documentation/diagrams/sequenct_diagrams/sensors_activity_sequence_diagram.svg @@ -0,0 +1,2 @@ + +
:ConnectionThread
:ConnectionThread
:Пользователь
:Пользователь
:Аппаратная платформа
:Аппаратная платформа
:TextView
:TextView
:SensorsActivity
:SensorsActivity
:BluetoothSocket
:BluetoothSocket
getInfoFromSensors()
getInfoFromSensors()
isConnected()
isConnected()
isConnected
isConnected
alt
alt
[isConnected = false]
[isConnected = false]
[else]
[else]
onProgressUpdate()
<span>onProgressUpdate()</span>
Вывод об ошибке
<span>Вывод об ошибке</span>
whiteUTF(INFO)
whiteUTF(INFO)
whiteUTF(INFO)
whiteUTF(INFO)
ОК
ОК
Получение информации с датчиков
Получение информации с датчиков
Проверка команды
Проверка команды
Информация с датчиков
Информация с датчиков
onProgressUpdate()
onProgressUpdate()
setText(info)
setText(info)
Вывод информации
Вывод информации
Получение информации с датчиков
Получение информации с датчиков
Информация с датчиков
Информация с датчиков
\ No newline at end of file diff --git a/documentation/diagrams/sequenct_diagrams/servo_activity_sequence_diagram.svg b/documentation/diagrams/sequenct_diagrams/servo_activity_sequence_diagram.svg new file mode 100644 index 0000000..e836cfb --- /dev/null +++ b/documentation/diagrams/sequenct_diagrams/servo_activity_sequence_diagram.svg @@ -0,0 +1,2 @@ + +
:ConnectionThread
:ConnectionThread
:Пользователь
:Пользователь
:Аппаратная платформа
:Аппаратная платформа
:Button
:Button
:ServoActivity
:ServoActivity
:BluetoothSocket
:BluetoothSocket
Нажатие на кнопку
Нажатие на кнопку
onClickListener()
onClickListener()
moveUp()
moveUp()
isConnected()
isConnected()
isConnected
isConnected
alt
alt
[isConnected = false]
[isConnected = false]
[else]
[else]
onProgressUpdate()
<span>onProgressUpdate()</span>
Вывод об ошибке
<span>Вывод об ошибке</span>
whiteUTF(UP)
whiteUTF(UP)
whiteUTF(UP)
whiteUTF(UP)
Изменение положения сервопривода
Изменение положения сервопривода
ОК
ОК
Управление сервоприводами платформы
Управление сервоприводами платформы
Проверка команды
Проверка команды
ОК
ОК
\ No newline at end of file diff --git a/documentation/diagrams/state_diagrams/API_language_state_diagram.svg b/documentation/diagrams/state_diagrams/API_language_state_diagram.svg new file mode 100644 index 0000000..a1d6a9d --- /dev/null +++ b/documentation/diagrams/state_diagrams/API_language_state_diagram.svg @@ -0,0 +1,2 @@ + +
Выбор API и выбор языка
Выбор API и выбор языка
нажата кнопка settings
нажата кнопка settings
Главное меню
Главное меню
[нет соединения]
[нет соединения]
назад
назад
выбор языка
выбор языка
Настройки
Настройки
выбор API
выбор API
\ No newline at end of file diff --git a/documentation/diagrams/state_diagrams/line_sensors_state_diagram.svg b/documentation/diagrams/state_diagrams/line_sensors_state_diagram.svg new file mode 100644 index 0000000..90502e0 --- /dev/null +++ b/documentation/diagrams/state_diagrams/line_sensors_state_diagram.svg @@ -0,0 +1,2 @@ + +
Получение информации с датчиков линии
Получение информации с датчиков линии
нажата кнопка sensors
нажата кнопка sensors
Главное меню
Главное меню
[нет соединения]
[нет соединения]
назад
назад
Отображение инфорации
Отображение инфорации
[информация получена]
[информация получена]
[сбой при получении информации]
[сбой при получении информации]
Получение информации с датчиков
Получение информации с датчиков
\ No newline at end of file diff --git a/documentation/diagrams/state_diagrams/motion_state_diagram.svg b/documentation/diagrams/state_diagrams/motion_state_diagram.svg new file mode 100644 index 0000000..2fb9098 --- /dev/null +++ b/documentation/diagrams/state_diagrams/motion_state_diagram.svg @@ -0,0 +1,2 @@ + +
нажата кнопка motion
нажата кнопка motion
Главное меню
Главное меню
Управление гусеницами платформы
Управление гусеницами платформы
[нет соединения]
[нет соединения]
назад
назад
движение вперед
движение вперед
Управление движением 
Управление движением 
движение назад
движение назад
движение влево
движение влево
движение вправо
движение вправо
\ No newline at end of file diff --git a/documentation/diagrams/state_diagrams/sensors_state_diagram.svg b/documentation/diagrams/state_diagrams/sensors_state_diagram.svg new file mode 100644 index 0000000..d058c70 --- /dev/null +++ b/documentation/diagrams/state_diagrams/sensors_state_diagram.svg @@ -0,0 +1,2 @@ + +
Получение информации с датчиков расстояния
Получение информации с датчиков расстояния
нажата кнопка sensors
нажата кнопка sensors
Главное меню
Главное меню
[нет соединения]
[нет соединения]
назад
назад
Отображение инфорации
Отображение инфорации
[информация получена]
[информация получена]
[сбой при получении информации]
[сбой при получении информации]
Получение информации с датчиков
Получение информации с датчиков
\ No newline at end of file diff --git a/documentation/diagrams/state_diagrams/servo_state_diagram.svg b/documentation/diagrams/state_diagrams/servo_state_diagram.svg new file mode 100644 index 0000000..f62809e --- /dev/null +++ b/documentation/diagrams/state_diagrams/servo_state_diagram.svg @@ -0,0 +1,2 @@ + +
Управление сервоприводами платформы
Управление сервоприводами платформы
нажата кнопка servo
нажата кнопка servo
Главное меню
Главное меню
[нет соединения]
[нет соединения]
назад
назад
поднять выше
поднять выше
Управление сервоприводами
Управление сервоприводами
опустить
опустить
повернуть вправо
повернуть вправо
повернуть влево
повернуть влево
\ No newline at end of file diff --git a/documentation/diagrams/use_case.png b/documentation/diagrams/use_case.png new file mode 100644 index 0000000..bcae242 Binary files /dev/null and b/documentation/diagrams/use_case.png differ diff --git a/documentation/diagrams_sources/activity_diagrams/api_change_activity_diagram.xml b/documentation/diagrams_sources/activity_diagrams/api_change_activity_diagram.xml new file mode 100644 index 0000000..b958e8c --- /dev/null +++ b/documentation/diagrams_sources/activity_diagrams/api_change_activity_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/activity_diagrams/change_language_activity_diagram.xml b/documentation/diagrams_sources/activity_diagrams/change_language_activity_diagram.xml new file mode 100644 index 0000000..baee6d5 --- /dev/null +++ b/documentation/diagrams_sources/activity_diagrams/change_language_activity_diagram.xml @@ -0,0 +1 @@ +7VrbcqM4EP0aP04KcQn4MfiS2aps1VRl9vYogwLaEcgF8tjer98WCBAGbLxOnMyO/aCoWwLJfY76onhizZLdY4bX8a88JGxiGuFuYs0npolsx4I/UrMvNe69WSqijIZqUqN4pv8QpTSUdkNDkrcmCs6ZoOu2MuBpSgLR0uEs49v2tBfO2quucUQ6iucAs672DxqKuNR6jtHoPxMaxdXKyFAjKxx8izK+SdV6E9N6KT7lcIKrd6n5eYxDvtVU1mJizTLORdlLdjPCpG0rs5XPLQdG631nJBWjHghQaE/tACHv3rDC8JN6w3fMNsoWk7kxmUKLJp4v+z4q2kWhgbcbRWdZKF1t2kPRVt9T7Cvb5luaMJyC5MciYaBE0A1iysInvOcbue9cgB0ryQcpE4oksJzlFwYm8itIqbahFAKe0ED1GV4R5teIzDjjGQylvFg8Fxn/RiolAGUUn3qkAl7u7oUyps1UkIKep2KJE8okz38nWYhTrNRqv8hUct9CmNEoBV0AaBEY9LvwVXiQTJCdplJwPhKeEJHtYYoatZXF1cmriLZtaOxWNI41Ck+nSonV0YnqNzf0gY5i0Eg2mR02Pf72y0hGdFDvMc4Qe09ba9g8Zq953Fcwz73huAibhget4Vrok909bIe2gTeA05Om2cZUkOc1DuTIFvxu21zvfSbqmVc4E0M0G31IkOG0TonTpYHdwwL7LUjg/RePC6KtRNlahcaqpmn9s91zwyN0mnT/I9eLs0A954x0Nmezzm2TDtld1tWJhE47601cs9v1NSEkQUrkmYh5xFPMFo32wMloRDiFN7jyB5mXHeiWVG649Fiau3dAJmlYPREwnOc0+BrTtBxQj6FS0h76mwixVzLeCA6q5os8cb6uY8sZBLyMaOOJlPNNFpDjoQKMFBFx3JNIGI/SMSMMC/q9neteRK6uGzmHS6jNJQ15viZtyI1XAfk4Vgf2Ox88bwRWzpWgGRFdTC1sAM2MIkUrwwY6FWy8op2dCjOLatot2AwHm04gGcO8wWBz77WCjeX1BBvkXCnHcU4nuoDuWnaTXSTvFO5W6yS9U0qdBdJKFCr1Jwn6F55TQbm07YoLwZNhNuhwVu94ULgI6TP8NckofFUJ0Fyl3V8alQ+1KKOSUXMiq3s/3ycrLncFwwlNsegGyEHGfkROXiXPRtdLtDu7tzokfIZIQtMofwjA51Kx75LyHSpTNVrXJO9RqXa233OAZRhxVREh22UVIupSpY4e86rWMLSg4aqYIFtHm6b3PaW5VTFvVsVY5xLzsIqZ9lUxPYHFeY3A0k/DhVYlz7WEo8xs/CO06ruOunHngqTEOoc7Vo9Tu14F3L19e8JptJH/GvhAccAx3jEO9FxQyvN2c+Af+xDa5xxC073iIey54L7kogBW/1NCfedU4l8K+R/rEkHNOXoD1HOr0J+mXeFWwbnBOBLGoUxah3HguL46apfd+P5MqPXdtl4JpOkNpLEesguS9zYggdj8JKMY0373Yi3+BQ== \ No newline at end of file diff --git a/documentation/diagrams_sources/activity_diagrams/motion_activity_activity_diagram.xml b/documentation/diagrams_sources/activity_diagrams/motion_activity_activity_diagram.xml new file mode 100644 index 0000000..dbaf817 --- /dev/null +++ b/documentation/diagrams_sources/activity_diagrams/motion_activity_activity_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/activity_diagrams/sensors_activity_activity_diagram.xml b/documentation/diagrams_sources/activity_diagrams/sensors_activity_activity_diagram.xml new file mode 100644 index 0000000..1b2c28d --- /dev/null +++ b/documentation/diagrams_sources/activity_diagrams/sensors_activity_activity_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/activity_diagrams/servo_activity_activity_diagram.xml b/documentation/diagrams_sources/activity_diagrams/servo_activity_activity_diagram.xml new file mode 100644 index 0000000..e948ced --- /dev/null +++ b/documentation/diagrams_sources/activity_diagrams/servo_activity_activity_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/sequence_diagrams/change_language_sequence_diagram.xml b/documentation/diagrams_sources/sequence_diagrams/change_language_sequence_diagram.xml new file mode 100644 index 0000000..a423585 --- /dev/null +++ b/documentation/diagrams_sources/sequence_diagrams/change_language_sequence_diagram.xml @@ -0,0 +1 @@ +7Vlbj+I2FP41kdqHVrkSeARm2K40q66WqpdHk5jEGieOHDMM/fV77NjBgTATWEZUFTwE+/Pd5/N3ThwnmBevnziq8i8sxdTx3fTVCR4c3/fCKIA/iewaJB75DZBxkupKe2BJ/sUadDW6ISmuOxUFY1SQqgsmrCxxIjoY4pxtu9XWjHZHrVCGj4Blgugx+hdJRa5Rz3X3Bb9hkuV66HGkC1Yoec4425R6PMcP1urXFBfI9KXr1zlK2daCgkcnmHPGRJMqXueYyr0129a0W5wobefNcSmGNIhXaIW8JFwlfrwOV+4v2k4viG70XjjB9AmV2UZuWTNnsTP7BNOvZHJT0CeyxpSUkJtVmJMCC8yhhGr46x6bbXMi8LJCiWy6BQYBlouCQs6DJBhVIGjC2zylqKrJSo3qAsJxsuE1ecHfcN1wR6JsI+RI85YTqqq0BU51rt1uV/VbkESnKVphOmuNN2eUyeFLphZUC86esQHBpq76tSWGI3K2a0KpVXOhfhKHVS1QQag8En9inqISaVjz3/N1vm8gRElWApaAYdUmZhTVtVlW00Eo08cM0KR4wVzgVwvSjPiEGRiG76CKLo3dcdNEn15/rPNb6ywYBufWMfDjUJ9Bff6ytu89ByGhaTiQkkYUbE4eEtGiT8VIKdT40cyJHg74yLjIWcZKRG1G/m9ZcsyGkyd+MD2iqMOOlgk2O3rI4QXuj5PD69UnB6wzWcjn7FE9Zw7s8niu0rGF++rpqtImHXXqD9Q3xAVJSIXUnkLZNBHSFLcSPmk6As5rqq0vmOy4hnFImf0hMw/B6DR99z7qhIZ2zkNHd04y/gcIerZc+ZP35erD1Kqd7l2criBO3vli1DF9PFCK4mtIUdQnRcuKlGAtfqmUzKTtEMzkria3UZMw8N5Vk+jD1KTHvd3V5GLbR+ca37gJbfvJMDm5SmAz6lUTLAScuhoCDPJCxO5SVYETCHahd1G5kahEk/BdUQk/TFR6qCUDZl8FvTMVAHsmSAYE5uGqbKiz8hkoJLBiaZP2mwoLE2y3fU51sP2GgB3SYsWEYAUU4DKdynsciVGWPF9kSbAX3/0tifCrG5n8P03eCwxgsf/hzRfomm14grthn0A8w8ZYWqtx2rlcOiaFZfSx3h6OKYIj3r1+6jO67u2rVP49v4Jw1OFXMD6QpGbuupV9H3TQUegfdBSPux01Cz7qSHGwXeIwWsZ3X3dFX3euJI3cSdfSk55Lnt7X+GtI0rjH9iMqGp9QQjpTaSx+Lz8LXCwxBa3H6ROpBQbv89PPpjqMZLe4ndgMk43bSUTkdV1Q6F4oESeJ8wESMTmiSZKjMsPmQlry4D9ncNsnnLzMvAEDRt7kgAHjyxgQe9HbHV2PAeExAwbELmeFI1YIveCowO8HwW+4FTv0vIaLGewRDF08Fem0gh1c6ZPAwZ1v1PdiZFhhe4vR5Px3I8juP4A1nNl/ZQwevwM= \ No newline at end of file diff --git a/documentation/diagrams_sources/sequence_diagrams/choose_api_sequence_diagram.xml b/documentation/diagrams_sources/sequence_diagrams/choose_api_sequence_diagram.xml new file mode 100644 index 0000000..0f4ba4e --- /dev/null +++ b/documentation/diagrams_sources/sequence_diagrams/choose_api_sequence_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/sequence_diagrams/motion_activity_sequence_diagram.xml b/documentation/diagrams_sources/sequence_diagrams/motion_activity_sequence_diagram.xml new file mode 100644 index 0000000..25764d5 --- /dev/null +++ b/documentation/diagrams_sources/sequence_diagrams/motion_activity_sequence_diagram.xml @@ -0,0 +1,2 @@ + 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/sequence_diagrams/sensors_activity_sequence_diagram.xml b/documentation/diagrams_sources/sequence_diagrams/sensors_activity_sequence_diagram.xml new file mode 100644 index 0000000..280d64e --- /dev/null +++ b/documentation/diagrams_sources/sequence_diagrams/sensors_activity_sequence_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/sequence_diagrams/servo_activity_sequence_diagram.xml b/documentation/diagrams_sources/sequence_diagrams/servo_activity_sequence_diagram.xml new file mode 100644 index 0000000..3c54867 --- /dev/null +++ b/documentation/diagrams_sources/sequence_diagrams/servo_activity_sequence_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/state_diagrams/API_language_choise_state_diagram.xml b/documentation/diagrams_sources/state_diagrams/API_language_choise_state_diagram.xml new file mode 100644 index 0000000..1404a64 --- /dev/null +++ b/documentation/diagrams_sources/state_diagrams/API_language_choise_state_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/state_diagrams/distance_sensors_state_diagram.xml b/documentation/diagrams_sources/state_diagrams/distance_sensors_state_diagram.xml new file mode 100644 index 0000000..e036e3f --- /dev/null +++ b/documentation/diagrams_sources/state_diagrams/distance_sensors_state_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/state_diagrams/line_sencsors_state_diagram.xml b/documentation/diagrams_sources/state_diagrams/line_sencsors_state_diagram.xml new file mode 100644 index 0000000..96370b4 --- /dev/null +++ b/documentation/diagrams_sources/state_diagrams/line_sencsors_state_diagram.xml @@ -0,0 +1 @@ +7LzZlqtKki36NfuxctA3j4AECBAgevFGL9H33dcfd0WsnWs3mZVZmVW37r0nxloRkoPA3c1s2pzmjn7BhWaXxqh/3bs0q3/BkHT/Bb/8gmEoRlDgD2w5vlpolP1qKMZ3+n3SXxvs95l9NyLfrcs7zabfnDh3XT2/+982Jl3bZsn8m7ZoHLvtt6flXf3bu/ZRkf2hwU6i+o+t/judX9+tKIL89YCcvYvX960Z8vtAHCVVMXZL+32/XzA8//x8HW6iH9f6Pn96RWm3/dSEX3/BhbHr5q9XzS5kNZzbH9P29Tnxbxz9td9j1s7/yAewCI8TjESiJEcolE7/g/m6whrVy/dc/HJBfmFF+Ju/fn7zv1zQXxj885v+tJCf35fPb+a7Bdz4r28vn5OJHxcBr7+OCp/fyKeF+ul85vNx0Ij+uA7x05nYT7f+Op/7qXvYj4/wv+3Azxf/TP18/DA3sEIPXy5NLY5RA17y2+s9Z3YfJbB9A14O2l5zU4N3KHj5MXGWfr/71YoIeJN0zTv5fl1HcVbzv/qE0NXdCA61XQvvMc1jV2U/GoGrIJ+fX4/8cD14i/xd1z+d+e1UoL1rZzFq3jWMNC8b06iNvpu/wwrFvt//2Y2i+l20oC0B/pKNcNw/7snCw68fPo6T4N0fnevb39ZsnLP9p6ZvZ5Oyrsnm8QCnfB/Fv/3+GxfAZT9vt5+CDPkRS6+fAowmvs+MviO7+PXSf/Vu8OLbwf+Gs//Rt3/vCeADAGOy3xr7h3tMczTO9hzN2R8N8jvT/dmRf4vP/Lvtnb5HAKDvDjZO3QKtwP8No/6J6f+mnVGG/I2hUQT/g6XxP7Hzj7Z/xcz4n0LYNwR8QQP1WzT5vP5GDe6nk78ARfypHZ42Ze3UjdMffScFOeT7bTfOr67o2qi+/rX1Jw9AfuthYFbHI4DtfyF/vH1+n1Zm83x82zZa5g40/fXqWtf1v14j5WDqg3fvs/arRXzDafpc5w8IklFJ8ncd9muEcFi/8QLgJmPy3UR8J+doLLIfufCf9RXkLzhIrb9xl//4QQTGrI7m9/rbDvyZc3xf3eze4KZ/hRsa/wv10w9N/BZ+KOYvyE8/v7v+10C/L/lzEv3n7kIgf374x22+Ju8PtwHGjI6fTuvhCdPfG+tvQw5nmf+k13/3fPDiqwd//mn0t0D+H+xvx9Tl+ZTNv/w+an81/j8UyMSfcxH8p+yOfKf838fsr/xD+C1BAfF+/UPg/haYozH5jjbQgT9NvMnfx/n/Jcj+dbduTLPx97wD0Jp3W3z36k+ZTje+T3Cj6AdAwWTwBvyY+77LDGHn35EocPR3iYLE/kgJsD/JFBhK/eupgvovgPhPsP33DfqngPxtSubvetA/6Ao/TF5n+Qyvvr/n7xwCZ/zz/pNE/oIC+fX13szGN5gl6CCXfxDisT9CPPEPW/mfw+9/FfLQb5n5pxD2XwAg+n8qx/9nufsf5QD/dC7/2aroPx68/2JapmnqLwSNkAwDFADGEr9N/hRB/0N5+L9g0B+e+/8Fi/6tRPA3LP0nsu3nKGf+6A//svH/URT+k5rDH1L0q2viZfrPhfk/n67/HUkM/y0OET+G9FMSY/4khxH/BrXD/nHySP4nPkR+i5xfCyo/k6S/VlaY337k55IJ+JT4C3n511Ll73LV7/lE3M1z1/xLSfPXaET/gqDMb+LxLzT7a7z+PgP+yJrobzIm+bcD6T+Jmn88N347z398X/dfxFTyd0QKw/97ZMbv70MQf19m/P58/Fuf/7ty9I+s9V+u6kD/+i/XdP4N4EFTv0t/zP9cqQT9k1rJ7yfvxzy9m0/R/NfQ1SD5Nbvp/V09+jWE/wYr/rlq+edyIpr6r2J+/t5hvuU/t+R+tCI/WsDrNJoBI+a+3mJiD9QMJrw93rA2RJWKjgM/uu2+rm4BXmXw7b0QuCf4e6E7+nqDLbysC7b3uAlcccu5V/UGbTeOV6yr6GbKOeFBzXh6wMLpxEQZd4TworTTTRHsq2JvfP0YDuH2Vmmh7/joePtX7zrGv2D86s2zGsc+yl5XcRlt1Bsw13s9d3ae367Xu72wCZWL3B49L+qVePF59XAs1T6Scy0P6/J4x/SLMxWgT8SaYC5A1YEo49mWbKzVyDIwZp4ixarKuIfACUw/LHCcYldyL/jifvuMVBA47sFtoEUqrgu3+6q1+9q+pPswB2OAxlYa5Kv08pMzeHBcJxNMO3T46BWT2FZM+x61E4yeb8ziduHAC28zFNupUBPfXy4f07LqgtbettV8eS89XTpbrXiKWMkTMxUPiZq2oGVqkla5iXNihTiocbRkdPYe1zvHJ7vQC/q76OxLnmXq/X07DPQ5uWofZW1GJqZ8eT2CeMY8l+eKy+280x5KoVFqyLKA0dECvGnBvRUgDJ+3KHB3/nJsWvo8mBvWi7qZWhtuWRTu7+HoR+mwJ2BCRT/KK1OOtvGGx3SY493hglmTi1v9tKoVp1jPzNcWqW37+rqFatWpXJFnLI2DcdMzXqfjCv4vXqO8u5H+eAe/TAQ31u8Ats0NHqNvllEegZyK1i2QUhKXKPLcn0N/Ndrp5WbzeS5Mo5Omok7C0j5sH3PG3kZL9+4PaGAQSOolphYrI5Jrj4q/cFygPlfxNubx+HwDn0XCe2XbQ/sgoYlAL/KAxegUTX2vj79aMui6FHOEd/B+fHRPw5BLfMDjqAEHgo6R22BAr3W6tFbvXtGZJ8jHvi/tYdyXOnGjmxLgRj0Jw5Qq561c1SWSaHABeLe4XKm12BhXN2pSswrusl2DpWmWxQ34bZKVM9ndTF4IHR3sSrm29t4hcZqX29NrZq/x2hBfYUcfY/FegRs8270t60CeLE8EuYunWf1Ag6GetMrTdlcAHmZ4cFRHjxvzNIU2Gtv2uD4xIUOPvjC4TfSTDJzCyy/ziWce4RdOidYl0jwW5t1vlZ4P42Nb0TZunwzHd4JW3/PS9fdp5J6mPOzpgj974/J6Epn8Svo0dwhMffeaTLCy1SGJJ+5Zi+mvp29vfuv0qD2zDINgqLa81RVJJWvogxEldZUh38wj2vfj7tXo0/TI1bs1S01b3ciOT1l0clTZuttlvS8qUzGdD+c0r6RQ/XKodcsnbQGvb1GaUzm5+y5yN+jTuA/o0pgVNKAODUEG9KKeeYMG1w2EvUC+URTF28g+JnbfCSZUqjLjNCvS7GrW0jye/CfyvCcKiNYC1WMv4sSckfmb3U3TuqIbzz3EuqCqSOroNs7o3Zaj2LPQSzFM04wOlctQp/ru+jEW5zywE3Z8ULkBfU25sXKIqj6FndTTqWwNza+bIg9gPJOzhj4TjOCluYJTBxmC2AZHSLUj2mjeTayXggEniMmwnmmD+dpbjN3ZMt18uiG8HSCICNG+eQ8mSHO8H6Tjd+TOfu8eaQrCtgY9G5CRf22sDWEhmBVkufAFHlCsVAH7JaN52ZNLl14iv+6neZ2X5TgOeuOD6PrO9QWJIhgveT7e4jGlNzrZ5wP1JrGb1FYgdYF7+RWbZGSt2jN+HOodmwsuPacxYLAZO2zd7I4sEa7t4O0RuFLV0Qxjp97ZRqXFYstYfpm4A//VFryunLA5qcUjM2T3Q6c+UnBEI6bZFfKspdKVnPBjnFZiJ1kEs0AqEL36DX5HrLfgop36I7UdGT5s1SPhZMGKZqMpnYQY6fItlFVyqWq7Psg01LyoDiXr5rYDPmL0uo6DSqH5ytItCMysxDYMQsOIULYhb6xE3Fkmyi67/aztW9Fs/FQP1UOdPRl0XkSCubdau5rqCR3i/FGy7JimN6YassuDbvr0DJuxnt6khvqHr1sLrlsUbbNvhC9DjPH7WeDNndTheLAgxTI9pyAgyDnpVrMFPWpE4TDRp/uJVlSXSuv0cLo+WCZ5xtlq6joeHOS1VpBp8FTSD2oqvbw2Uqm6py5R8TiOswFja0SrwwpHD0LI7E2TWKMY5ruqsK0nTAsvKoQpbhtqvXrrYC6QjpXLdtIHhErEI5fPZSauQoxfEWID11+qwa61lXVJ2E0GD8GHlapS6RTyr6NVRlcT3nAQ/IvSRfzg4wwdJ4Y1Fb4aHOFBzx41HWMSgDOMc0TcK6/5JIif7jFFII7tPQlEAyB0bSb3eVBpAya4VePsD7rzxk3bk1yGHnbhCqsjk8HGA198dZF1usiJUbOnIals5QWavynLLpHsFfuHKuB5N6qzywKalAfV28fY1aTss4+Cw9Zusm4SjHZwyKNX3KoNhM8A3wgkArYiztVyjFrsSxa1DuW0rEKGM0gw0Il2re2naIUiTu5yvjh7pHGHGWeThE4L3T02jt+qqGNW2gR4KkW6P7nSaxhcKjVsu4tLM3i9dmbQbFSvgJcybcEcE22gq1zuNHKZAUZdX49chrTIRmqIlOdaT5MHXLydXHmnJggvfIE9jEkY+Wd6ceIhElNsmC++WAcskdNr75+H7neTLAU4SzgSL6bbFtYcvU1FHlOov68udLpLuctxNYx3tAE5rsy6UZNnqgLUkeHFYb1xQ6rZ7oLHMwzIVq8yQzbl0Hw/G6uORkBxeM4e5ptzRNuC7yrwfwTitbM4Q0SnTuiOqcQSpYMp9D4V6ZNN45YnrcBTFW6gAOISVw1ABb97rpplwoobrgJNoeLJ6qEho9Z4vLfptPPXVVMJnmO4emsG1OsrpMMUf7yNtTfMnt7PutjN4vVIDRQQXOjmFmK83MfVuOD+DHydUCYuHbwqwlsPQrI9HDU9m2lVLhsfPo2lhq2sBX8DccfXA8+loWTizCuCxQVRUby0IBBIWdSl5zPvqDEEkHIeuqcw3oliA7mJsEiWzVKTPAbWHWpmqdcWp6k1jmM2e1vPJVqp+Eg5dLxS5bgw7jDeUH051aOOz3KSdn84Nl8POjc148YhbZbxdfEyohYe0DvM/N7kD/IbstJKtQFjYEz6AgJjhJny9MRjNQpAhvmYj8ZApfFsBEJiaZxwbeRHm+J3mI5mr6hqdpkvzdUIrKvTJYfwnPAvGXATDoFY4tQMYyLlVxmNJRNgFB+Q2GHdYKYjfUfO20jewNmT4S3+oJQw47FiDo4yAs9EX/TMbl6jU4LcxGnt1SPS5ZOvJpa5A+pedCpTAxokxlN/lSBCvio3EHufRt8YpHPpW+SzJrjILUrequTFDnFa1A5P4FqPbd5ZazRhOQ3FKk9UFV/temJTtezOe22XAnyCZVuIJws2Lup7Cl+MWZYvSK8SQEX9OhC/2MRLdNl7NY0LhBzaHULzYFY1gln6wB9DCxMBz3MNEeJvNlBHVkNxCOKGehbbBhXoyydbmfQ0fouBYGLHa+3gypA5CGADc3e+T/oSvTcz3s05j0FW8GTmKKvhcByfDER6KIB+sz3wym1e3cDfnCu0M2I0Po5+IaEvm0wSHD22pC6q1jZp2V40m9gjFkMN9i9k4vcbMsX3a0YmOxnp2+Blca7gMfms+CCjtyW5USu8WAgogLjTIfQhV7EIIFbAq3QczMznboKGFBDSGU5HKTbUIUajPnCnisgctr5KTHrCQQdRiC9eSodXfVhAQk9ZgN/iDAbkjf6JNv3aUdC6WeXzsW/WWusMqKkOBYMOTVGNKQy0qHXQ3dOf2OXtQc9EfE+vroqZOjAEV5CL0545ux89jNjLp4ePyUNxpnEUbOUAO4qmJtD4B54Lr0jzDOs4MsOOlVjCMzZuNuoTGqxY0rWTOROkI8dKz+phXG9ensaIgDGxCuZ1ehzQi0sEmAZgjMvqd5+nAhuBbIWlXxCVlzC1njAG3ENix1rJsCYOt/fNS3Kv89OJqLV5Ll2SnbUSwvdrjMc38dGCz/cowCudz+mTyxw8aC49ruE8a6EMmgntbWw1Hs9IPBoTFDu8aDwXCpfoML5KmT5hlin3cE5VVxTWASsaj62zATewnJonMaH6VKRIDfaSmDEYkW4oe1SmhUK2poFrJJUdqjSiVg4UdWhIPeecaRYaewH1JXPKYL0QPXA694olhiaC/vNiNEHC+nLgJKKQWjTQFNiWSPWKB1Ef1BAzAL/gUb1UXcqbH+SesGWWBkCiYOkqqycHLgw0KpaZMkWi6+JT4aQcNMTZ1wpNTVpPcX5iNkjSDo65N09O55ykdUZil0UpQGIVt7c6kcyC5+tYrusqAv2GTLViu4MmnIhTeqEvvrsJy81hFDZXAHbbKdM6qGBgIrITpowVL44CYalVz5Ec85tJk/5419iI0/MrgccaWbw8JKlXaGj2faI6zEBiz95iPKUCGLEXa0ABx8NI2uiY0HA5jlu627A8u/xCBPjzMQVh3Ir7ZDtKPOYaHcRaNPpDr1rXHtBxoShug+ZrS6ZOy0i8LiZTFNyVu/jGPtzFS2utTt+5JWy73y7011+O44sLrN18FT0kWNvZPp+73zksN5QDOUFX9MuQcM87LPFAOc1xTzBxHCdd4ekAhLnr/6uO6fNdDO5d1uKSyK/pqiEthbprzKbBC+eieSVtpNcTAYTWhdhkpk2WN3qJjvIBCNbo1mzo9MlrqGLvEe9BcqvfTkg/rnrQMv1iWblNXy79JLOARuLl9hZfbO2lWujuNIkCfYEBjgFDKBOCJ2HLfDN2G1+iNrcHtiwUyWqobAapbSyhihn574mCKGU8Iq6e6o7Tp8uYj/OduLvX5nBgSjOBOIomb4nC6Qi1RzHvFF0aWcsPGuGLfB3GEHlLBMKQw+9Ijn50MhjoiALN9cRpbJ92iurpVCgGGOD3c0i96AEBTsfmWkVa6SMoOAGLkQdMf2EtTCyZBaivWYe0lmwCVYd8hmFVQ1iD3eqN1VHW+Xj0GnT9Z3LxYWg+E4l6Z2Z+zezUtOPcxGc8hyx5pic3qBYxCnIM1R50ho9f3GEOXoHqtaJQNEb1UnAbjF26WLuy0KqgCeOHJQT+UJYrmHd87Yp4cZRrvcxIRrOYOzLIYRGNcanTB/tY8IhvWuyElHBcPCinEXVEqYAkgwcficOdB3SU2I/+U71E02Pri5AQtbNQA8pRBtF6uJ0hXgzkbSNrlFUpja4pVjNiV1HPPnPjcS1HbTuDzKeUNo/ne7DQBkPhK/7W+TU/xVuViVhpbX6/e+M6yw39wGhWFsMTKdMczcO7SyXabDkTnQ+HJjIQWXvIcyLAE+6MpArOs38nORUZiOmnCNHaLxkl0kKJr5hQdm9ZoEGGyFHj3tNbMKG2LgjB9dVXvSDgF/qlUod/h1ds19xY3+NLRWr6Ahluhy8Ki38VHN6QkmxJ9jSGhh4NVwZvEyOOvEDwSAXrpWBAY5ZV3frg9RZZvYXW1+LJiZA9PLcrk9TvJObEemWcL/K2Ei84Fs1Cz5wRMVXsLk/+3VQBqWPrECCIFYP4mV/YpfDRKN25nnhtC6bFRrBnNX0+1JrUJhVw87QQtFvfi6i9Qt+004O6VXXgahrKkqeRYEM8HavD4vSrjDpxnArvqcv1Bdtz8bnUYBTliw7GYIFeGdQ1sOYLMm89Yrmd0x7G3pJaeYD5mWhNY2Vm/RpBQBlriToEZavgBZsJX066DOgYQmbSUN1tMudsWdcP9WvI+LXIvV9gR1IN9RLcr40N4xaI+oG8r3mweOzA0shx0tF9KU90WyJ6gUkx1rI5Xt022N4GG6eHJtA5NAydouh2ens0J5gtKuEI2PGNriOmZ0p/lJsGHcwruxpdPLVpqqOPc+hi/xHDmVfvFRFQH39C1nhFnlqwEES+UFEw8m36eKjuKpUY/crW2dywQJFRVNFylU1lau2jQi+kKKknvIxhsXGt+tVqe6kAxNFhM5reWfsRyeu4HOp5WGhKhV+zhkVR9o4kSID71LbGZKWxCR0BeTzbBZVXrcTK/gUNSeP3BMSLXk1o41XonBAbN3pUC2ueuNEvmHSZtB5u8CnGbKehh0pl5ngLeYAoVtfLkkHcaP03Wm6k7UmPuE3qpgAJDlzqmsiH/BSxTBRqIPWS/sG4dTygihERdFyh7qM+btma3RCduBgO4PREoXm1VUkbPmEIBUNkDIIzutvDcOD+e4sSyaWD1G390YTS5aqPbkfgwJoDMpBzdelRjVtezUR22RFJsL9eHkTYLZEXj7RCDYsHAIJR/SrIboQwyjyfufng2+dMQqg2Y1iIOWnzcimvBu4Y5MKEyUfNyzldK5Kdm8EznSQ2kHx0EfX1ydG0woRIcwmQmYk1PmtbH4UIOMBPjVf1XD8lI3nv6G4Q0jZOpT2VMjS2YeTCKukhXAskFtU5dFCq3q6XMUuXK2VeQ496tc/OynIZbefgo/2mu9HSnocO6NmYedvBUVQordRpeLXIk2pdshZnn4p9rNn8ehKkO0+WnLWRiRhACogGeqUit06op4busEIltrGwhPgm+ood1QMs942Xo7lSiSqma9Y9Kzz1pByvpQMYGo6lS9k5Y4tyvp05LI3h1JNldTF0XyIApseYX9CU7QjWl1Edc0aJSh+tU6oNiwoVxL1LmlyptKRcmtXidhAM17g/aJYcKh6qykpfZyRYP5WF0imtVk3JZzcFxpMeF4AkPSbU+pQRkIszLsydZj4iFiwLxl8IsRaTGIL8Tt0SwNSy+FgVo71NzsFOvrAqF4/YRH/b0GedX9LJiGQc+lMfKQjhqUOUPug8RcU2uGRUgcnPT3WODoozmJnAReX3/aVVjmnqYgD5A22iXTaW75a1btL7NvcddeeeuFO8H1akpabR8SqeVSptrmeZdpeupqLQauPtc1ltwbYIHfOz3qBQHD7rByQzNegNjt9e5CTabl6p37jzJHcvqseQjQs2wD6l6lsl7IkrRYy9ZRqOoT1Bsdhdm6QyVL74x5k763212Z62hjWAiWhCHQ53ZkIsAGfp0Cc2rFLD4EwCVYDUrBIqUqrGwe7tGQNmAr4ynISgxDflnsuHrWiCR7FBpryAcqQjJ2OWMe1ZA1CacPMhpGJQyEAUUmDdMYdu1cl5Wvkmia2xGCVQkUA15KtlM5TmiJWo4L48WHgOoBdeU7Mf2g0BWVy/L4c+NfinsMNKj46FhaqeApqRzBm27/MMpIt69s848yDry5ZCzfNc0poulyNbppemhjbe65lh2dcTzNgEhc+lzukcu6R9cdQtYJ4cnnl4Tpx0FxmXB13AXqVAp0+1nH/beo3SJvARBhaptMa+inBFQ8S3B/ry2W7cThVg3AAnWiSV0TzGnuwoM4rugkdnY1Kza4n4a90huMkSn7VhtSEWY49w3At29kkU9wTWYbD3ndF5jt4zqwOEWF3EkHB3Y0rJOGijGcEofIDwsQ7COF52WkHjWYOg2aTsRg8dG3jjbrZkn3cT0jkPz/rMeIQ/b6l+ZSK39VxKQHfqSYCkgLAnztItHUZs4tvC1qL36i15l4inoFeIWQtzEKw4YHXheRr+5mI4IfnDhGHYv9V4luASUa1xBZ9EfMKAcdzNM1eBkqSGOfVQNKLOeliRlMuGuLzSge6RfXNi/U65/c2VpNJLGULTYMpcul1aVlWdPzX2pienI3odz1luaduG46DP6/y1SsHsZIjiQRDqRyvrIMmv5IidIwOE+5GMQZTchY83ZVcchRqD5ApYBcNVe1q9a+nhGv90gfdiz1vUTtlqeB5tz0nIADHCURWO+pbr1e65S1b6YuPacNovmNlsWBALVjrPcOjx403ouEgiAv3Gz5wV6YBmYjYSUlYnY7nipWEOPfhBtxTblmGaxuMLtx9mzPdkFMyGk1JGLJ4E5KAwk2tXMzg6kzdHyr8jlyJ/ZocuajA9nzYkNuKE9IB2g4yskF4Kq060YyDDV+Z0UC9DUdYL5oilAtw906eJ2dwJJ689obLA4TSsYeBDEVFEwbT4uj0t6mMuMuzCjtRsADbdjq85QVefUXIfTAIhc9r7oS0FStxl9rk/Mq+N/akZLrDXLekNWfUptOAsyt+mK3rhp7AL8ip0sXti4t6CQjwlOwLoogvJCA+GTs+QUocVQ2IbfT/JocPnhaYkCyKixvg1e3ndsgx8jKdCWh/aITkGXc/xV9Tju8YRNGu7ELuptQbWKIp98zmsPh8cT9Ib3Vrnrq/UcFO6c/YwKj5iOytHYl7dQsjH/IE0AyA2lYbuJ8kYeEJRDV2sUQHl4GobCKyY5FJUPpiBrotKDS4tlvaoEVrR+Hyy2RWRIpqtp1enazGxxm6O2Rv7uN0dbZiA9b+sWZehKrFt4cIKFtRC5AnYEoQJ8fTT+GCksWZhSLkccuvTieMMIQ576sY9aZa9UPiVBc7LSTf3iu0dy+OymLq1gi+LpKzxC665BHSsGiU220cPQxF7qPOvrIbF0WRe1I4cKXYGyYDN8ZX1S4y70zo8nka3SRlMaplzI8oblLUPMtRF9r7YkHew+e0ypcOs2idOsRlrN/iZwgBUYY6ZLhw2sjwm4e1aHVmOMignHhun0a+mLEPah92pLnSc1Rp9YT2mhd67yq9rdH/zUvEU/YsFwekBJ2sZWmASpXfbpnyngkFnObZfvkupg/OwrPAw3/Y0DGThw9nUuF5dYTlKTCSQjFI4qQG9+JBtYChxC9AsOlWFRtnxsjZZTTFeruOcXd5AyL+MwnCYnFKQkL5BtMEzLCARNGino3rO0dGMtqbV6wpidmi1x+VhzOf2UAlmecQj3AslTnOoaHFXvaQeJu20PShjovVy4EZ6otB1PddOR6EuO63AXLcwyRdNq1i5rmZxRrb5pmc5swLa28qQ9VBVAzPASssSSNakgabj4dPeGzsbBsOOkfRoP27du2zqMpyW0tBo3fWX3nrceEDxiHRg4QXIdUEx7jbhbWPhFmWmLRV6PhLnoOEd09nmy19IZqYvzZt3uEFFpM28n9dWOd67a8U1zFAqO6pic9khoR4vj81gA+Rp5CQaEMcL51Q84K1KlFOggwCmavRahzBY+aXJYJF6HeKcx6llOMYJAnY+lx6GeMNcN4Opq9tGjT1B49hbQZggSpMMzukd7pnB7nkZXKkBeccz6aeV64nzUB95fAhaIrwbJMqaQzlzyl05xad1aYIVaTIXM10SY7rYeDUwEhvT8wskrmvpXKmdJWZ+oUN+WQ0sLim8OWHsDOd4rWUUjlE6NTtEGNzZ25cVnMF1rmfEZ00odhbbQyJiuaNhrLevZx6C7s4rpBKjCeaVuRMhnU1Z/BCIm5RzHZHLGZYIAyRNl8NLV1vMcG1Eq9krEGYeonY3GVTVA7WMpQ4abTLV54n5iSe/hi6x7zZrXNxgJmfxzZCusezQ4SVzX8tzG5EI07KUK4w5W09e3R13H55eBKHYmhih3u/kK1tKeo0PB5LjHc/j0XbIkybGW0mnW8gaAArXYE6i3I+Z/jGkSwk/tTTeBFU2FA3O6BxMtTBbNo7zQCW4pNVkn3TmxXoEliKkqXnjJTzKq4HXq+XCtYDV4hPamwckgA8dV46mc54wMbGZHBi9znr11UpnhBq7dVkoQ1bUZhuMWDH6fsA5JE3zrKJ7TR3LLx/lSb2k5qRd5idGWa2hDixKwnoUXVZh6uPPz9ydoU/1LJPDXU/8lqAs4HHvbtgi5gnkcnefpTF8g08qQ/pEgDOxGhpfR9wZXjSNLg2IQIbTkkkUMm5HySzFYxClA7YQeVQyFGoA7RqSjytBtmPOZSeWyc5mq0S2CLNyYQ9PEbO+Z/uS17NK1rPDwSBJ57O3mTuOj/iflYxwDsAkh5/QraGGhNN8kch8fJX3hQX39Na1OGy4hSTXsdV5p4boj/F7kCh6ek5TPWp0IMzLHDWPafWvc4tZA8RPYxEPe9UyroUJxpnhIs3AFnWqhB4rhbI6zveviM/Plg2IGUYcBTSryeans7EukJcNDUEwe3xv2lrdDD60IupTEn0Kjp4y1DYsMoml05MDnbWMfvkMIQ43IDuzCJ1p2q1WJmFyOo0LyJTKtjAFFWJbn3l3ZxS/wDy5YWsuaI9Hp8wLZJiqA7fLiqSdqa1Ern7GunW17gcL+H1cWgLD+WPa0IRiUK9oGXtcbceGopjpPMrdWY9c6KXEzbQ5Ac4jD6LO2KavA5ABEtELP8tDtCO4Nf2GQosyzcOGFS2cNFGK7l2q7eiyxBFki5IYztRHXcJP3TE8rTOoMV/Do8xxc4MfzHA4w/mojGc0UtKJXtM39MkM1bSAXp9aYGF+dkC2NZoQXOOuyTKc8oTajRkWgkIDLWWA9AWzg/OpPKZ07ZHlUkLIahS8bmImvMEdP3gI5G86LNmF1UAehqu0Zq2YuVW9a0Z6sEH1mDCy1WK85EkGxKcfJ+MWFMYiQJ3+fo6pP5qof2HYe5RGfFhwSxzGryuZ4MxESgkJL6m7vVX5eJW2E8KskakogQ76OtvkSygwXD3fuF8kBqm7ZEupLPQTcYbaX2Hsq5qkb7f2jOmB5EOK73QnuuyCuJ2mWi86IQL8EJ9tplxqwwBoS0+T0OwJWQqP5lQ1/NIzusRYM2uk41UTbJIeI5nXF5cMnJ5Q9LwVjyc33M8bQgrRA5FeNlbTzRneDrg0TEe37jQSX2/e9nu52zOeL1HQppCB5/JYP12jPGwEC7gm47GcXQFLibS1vHyWZL7WLazfrGnIvFJ2qvEeeZo+s55yZUTEbjk4hKBvlxTGri9J8yRPAu5hnZaB47mLAD/Pgc9/L/V8b3m9/S84dmzwqz7EY9/xhwUaEb1/lhZBfEYbSAK23Xnux2oUZuzYwjCe2K011ycCdxfqLdP7zMj23Vd7ZCJ8iS+6kkkvBJg65ApXLJhRf/s+Pir3yr/y/LY9OpHj+DrmI633eluHay6uVAgcOihHiiupSX6BEk706NyNjzE4IkdOENA/dDgqPM/xScXm+SWAJj7N5gffPPgnx8n+iCt4Iumu0JicyKn84iSoRnY3ibtz3FhcLxwYdsjAzdQlJzlwCsKNLzau4K7A3KD59W1ujvucyz3+txy7qLJkheA9OFxfH97jf1Hf/u+x/3vs/7fHMGRzuU/hLmyiBu6tkw8yEGinTzgzvkTxVikX0ULSOO7cTqwem1RY9/J+pvaTxvBHyAhGAMldwDpc/ZqvFvKIdPG4r6aOIkJTNLnmdQP3KmZuxg3Nyn685/7syQmIdP/OY5sUUZwqoHBnYz2vs9e+iEU6MMhfWBPJnb1IIyPHPU5zwgVXiyDAX3zVOrIc5N04ruvYBjSqW+53oWPND1TJVuH1wp3zdNLAh0tVTkWZ4ntPxzMbvWPC9dp+iIa1Rff2vdH9hDkWQqf9o1rzcRjQ4cxan4WVpfOiflYhIjZbPnupa9Tp30Vxu/Ia3i4r1saoGVBi68w4Veem+V7kjZIDHH9dgIC0zA6ajInjWLnCSl6gqcDa+fAOgPwR0ESxvcPoMbs33DyvXy0H12KJXKth8Y5U7eo9jk5jVZER35tkvB0iLwACK5X8+1XcOI5OKdbH1mCcfUBMJjRinxMLZXQeEI3yTrpYV19wbw7ruJ4RNKRRqmuLjbwvbonGVUeGYtA7auRohjlv/f6W5Pjawp1MVOvC/zgkXcSGQGKebKdZs/juT5IrM9e7yJsKXORPED2a/TPoVkmYKsVwOtJ2a36MT5Jg/b0KpbBDolBpTPNV1I4p1vYcUG2yrhToNZaO9HyQy+KDVO5oWpy6EVRYpULSD7rfEhzMJ+55wjQSUbIez0Z5DXSaLUE07U8mh0u9Zsfr3HGZbjwV6QsGdGffwYfx+KGVoBilyEQNc61/ClwhjaPenM/OxGn2mHrVhaXtzLCtaMaQJxPdkchSYD3HuZ9oeiQj3GgKd5jnFyYxhe1tKVCe03t5dIO6KnTu8iMgOBc2FcYUY2rlHQ4EluWqM9FwTTjBZByQ3gwwnO1pSp4y435eh8wTxwPLKZOMiDPlanua+iqgUBt0eLcdYe+ObhNJpiPE9FA0b0AOWD5DuQixuMfpwoWJcidQL/KHwVPR1PfplGYx4qMU+jEI8jR9AOkMfRhWwZb3/iTVapfoNJqhuHeux32bNKH+2OxIZJPx6CEvoQ5xto0Ybm/9YkMWh2r8RiSMNLMPab5ynInq0ohEmtcjyEcPg39vuDVzKS8XIE6JI70zeoNNKuB4Y8u7pbd/NinjLMU1+Q5XpDRhv5fnebyvvQYlTqDCaBOJ2aEK3Va5IuhU4dFaF1uXKB30Hfk6775oR9Ehapbnw2gE8dA5JLS1Oc+UqRCa50en/HmWYBDlwcQE7iN/4p7yNFg+6esWARZ7cJeLw0MuL78UpAMWoQ97lkc06hE2YyP6fGXanmrTnAZSy6Tf9StZDuM81oOvUkGuIFSa9HC5YvMiabs9oxufrcEyfsJw8Ud2aeMsZqe7aZJOGs/Zc/L1MeYTVxQsxahXWTDUN8BxJQ0STycfH6sygUjlK44v67voNDYd8k9FCPy6daIPoFSSmpJ5cRUF7xNN3sBm4+MuX5aS86Cu7V+veXGvr5t9Q2dimtsGCB7y+tYxzKpDu8J1NHl1kaSWtxOJYG2RN1e6OkJTszpvxdUSpdicnlC7QG0QNY9nZARqVbw2I88dy2KphVLmkQoovxekC48stlk3ezeFc/1m86DxYthlDWd8BGtwGiE+1aTnKHdsmmbwEXDeeggzSHt3XeQ3EGbX0vr0nu33JMlVWox19LsUm/no/II1gW3DB1RtHGTWbPZO0DRqxSsejKDHLB6k9cxOKBuScF1HJM9khzo8/SovZMsa+D7pe3UWrAmYxSKqusJ9Pk1MEsz13B6k79b6A0aLOginHzsT88EQsjpDbHwVBUCctjn5GmXnhzp5LUaGcMMEFuvENLD+ABc7RPazN3/dsxi/fzsN3SO0+1JcP+xh0NKrHxW9bXCFG3dYbLTZGk+Db8pl07qULsM9ZXWEZiy7jmNTpmtbkpqdSpkZTJXtRaOX4xSbmsD1TG/A8zUcFtJ4ErnMH5O1s6ynwTnToylUizDSq3lPYjmU9gdvnq+NUS/99TVUg/q6SVYVJuOavjtMHwOX85CJySsTpXQ6TbmGw3eZi/jrAnSQtO0XLrpVzxfn/rdzoYgXJ71f++vM3z91Ust9wZ7IwqPS9Zrgm63JtLob1roprG4wSsWtP88+1sfiHdJAXOGyhLRhr6cvZSUbd6q/i3wSZMgWcA8egOg90P+fYHrz6y5uF8LGwqZftQN6mHcs7hFwsGh1Yv6mChvqpTLIwd6NWw+JQ2ylCpt4cOQIoxzt4YjbUn9Ka8rTsdyZE0vr+dKg9+XAagRnvhMkvH3YICWHi5x/v+f+p/ZqXgprc0Xe6UlmeKhC0d9h9N4CLG3DYxpVomyYx8XYGpvgIq71R29pU9Jw0qx83IKKkavafjbqu593tEaiuySKNUYgMVT0oyiiVJcGn3rQ6lg0rDgxVq8iaTL5a/Cp/b4irQDpQ+SZoMfkIBjWnWByLXyv8ItyxFOSMBbQlCyn1CiOZ+VyOdmEOCUsZpcGBHSrnk/Mg1U4EJ5z2vYgQzK+JmKrTs2BeiaYp3AuKfPdkWmXBdAvXXZmbPyUHLiB98EcPKx7qxxet+U0AZ+yW1bgrSAUJXXFiQQE+OyO5kk25UgwCRI7NIStdKGPrq9Ss/dkm06X0fls5DbzIO6RKaATBBCM4PNEqSdG7vgFbjH62cTi1JH/XU0N+50gUn9Eh9ojCcYF1niAqWiWFc1nrcZGb6h9WDOfuAvewC0GOM4GY6g5VOo8IoretXIB1FMK71gy3A79AkIPUE/x/eJuAjdaNNwOG8Qf6rmiwx5O8ClD+GAHTIzN2qDcgCSwegWTvfnaAYMhXI6SHx9OySC4uDMpjbLovu8oRWuyXCuAbqni5UX1Ac2SHvZ+1krWhCFJ9SwtUZ/d9VmcrxMtnSytNu0s5aY8fj+Psi7RvfHVcTwPewqkfRmvb8ukiG5adekCmR+tvonFmwbpEqrV3TelTMnNtkRjiINNafVV84QBKQkeA0njABdmIfXVtKZE6XkBYB0tkIFS6EYVxkAAeoM95mYJcInC+WJLfPBRxa5eN1dyPuzYV2SMimvslC/Mca8VpwdxrUh4PE8YvQqK61FsRsdm2ldY7Imv5yAsy3JXYpZ46hJt/ShY1Yod9DzBMO6C37PkeN4/rFpNPqinOhW5lH1ymYXuete5q9esoXmIbT7SJhvpUpmqzh3Lh6Ya09UkfDSOZrgSMukCHcsWyanphKkXMD/KEKeRC33IAFzFYI8TZJ/wWuGBA37cjKIj5UrjNJ9yCPRy3kTki3JJ4zodomHMfFqtsHUglssbxMSC7c3y2VrBt+dOKi7cNLPgMa4Ri1miUWrKO3BOqTzJCfXmNqHadDjC5zql4yLBlUBxCQIawS6i4jYqHpdupgIRYDVgqgBrODwRhCYMkWCLH1TL6ZL0Fga1+GzOcRTI3oPDPtgeqgy4cvP9JQaDbnVIOh4K96JmqbQodAZsmh2K4CTRNJZflden87JQeMQAtuGWTepUX7s8cb9x9HaW8VgfcZadF8ii3NYzGk+HOHcCtgqfMEZIEGWAloAfsgZ0akWhFX2KeD5jEbAEokYzX6ZHTwYESEVRg1AvdZgFCpU7w/N9e4sDznvcyb1eXfcC/OhdAL3SgpnCHRJ4C+j26/FGo0UUUgPPfVRelyF4xi5gcHBxoJVIOnBBsENOw50FVMpObu/mBdKW4P1FrlhRRR+efHnBOA0oeC7bv9F4HgD3vHPxKK3+qIjunM8hkMiY+uACvrjCvHyV5fKFfHQnmQW1CmSflYGzUwM7YTYKGNxsIjmNmhfJ0po4xA/g04Odm6vnzpmL4g7orGvIao1LzpA6GB3OLt5TS00CRw90MM9yCvjJchKEIZaXV4E7TemNsyRfeGA+Aw3bsz8t8ZyxAcbUCBT8sAy0zr4nx8HIh97x3O3JqMY2XS5pZhj6ssqSRHsrjdIsbcDnXeGuxuO0CuLKAY8FOmuMsO3OSWl2bRTB6QqrOof3Nmpv2ndwmoGP9eAMUcwsY0LQ5mciTVErNPHxLqloOCGAo0Et42OaWH5AcmzTGISrGfcRwiUi7zb2+Xp6qNfLbl4XIz1QQyG7ZSU+QUBN2Fg7AFdnt5dMxADZkc6a+rNfLfjs/M/je4Jj1GdhRoXP6lQoj9DDAGUeNQyjyAPXtrB+cPqT7HacNc2nvUKh5nXFCte/5IEBjFu3iFU9Zm2JG1IoKt3zraoHGMulPHVNeO567M/peoGCcFUDDEBHC0saKHyWtpoIPZE6Q0whLoPu3O0xDmO+AwrKSWIABBqk74B2r/jQAJxdRnv2FzR+Jnf5vcPNeo0D0slgziDkmPcYc03BQF8v3nKNJ+OJ48OIFfdnIFCBNwANH8Gnq9fmCR/7A5lyxhYcW+RzXlrB6b93GBAvyhkKihkucFvgi//6Xgf4SA1Fkig+AMK8AMIBR0QvC63FdNhTJ9ysxKs82qFxIUFhuN8qh83btj1mOAo8TrPvcAFQurSQ4/e200bQ+/OBAVmLAvgy0fT4hOr5IIBXs/qXbrNOKBDlFxGP+Lqug+fqna8UFQjzHjnpAM4fnQD1odgpXC3MaQZILmWQFW+e2BahNdOMlvjegAz6vAGOolPTw0vz8SF8PcS9YNF9bs5ci8ZgIBFoovFpX1/y6PED33xQ+hLFTsKwLLl9jcPgLpqHUZ7JTCYD+GdPFLokC7wOJUoejybnTqFk1dHcHCEMZlza77FvEJcSosfdwyMqvcNCSY42Sa/GfYNp/IARW2igMf1NQwJCEC/RCyfQyBs9GofwuSyRDv9mZjUrjEsfz9iL4DSaCJabIx61+pOTptQOxPN+wo1KBMkjRKbziAA8vTpSU30nrYUASvMctDe17vWgaA9PtCrndtwXC1t2N5bQuUYKylHhxh2C905VkARE4FONU00SeHenWu8r/4C1yG8a+0XeYZ0Sfj8OoLj/jmN8d7XpjzihYGFn/Ss3h9VbJ8w4gbiYko0owZFbt8qSLaCmmVU7yUAlL2JyyWkzjLlOu+SQj5wVrz2FatHW6KkVN67QI0lrYHX1+0mvv/cU2L/12PHh74yS38/rWZNZroEeh9pnO9tTM0ORf0bDUnaRbtTcHRO4a6RVShMOjhliUawV0A9hPXsNke7WHf5b2Lv58Zmrdals5HoSsS7a0FbX7IXFY/v9/r/DTn9+LFEooShUQFNqm3+4Yl+t+xDLaOinrQqkzMA2+Ygv+wpJKLcnSrMUl+I5Ao7jgGPkMT2IxDgyc7cVgBn7HSUBudYl7foWRqA8AFB8f4kBc/1sovuImp5gmy8i/cSrwYbZffA+1QiVyIGUyPPsCpK5B3diYsjB0E6oIFABBJoi697q5yFiDgMp/GO17+H4FEqeM9w24sCl1ehTranFh6sATgi1G0Lr/agH9IcfD6gewyzYXeATiCLg7a3il59dHK/NeH0IB+S+sbhPzw+kvXaQElEbxiKgBMZa7qc1m+vKAhKsvhsLUuXaTbUZqAqjLQFQAZS1yfTEtD5LnAH+/yo0inf4bRdDGOIHBhrTfKjNqiKrUCqbUwFGub8ej0oVrG57dk9gRQPPVm8egcbwwIBj3V99zQRJif1UBQe7srSGXJ6D+p5VL89nCjogGNOsZXm+IE8mMT59h3zpYwIVPjwQebAvDwzWJUzfkOHWi8V6TMGxiBt1ZwHOt3Di5HJdwL/laphmHj0roCQ/T86awQD4iopRNkAB1HmQpR8aeDRb3ZkOm3SxRqAOA/3P1cnERp6K5kN6fE0JLGmH2LrgGhDNz6ZPphN+G0OQoXgINDeFeboZJR/MDb6fwMsTNEwGV5ldeZbDhAOcpabDsWb3Zd6ed1ksalN49Ddb5CHi1m8LKGMyrQgGipTGDka0xFkXrnNMrI+DpC7R36W2AGhUOx/5G8G61HnL7iA9KRUWKRI8Ye2BWIGkybMwwDbU0GjtXsHGcPZJc+AYLrwLAvwWOXq4wJ0xMDPnlAs0jGqDodUDoV/DNwR+YlER+B1ZsDZuc8BlROFEzTS0u66iIqDrh35f6RSI+aK2yWcXgj6auXyFtSF/MKl+9pHafvriq/r48sZXW2cSF356LfMxoboXrJpX23GAJkByA7aNxgQdZK927Ihn4l0t6dXDDE/VGwhynZtYC2HT6rBr/T37BE6XQCvCrztrZBAiPfy+MGPF1nzCbF0BqoPN4IgRADoE9D7FbNvdLp4S35QzPi5UrleAQUIbL95ZANv1LgzO+LNBMIY17jwHAk/UffH9lNu2uoa+Xy+D56FkX6+demAMLxSEMbZBXq4aCpM/RBX1jczsg4gOBm7IB+rnl8/+Ox4ZvO/QxXCQTQFSrxq8F4PNJcGl1+ulGh7WDXl2ql0r0BljyBf4UG9oqyPcG2C6rwdcD0Nni6aHdtf7/ocWOb+0CKXFh0/0jOTUQ30hw8XT4hnDHXBvTQ/ktwV5m+/h19iVjLofQiommkH7E82y6HCLCc+h3cbxU4/S+suCAe6CXNTCJ75HC6Bw/4Wq4n6aDtuWbdT2WWvtOzWiTfzorjJFgejwvHWhTjpkPkwQ8iOdSu7P+xlCNhWwaZYBuj1/dhPD/b/dJFYTG7SybrRO1xlAP+GfTYLtg5p9oAwHv4V7rFZRhPV4t73UZ6jlgJUgOacNReGPwjYpCEEgeDRRiQHiCfWAT72GIUwWP8pMQDR9bH64kgqkYDcPeaUID6NjHPjNWzTL0iPRqV/fsABdga7gjbqBnq+sz6Q3MNHH5jltirrtDxWzyl+8jDfLslnzYKXgd3TRUEYkLnSAQTC0NabWluUi5Ml1LBAvgdHqDR6RpoF1IsVmgMOmKJwIkPjy8kRJpnl8rXoxka5nUPjc80CsGXZL8xIQmsFsQx+o6TMJbv719e6O+6gZQApgyxEazdtS7BnbO6RFORvgtY3+Xc0Rm7e2YbBG/pRFdlp5avLIzmnOeNDSDwBetQ3XfSdflMspTNYAJWvY36FbzCj2sdad7y1+od8uZBbsE6AdQKAGms/3WTe7GfyxxNZBur0SxnqmP/MMqJgRrefV80K/hg4A5CZ9uWQj/B4QGwFi/yzX1dPXFoXPz+YpjpNBGs+5+/mGwj6lcJ9pVg3oItrOXf7Jc34HNAaUQeN5nmxArfG8rHmWnd6CX4pagWu95xxHbLSgmXh5sTaZYCmLMllH3IHDzR4sezhPxhSBVGrTfPUHAsJRj8RwuSGLewSn+hOLTiqt25YN7o1joMn9KsRpw/hP4/+w915Nr2JL2uCvmXu8uQQhQIBwwt9hhfDe/fpZi111+kx3fzMx0afHRHRFVW30bl5hVprnycyVuW5Nz3uwZJjHNV32r2hrFm9E75hS0fTgFjq0UPMaMdVoe5LBOL0HGsZkrPb2e96sD+vdg5Egi0LgeXSkMtjIC8pYeJd36inAG2f8lqQHPUCLgecpuwDbInkjligdXOc0eR5LSH9fhgCLOIP+DuiMQKHhjogYkgVgOWhqCoKAzZkcMAXfHdXseOkw71JsOBUXE0JZWN5e0JabDW3TWQ+vJ9pDEcWfvl0lwd8g1tpzJBoS6D1a3OFeAWeBl3n1C47dKM9wahI6eLc50kBDVzUZLanRC9eT7Hf1Okk5poHPS3yKtbEyP7dpcIHp1eJH/Qo16wUu+T2+gbyDT/ZTeL8e/+q6if/wd+CqIjtfcB2gbyu0qB8tWNRRwhxf+0G4P0Ca8YIPbb1uTRo//1ZPIqApV/xdT7JFzILoSvjrV82MY43jHt8lfmrSTTH+H64ixM72sQuM4rwvF+8gMQCc6CYZsGQ8AvcMwEg4GtUUZw+Yr4K5o+f5vnRUqbYk44EQ/yhYAyNu5HNWejX/AWS4ApLBbuvXTjn5MuLnn5XLBKB43V+f/5trX/7p73oP5YGqvzuHGr/9m0dUO19o45g7h2TXWjbJ3GP54Lwg23pLOADGHqVfTVTuRFbPRVV//tjfs0HxOP28np6P4Ul59MA0E6EXs2zeOVBrYaZkRjfWGKcJm2AmA53WtznR5w/6HD0pdZQiM8+z3UFbW0cUOev18Dczz2EqEweubkNHLC+a1CwRY9k2VerHx+/eAtIQGIZ9BplZ/Y8KzNy4ldGZyo+/crgYtvjJ4q9Au+rR4fYnn2XgSivkObFuBjPQvs4st3P7qsvTkt7eDyENr9ZI2MksgFEL2bocgHf0KvRVtzABngemdrjzHhdr+vaLHLC/wuU57QEQGryoLhxWFCH/5IqONWXWIBle6ndNtqckjOOhOS7qJTVlTOuVLGgf8t9U1qlRV7QuS2DUt2kXz1lRGIXqnlQH/4PidEkSPlGtnzHoeiBGh6wOwpoo8ie+zDcGsCbiA+BtDJUz4BrcvEIyml0vu4HRVRmnsxmn2JhF2cwLPKwLEDP14hcC7UYM01UopYoQ73m7YTqdzrJuIZ9MxiJZxp7lcZC0AzNMdg9sbgkcM5kNPvpxBzUfP/JbXY7zPDGKjKJk/F00YgMOIGdGtf4N8WAE9DYXGD5CCPBv7KOzi32JOnb78ywTYAAGZcLeZNmdKYsyXJZxrP4r8wIRGT6RQ5QjlAGRI6CNajPQ52a1MCKvoj42khnMNEsVv4eKDwja51lyNuA3R1QDwrt2bntuxjRr3P7J1OmuHa5+/ahSi9sqH0/kdyb3JBXSGtipYt2Mug2CJIrSybiW2JCdlTnRu0vQ3iO8X3Cx5o5ru0LSUUCvgEKA4vbH25E9a7UBgv1DIwz1brWriT/8Y+0M60l5Mnkr9lE0cLuNQ1xJpSCHZY2AiI/kPgY+OyG8k3Lx27u7q3w56YReClUdF/dyZPU9cS4gTpt9U0a738Ki2oW836Z6vn5Wfbc3+TCZIT++14pcznBaihyMqNpJSQqeJV4jmK05f+vGPsgpyZkJEb/Ptzgu/5TbONwQgEPydteQZbcAecvVQXSjeKN62oPudDvGgiX/XikR0Vy5q8qXL1KRKMuNOMRxk+e57xkTjIb7LOnJ9jfEVKHSDWB5vN5ZR8EeeyR8uwqA1e1f8Tv91t3h6WoiNtl7Dxit1l7DQl4OgeEnftGXkwGyR63LdGjNSVFTcfpdv9mnKFXsu1MbGO/kk2j1gX8ff/a707tvQZ9sNo7qFVHzfPd9pXFWbjz0gtU6wVLhaP7VPxKH5P9VzP/XaRWGiJQJJJpNBYYK+6K77hhUHFOs9+eUBLA1uGWQyQEhm3F9SrR5A+97/H52VKtw0S916vWSzh7QybyTJOxv1H9b27OvddHRmh/uwN6/I4YC+H+49tN+Lg5Tvj5PSYVYJ1y1L3EXzuc56rm+ZpLBAYvKx+Tj2rynVrDyaPt00pRfC1ZXn08/qHELHRykAhe5thkpfdiaPGcmB7KHt0w5AUWUlgenmh42eddwRQu2OtcyHADXLtM5WAOwySjFZgWlqzEOZKsmfZiA16XrT4Xd8AvbV/3JmNRAoybPVizJ4F8UwQrbxeRCn1f+tMEAkkY8BPcJuIMXz9KD7za80Whvwy+qoCij6k9PKT/oLrRGcsWwekwsKnluvnO+YSiKH6t7ibD5paceK0KzCbN9X7plPSrU7s9M/dZxQSYJ6tHuS9DI4iU5qPJBvv5Gu1qPJyueTDjqtV4TAT9VMAiKUuWEUgSVGT/rD6uA+lelCszDu+0HdgLX2m2hz8UKDnhDcKto656pIUr3YlCkC3gISuM4Pi7ANId3XMTIAK+ZdGyyiMIYHegdgRMhJR32peUztZIoqiiJXKJYmqbbaWE2uvxjLjt7+Twbm1w7B80SgGMgWOappYhzGOefzgtnR/gjGlhMklmfEIo7FPpoF59m83JnMrc+3tUzNuUVXVDSuSUQRrj96n8V6YdE/oBxKoYiXqlQY+H7KeMAZORRFHeP8j9g8oY4OXtPZfWO/7M0W6IDIDbPtGAZ6tP9YEscz/5IvWSi6Oz+nrybsGn4fiVvMV0Ay5iA9Sfv/rjd7k79JIb64ztZbBpjRV/pYsQXVwiRyScNHk9p9wbe6If6inSS5J323gY1d/jTXqZgMwsPM6u9AGtKQ5JOYwy8r2bPo7t0Avx/87dgGtHC3GgiTwqzvfJtaa/IXYC8xltG0+Rdl4b3/WXe/ekniqrTyVsctflssMPAJkS2SAar4iALsLYwulGXofq6k0DQXe6Q/VUnzJ45PeU3WZq6XpYCORMZvxCfWJNNSwax2Qh7nwbgJtT6ttERA63dG+o57rPAogAoipgI4XLI4bYvhk9l7hMmqyj4ACO+ADp8PgQOoOLv/l/4nHHQZEA7WnxCBR+Ur/L2yCpL1EgOuSGM6FFZSB0pi7+6AYwjwNME5gF+bly7XlO4HevOHG3m26jfOCW1KOBcjrUL3JCGQ8xxrycA6w8eVgB9rfBf9Vn61TwhKOnm9IgDe9joTbJk1cw+BuMLxNylpRhK87bRCKUDQf3uQS7DLCt6YaaMtO/9B5aCHWpU9CWq9kwrewVViJnDM/9aMbLiz/ZBfRfTwNMtRkbkv+cx1prv9W2BlqnYTNe9S6ovRuAsEx9/n3xE/cnDKm+iYNdx6iym5ohUNJ4NYHxg9gB1zQlFM7rQ9hxWX/qTUsN9w3kCowcppO/AcndNw6YFjv8qsIA5lHIauMQimFqGJamo6yhEfBwJEzAMrFIyCIh/5yIH7NUBXGGbumvE+G8oX3Sl/4EK2zmOQ0+mWLz4kz/K3TbPd5yqmJZlWUe6uUiSAigyXHxsQDLt4+OBomleew7qOMKe2uM1HERtZ9kCK9actl8C7bdXPzbLl/iQ8Wu3CnTKNMvHcV5giwDtEm+B9URPnFp3Le12gRenP0FraM26qa7dm3DAsS7ianbtXdmJbWYHkMF6ZAXc9Cky6HUzgWnF8e4f4CcfFr3dAIMK4FfImK+hbH6S6a3661EBLIGKrHQ3B/hzPWiWpxajKCqZ2afPf1YufCOsYKLjOUSTHt2dJr/Mn+/XHuPYjIvXApYG3tgImzfPNCnYMbECtXSeOnhE7O5k8JRHahrLFEtGFl1RgsjgVvZR02iqP8I5QEkUx8s2fyrfngujgeoJmh6/SUKfh1ASjK/dMw3iIAbn0le0k/MVzbjyzYXo+5y+siCa3TzDGxsbH0+urmNyHJCNosgyCAfxlkMSnU3ATYoUwyD4SA1jLv8IEgAqlH2S37gu4duHkkCT5B1pjCF5yOCXVtDJFe9NMvhpojEMshpvWjA67gF2TVwBxq13GReOp/8IX/UaaCNWQNdy7UbI4FIJl+DtAHcqCQusgwXCBnzo4Bl0tMHCNtEbrx57XTwacIakZmr4jo11XccxpUkqx+ctf++Xc7EZcYc02VwHb6iJwO17FPVXLuKbGrJSPcZQNOB9AHQKlvJPX17DjBkAUBz3jqAJO+ytwpslkQCdaQu73x+WFSo/qSp30l2WvJjacVxgfp8VOVTqsXuGabzKj7IIFAW+IFeCQdgiKVUi52qw3qaZLIN7V4Ll01vmd8fAJ2xHpOnuLl1MI5W3g0lf52fDK8aQ9+YNgzg8z/mOAkvqZae0NOzKC51cPJQkowxm6HXR9jxnwenx+Lviz0swdqviIy8yGP7k9regBxVNF36XsdRAkiQ9dTRLKu+sO7Ze4CRJDTSCMcR/xPwvGga3eTQrgiI1hcyHOyzG5c8zdVr/tQojpzcFinV+2x0Wm4qtw/6EDA2p3FPaqFJLKv4T7wmlxrReWaZjPzuv7VBXSf6/5Nv+k8/1EcSCFVO23D+lRVsO5bvO2hxVb5Yr0V+SA11opo/4Z+c+tY7UVoW+FiR0wSHOK5J6VLpaBrnifcuGsfDiATWE/ck1x9j13PNrvTj+9YRxah5W9f7P5//5/D+f/7s/G0LBqj/h+gHmUsFmyuCvXc+wVRK4lhecqfXfPdjw72Hqfw9Y/XuK4T9P5/17tPs/DydD6X/BdLK/56/+n01yp//p+L823BP998M9//81wPPvMXv/YRbhv3x6K8P+u0mD5L9b63/RpEEW+z9eh/xrTuz/atLgvz//7/v6l00aJP9TcWSff03Y/LfBmuj9E+SfRJP6zwZr/vOccuafJpQTf3/VP38JOKb+6UzmP8j6/0wx/39vijn99zDyv4di4v9xhuN/3xTzv7/4f6Y4/udTHDPG0/PsH2w4EF84NYqp9XhJfV0Kmafrc4ipjiHRcALTQeuo3ilEgxV3+yI/cvSlQTstXB9BfKbheRl6Fe5W/K5dXO6/Dayt4ofH5i/Si0H7E3IEM4wJ9FKr9/g66oKkTPsgfBawEXLZNSTYjDXP83F/pY+H9HxKijtaZsbBY0NzPpwSwp8DPAAOwM8eL055PcTnUwUHHCfW6it1H407ip8xOVaP2rxzgoTm/KLucpQsVnO4xX3Lw+AI2SDMKS5dFVYpshtGMfPbbnjrqUpln3zwZWdTmGxUK9doyWBf1O55iZjUU6kcPOU1VTn1Maoowf0y7+P3ujjsmIIuDKWzHWp99ufr9Q5j0qrCWnlZunSFlmzjsIqPHtV2cJNwC7SfxZo2ovO9fqW4ThpF56JsMR077erIFTH0EzAYQ+sfG5+QKm1dCaPZb2W5Tt4+MOMc0RQVPDYxmiGSjbHUujegL7N4ms7xut+S9NbTV9QmLbOla/DmHxxj8icH7ulD0zSVjJ7RhVORzNm2OEp9lrD68fsUMM3bYDbgeCeS8COZbyI8H+Gnc95KuWBvPAMa3xlJSiRCNd9bW7VXKri8kXfPZGb5y91jSKB6Kj7nQ/cskwoGpq6/3OOUn5LqgTUSEtq1RTuQBcFJuZVDyIu8x0ZRjTOw2geZtSShWT3G5gnWlXpi5KttQI9LUabKw2/mpD4jnY0bc94r742ZnCjLYaJOrjT1CDVenzyNVIKc3vW0UbM7RRSLrSHedeJdEEIryvuWm7dPR3PrP8swsJFM4oORDb5dQLFGzckCSjWaer4Xe9R9dEnS4cC/WigmlPILG/WiO1xRKd4wTqz6Q8DRbwfOjrzpNRQTc5faGfhoGuPiXq3JDnooPq9w4RE0VJSk9adJ1bYha5Dl5f9i6nh14Xptgzph3JTOxGjorv9D+bdbP4+PV43xWg8Ubk8w7hJwfPT4CbJKBA+rUZxn/fM0Qy5WWRLLMK/QfL3AKyuk4+18U+HXT+peKx9fHFSr9h69V4WYHmgohfrvF7YFHWWUfTSf4TtxpNGz1acwp6EmkuW4+JOrZSMJU0x1ReOKdw9jPON4fpaNj7CXmXl/wnOwB2MMc8JrAiPznkj+jgr5M+NPrJSHgpD2IoyrOCzYlnZ3KSqjr+9gTmEXholbCIDHlPi7Sp9Hv+o8mVxFUIyXgn3Z5b2aM/n6a+Xw5hx8biYz+jwxnHt8+UlUh1lv5vaNtjB+2LN7ZXY4tTyBlOEE4PBsx65XBKMDJGaNAWMe6/oy7t4FSPyLnyXdLB61fudMf98hpeXC3nLIaAJ+miTdMVJJmP5OzztKWrbRuphrbUG9UWjECuKAqjTt5cJUQyFLjsApYLmROGo2L0HPVYcXTHXIEurKwnNKfma59KnSOj9dvbMyMlF4VBfBUIppp/uYwM1kMgF/N/pj6d6fftFCPJqxwsEzXGfWQANe4cVJglL/XER3vHL2KuvefPQEKwpW/PdyxqyCb+RTP+j1/cIN4RcCeZgzYcyedxjE1JK6b+LhLbaLpnzDg838S9XkaM75L/ZYyunlv+CSagaRCiXLaE5vmxfuSxoK99tSMB9MsUFSoQvs4s1XMOnu5BOLU86CGSQvuO20iP3dbhSJPL3/UjCPwnAojFQzD70J2L+qCaIo2lhSjwxCJWCuhOyYKCvwkF7Wu46nV9QplXgOO3xyIjEc1ofA9zd85+P2ILqbyo/9ORwXOe+lLlju9906CqX7I9VO466Da3+GQGuA3XvLAkzpwWjj3uveCHegvioLQe899MnBpMLw/TwR6uX1esy74qhbBCw91LC9XoAfREcUW9mAnu+IMvDOw6Jdcm3q158NQ6KzFg1C8Z8nTMPA2tbQGDVssp28+rn0IxL0vzYALLBPBc+cqOjcw6ceb+4RseRp6GGMpJrpY7qvr/HMT7FpJrSFT5z1/R524/nepj0e8OUAXa+sGBhW8E+mPNyGyUiaxp679PjCXYyTSmzNSeaVO7avSnbyF+pPeLH46uCrfqK3T7uOjPQqKeTRudHbl0M6A0vepjyXy+/P+kNT0s28p69wMP17gKU3ZIfcZSvNBwEq9KxHBGOZ7Tt/Oma3YmhQEpYNF+mFcTpMBmJ9jva7z/30VuOM72jCrQR3rPCBboNDb7XcD3zTwxEZTdkYz5l/PARRgpNmpXJOGpuaY7oKQ5mTLETkubgdxs+RrsoDjdl0PHAPzaxnoV1PMmTCN7Fqv7LyGC8UdOLD/fznqprl50LDyIB5JfFR2FAYDc9XMT8RuPwLQ6xwcgiwC+qPM8phLHIKZxWXIzjMWMhlvcKz3T4bjNkzGlzaiYpIiwMU+RBWMeHHr9mE45firNsjwxJGZ9wS6oJZ2edXg9Fx8/f6vqRyzYBZDekgATgozR7fWfuFlHGs4o7oiW+36DI5yj0+UHv+4k87tOqFhRF6+bn36QOP/vGejMSj+T0zG3jfIVbPKTKa+tBfVWcZWcJeazQZCXChoX/3aG5KyxXtVN799EkfrpVM/OLVAW1e/Ekcyy5hqNZ5r1ZPzx2pHz7ET2OVPyl71ktgdGBEGPPHmNn0a2LCVvnFlRdD0bv3hVht2tMAbj2dfrFDJPO0CA2nJPIdZimj+XJZYC61A+lLADp3lo8Hr2AJiT5/jF0PkWKb0edugnt3Lv1t2InpenQxF3f3yexE5PxY8yu0QoW1xyVbf1JMerN3Jajfo/6I+I07iXJQpHv4umuoqpl+firEOmgotrvBn2Is5MWIbRXcItyZDLnxolb5SM++CQXFl7X7/JmnPb2ev4rdNvZxoqSxC92WARvk5DRtrcUbPm59XQx5aO+XZtQ8RDqGLLMEEgQJmk+o91s8uHM8XbKMxf+C3jQsQSBIpqWoJsbs/anOZ91/32inrlOPBhf5Kb0YgI+Cp8XOSZgEQ+QM1Vn9pUfmlcgY9JjLN9PCHSmfVP7rcKbyZvOLjkw+UpasvSyr2/kRfAeNuySVV70Jsy/n/i51aoApPmC7VB71ic5wVNcIG1tX5nmTz18LEP5J8tR2Uvc0A+bM7h7cFWOmTvE5qw/MkLGdjMCRl/y9CxAPxgBfsPxJPj6sBN0nqiPft2/15XGV8K3DDgLAcoUh8XmWjwqviPxE3tF3FPlyzjrFCZHGrM5ntLMZ+VRYqFsS1TvYgzTU3YcTQ3gEmokhz93gfminrwVZRyUHXf66p3rmsDeafalNQ1Z0nsk0sFFoGnHPw5RnfSNRw4io8NC4P/5z0XaM2yu5MlEmgJbOH4xAqh5OvqKasP1WtOS8ofx5TI7r4RSV6mPBANJJCViG4LgIatGj0M9XSssV8QJWFl9Rxu8CAFD5C1mEgMIyk68fYv96peEAhVpXnvbTvrF3ShtO96F2B/u8r7MQjnjqik/4EMa7u09VuJTXox9Y4IV2F9Z4feCAEyuLCx9fwqTKCgLQ/M2VUvBmnFHwYVvyKZBzGv7O9ethvvet83/xk5SAGaP840SSXQOMF5rAXEl1bZS4UVbZaGgdiZP8S0p3FiZ+Xyx+BzH5oXL9LuOxzVtb4XML8GwlooJpMxVnV2MuzVu2FQk3B/on3vKCblY2XBQn66yST1/3Ef7xdS27HoT9BqzhQYcMl6u7YHrK32+oRHG8MP6cydS7q4mbYNvQSevx9gOM1bGSJPjNL8UnIZu9tg1VtnUtfgBQB9+jq4A/iZFXJvVQgfHf+AgHfWfFP5Vzd7s4+jSXe3DPzB8+bJL2p6WT6MC9AyIt6Sv4RiW4JJM7xYMVJbs00ByABULkKGdN7DuHPu347uP131L1VnFy2bahvf3QtWvCwTCSgCdnk7KbnShFyx7Nwur0JNZ6kdF4llULgBTAepWFrwxjWthho/lZVwQRJVTo629sPXZykUu89IZZX1sXcfp0lvNi2sKIGOsX6Twj5KjbsTh85IoEFhV61UMqkL/vTo0zzUMogN9X423A9eFROijYhBYA/6S3r+EL3+FG7sDyQDwjfsqLMtPpm1HEKi108mH0yM+4doC0hJiE5J3lsJTFYBBuCgMgH7n80TGmU4XQDvxXnAFuCjRPlFeGo2d2nzSr4T4n4PbGE1bDpHSWDy494cB8gHW4ENYE+pp9Gs0JIjTzn3AKN9+N1KyMS67shgbn1WIrn6MU4urFDz/SiV5LqTUjJT6A/wPX6TchqdNEqkXcunPAsIl0SDVzGGsvBC1gEdbmuKy2U9U7WyntsTGBaosAZUhq8DTFPpbKc5594OiyH+M+vk+q2zEK79F4ovJu2P346rN7JFqJ/rLNH/lje4QdQOLcXJbmQwd+2XRJnDXy0HG+f8cweFJovi/gt8B54CC0rNeXq78v17J6cMBxPkB0JTi4PW7JfTk6RHGaGxCJsMA5pSnn0MMAlMs9v/d7fL7gwQ7+fD0t7tZw8HXch+M0+P3ggIeewPrCAw78+bXvA3AdcPDnfnl48JxLnn/cB+DPB//kbtz1EO9L/X/+mjGnZ9xbIsjEe5JfWiFIKL8mOffK/AOs06kYtjyL/cnJNHGieqrm2x4D1MHUNSWCKxVMxHDQUp75V4O/6/ZGPLiq9VQI7m4Z+NOFMZ4wJpKHYxZw+yyOd/isyT7le964B2zcdRXfU56ZRhMdrd5q5VJ2v3TIj00XEcDqqMJkht7wTnKM/sXyMq+JSPjRnGH9KsK+/nZMKK3mmcgkug76MktkYj4ldZb0N1/IOBFsq0m94LQM3Lybeb8YgVuyPhfujv2AGBqTkQn6c2C4FqOiQynWDhFrWxHkrWPJjAeQHi0g/iTTLdTuqe0m9b4w4BL5t3k9LOYyzcBtdE2nWYpwThmGHDZ2ups4zX7y5jcBJYoNxgHGjSH/WOqaZdciCtdPI7J5DPjE8lk+WEFifsgnegDNN1Os4KtXmdm5UFBCbmFCugDCj+P7KBGCOiIxlvy2028JpnttGoyhZC2zPdg2HYuJtFFX1LtX9VxLo3F6lu89/TxSR7FdB1aM4PdmUXadL3k6Jgla+0w/EG5l8bsL/LLoWoaBFXOP7TO4qSOXm1AVJG46JLEQJiboqX4G9euJDd93yDVQDtiDIfYPblL3qIu0Vokn5TQu5ejgLVNi9vq9wqQ5Q8GVf4OYRKR2pfn19b5Xv4db9zPf+Kl3DvqnRIhPO9Wpin49C+ODqX+VJiWvUUMNwCcdsBZ44xvw59qCzvl8Sd8cyy+mMsdWm2iawC91JC7YTXE5Z0Omz2mfXwJrnlOcn6p2hZ8OddDrkXb2g9fzqLXcDcKxX6ZOmHksbs1W7Vp9BaO1neehOCc32VqFexg+fGA1E72jzLIS1rKPyS8z6eP0i3uQz+APJrwxWJYCS0yKcbv+3L9XmCI9ihrziPb23nwHFejBqc/SX+m8MWCB0vcQe2zglATgO/DXMflpej2lJ3YZkyGdMIA24Dsigv5ZqvOf6da2WuOu7L5t79c3o0O4z3vLY7T1ohoEtW0VFCw65kmpvDp3CSldiPvF7z+v3ZQyi7yjKSoXXcI+bTnEQ0pMbh8yWoPuY79/hTRqWl3p9TcwNIL09AhJKcrEb53g4+8lyV9+DZTph2Dp6+2F8GmnQtVtiBksIDhLLnZfWpIblJnCDRs9XvtZDWz1oA7un7eTo+rGQOFhf5n2y5IpN1r0tb0MlFYO3HXWtUVUKXpXXMLRsgIZIsocGkbdQcROm366e9Qqw+jDJq4pWaAwpkbRrOE2MvTj2QOsLSSU/ErFZ96Ac5Nn+ZV1t9d+zJe9zVlK5Zu6sUVNfgqAvguHEhonrZ/HnE3SuUF+Wf5w5hkvE2oTlQjX4m0Jb/RHKnyjTycTt3YDQ0ublki7RLgLXWYdi8xG+nmOV/mAlkQLTfAOtMKulJ563jo/SXLSUn64TrsZJbAXilNTBSy/jSNy35RO1TokxR3fgZvnuCSIsZSalghnCi8lE/pwiMQ3vtt7iTVvxKp5BpB4n5dpPmcGWyEDcWY1bqm9+xjbzEeRL5nzEiUWtTayu5vXapTa1wpHVYh9zHmE0a/gZ4f7XKVxfYbTl99dSej7S6wyr6Row8qm1c8dzwhbXjMuqbGDx7DCImOT+H2a8nha8ozzq/lazif7I5JRS4rJU49QTXMjao5CrgISKWlcWH66ddRmFT71V2s8jX46yIUsrb/aUAXC4TpD5tOJ95m67QcMsy8PX4hYeALNuo1L1H3qoGU3V5zEt0X+AJyxaVznGWTsuaPz54u+kuzq9/ZeuXohirdMLVgTR9XXd+dA9N4hy+iWUHDY2BSHRyzmOakJK5SZ7GDIXimMRZZR0bt7MdjH5uFh5aCzfNjPW97Q6nx8FydorK6j0qKrhbo517kq/kR4edRutySflxBVa6YzG8+H+/cVBxVtHGdY1glxHd2wkMxr1vspoSAqiMBxaHVPOy8ph6bjjOFIi7W83eDSciW2r4iuvvO2JzcRqVSBBeGbmIuFrwcfqyllTZ4iU2nLVvBH/JdDanU3RfA/WTuNmwD9sWEf8OePuf3M6ZYDDwq5BVuQGc56yQf1mV8IJKBiGearOX6KpstnVKchMtaJrgy3PnQY5Axvyf9xtf0yM3oVtpWZSEb6ZsdM5EN9quRrw53Hm9UitS5F+Cu0v0KdeG949Ztg1LBFO6mYTdRWGxhCkVm4fS19uCLZEH+Nn8m4jiP3JghjMYa6zbGs+AQYnUysAK1Eojv64FrRup0DRXm73d5DG3zRz/JvP/wA1hrY9ejaCgxZRQL4BaNgVfA+nNR+wi374eeVoPXxHEJVp05YiyCinK7sY1xIfber+IQMn4I9qJ5duxBvoP+fdKixOTxkDTYvX7lZYX5dwqUzLU6DLqbgcEle+2Rl9zwvhMB6G2t3flZOIlc9MChEhlELelU9vZ0mJ7bqMhHb/Oa2MFza/b6m1+ufKceaTXkzAJUvs6rR9wbO+Qm7kqwG/UB/h/Jqvy/BN3Hol6qLyfRyfBvF9We3obifvwmss4ozGxH+rWrl6YqermDptphCh1PHQ6a6Cq+RKJE3oSgqbBnm9hloCzx9LoIT/6E20pwTfaq/d/cgYS9GPsun32tWlHZpBeXd2Q1/TGkWeG37nXSFC7vzlfbnAbVowsPfzyweovPIoM/jqenGpXyaXmtQYzl8pWbvwH1X1VzOdX28gv3g3vCpdF8jadwX7do+DMi2VdMkdFz4+jyCsp8wh4bvgFbayH3U1hlhBSLuSPM6P0loppeHa6/dVYVm+nb2WnD545Hx+5+l2jgRpnR4lbDuQlzTejLKHr3TUf10rYxDJ25ewvI5cRRItbsqw1c0Cik1dXgvGprTOyNv04xgW0Ztwe+omWR/ZkKPqkdKd1eBoes7rqqJ6UPm5U7UK5OLBH8DpJsE2b6wuFcIL/HSbCqz6ys8jgfz+zBfCtvgNr+c/uIFlrNETVcCkt7znTp2mDsu4g7DeymE8XTFcWqWYU23dDBq8q+mzJGJawgc7Swa7hmTcddDt+LOvrzYGvRyfv2R5zSvOh1fCRNKZHDjArg3RsxH9PXIzclVYVwQrk+CbVftN+lCVXSBNIDOHABvGd8mLAPMkKkxTEySbm62cXeLXEeoyh/qusYeyzhjNp1wy8kxqTx4BdkSuKcIaKwCVPlI5YB+tbYx4XcfU0YELvUwnGpgx1CHOqF2yTKCpcEDPNreBrqZjwDmla5yIgFpvzMKiAHj65H/IUhqsPZTpL3vWb5Sejv64rpdNlO32jhvGo84E5cnDBkh5NzhAaaH0rik6Dujs+uX5qGq4MG7wyNmcVNAEIoPu0KoM6BPJXR2UeNyRiHMzswhAt3cKSWDUnkZxz0EfFO/rFszYQbtNbYGhn0pI1Uf6aZr7QIhSr+8zNEv3447K2Hmvs8NH8v5ze7y63r8KGwOjFeaDPupJpppI5G0fsktr5nnOFbjimYUxKQfxhcoqm4UIvzIx/KIX18JTWCkZJBo04OW2mKZ7MZfjnrd+Kfz6A0ZXExv8KkG3B/FzX41WE33Bip5fZ6xzonCPUKZmk08+kE+V0HSkiWbRRG/x5MSWY7exUJmVPvpPmvwbtXHkUpx2jG2+bGvhoZZIyJntLvRAfQ9nC6wBFoV3K456ewYDrfYlGNiPZQZFMb3kJlgpXk/FpZ85yySxnAPXVs47C+FOifTwyRhqzvsbP8nSsV/K0D8UnSCwtlQzUwlgc9iPzRj8BMmMVzoJ6Ck0U4qgXskrO6y+G732ML60TJkccAN0OEVQ5TebQBrUpiz+ijb1nmEw8tk9+CsyBgtTgfqLSHYq6N1q6TeAMnTa7UMbMEnnuIDGyj8b3/Xk9Sv3/RFlpYe50YMw1i61qPxYHRytl5k1rV1rA2Z183VLJuCGJt7iWV+1NmJ2aopGeED06l3F5WaV/G7ywbbmKkwsGkHuSbyMJ6SLu3cO1ReDvu0qTbK24dtBOYzNAiZbhArVy2loki6nh9nhwuW7pQOfM1dYui/7zYPVIQA7nz3L8Fhwi0tgZ1pTOVxT10gZWkB3JHG+q+cvoqSwA3ld+cdPXaFvYN5duGWaP/0u0l8skQcBWdM5Eg2L7ogmZzp8ALfivFLaFDt9rhEcJqJCo0iqVGUoCWSbO4hlNpj836sZsXZdb85ql5YzvW7An7sjI5PRMGaPw9r+NwJ4Q/cE/fXfmyvN6dPTkmKAt+tnId5JcAw2co24+s1B9pe+uwaJSItIEcM5JV/+IRDkgsx1MFjQnLjGKiLOvN2gfAEkwpsbRjmWRln4KoPvTiQE1GaKOH/tPMVZWbWjm3dsp8ykh58G/0HDqso0gRPCb45EYuojvC9P9/PLyz2pzScKNc/Xl1sHhuxxA5Q1t3Cg3zeJg/Bd4PgAw1ykYlM35vwkH+6V15Zd03ZN7tKa0Q/czBMbxoCJXjJlo4v6jCJe1c6KR8Z8frzOqjLKmRZNkRIN1QBDdTOuDo/S/KaxhgppEokeQf+JESy9EXUJpydVcF9Git+aFy5SyQu1Zx2Gm4RjdiusJWXGOOGB5B4gp90NTmYt6PKFiW+zYKFdYM+WwP9h/iDG8ysJx9SXfD1MF4CYqRL9jPF2tGwNxftMNJomoX4q/CyiteWKaFVqOpufiFxSAKmyLQRHVw1KWrH/lhUD1zJbaZSfkzvK5yWlCj9yYtIYD+tKMNVz3BJJIzbZCYzVqNyBhdcAgbV26aljA53sFNSf18WXyt6AUhqWINiA0CvEbeE4Fie/nS6Ip86TbaB42vGn/W1LY5Fe8bB9E2j9rxaMuxXCNKr2vESn9kmf9yRFSiIdU1eMK5iKDupviVpGKShKXp/TePuxd6dxejma2cokwaraaRBgmN11c1YDolKcO+niodxj+gc4K6PLPWX7HF4bHcdNCQo3H8SjtVJ6dkvgIklCHC8pymRfNsDjuRP4MnMVIaSGaVpXSoQaKcZDZA81maizMuy1vYNQxVE9BmaAPaMEleWNqR+J/8sR/c5z1RCWKtWxm67PnItcUt+UcRnLJRzsJXauQ6CO8+pQunNYL+CE6AyzgLcYRKpdQ+HSQd3bGfaCH6zMGzZHoHfyu4Y1+m0EZOVbzPs97jXGBgj4THA+frUDL8X8fu9a+dFlyjtfozO7+uPup3qh7+3Q81NMpUYlEAKfhkVOs/xKI9r9hYtjn5h95nz1j+D6wDWlMvkAN+8CjA/DEYt8SIgRkK7IPwwk1zt1IvYenYY4xWiUTSFmoOaWHwkRLDfw3jnPwIwV3BL3pSQ0Q5dV68cT2fIzZOnLEscg2Zydn+h7eQX9uofmiGGwzmpo5f52Q7YifjTrKO1uC9h7wVGxmR+ZZiNGOxW3HkbGWUhU1jJQpy4oHLUleETOSXUR7cRmqwjeDMz+GfW4Rj13QHAszjRO0FT7E9A4KD4jeOOMbdGdetfZIkJmW/nxts2EYlGw9OlozH0vCGeL4iM8CAbaxx1PIxZ4vxzYVhYPaemuK0K3wSRsBZBSqvfNr5niJQLl1vOnHfwvYxGvGLsCziF1E71u+sHS5vO96ICHrzSrcsvhN4h8mIW5XG4J0DnTg75dEQG0BZdRxqaBd7FdLo9U3Nijs5pIhx9Pv/NZ84vHtLnLvscsOZIhK3YmnNgUaNHTgLFKqa4PggAuYR1twWItD+/p2Vi+cqGPLe01rnO0j2oSY4bdN8MNyT/ejswMmLhox+EvyN677pVZNithchedLbvZ5imrHn/Sdmr6Aw0AFaybVY525PQB2zxPd6VRJ/BjT9N2c1+OgtBgf/SoFhHymgPaOGxnw6wH2YO49Nhyax/4MR+yLJr7kT2hL/eddrTpbIYDQH1lsSEyI+SwpPfVrXC3cEqKeL0W2D0ZGcEmTONPBmXz25v08y7HyR4YnSmA+0Ek37pQoEjHmdeB0C/JKNN8haM29NBQz4HBt88Eygg1R4ryLkYGOB3cfKl3p3UVT+fyOXIUdwAiaYrDx4fCmUob5UN+TE7Uy3T3FD8mMCAxbc8TE4VKn7fYW8L79IetvGoYAc4vqhrfP2RZDaxpphvPnduOkrGNnIgbzmmv7SHb9YMi/TFTm/5Q7GVn78Az3H4blZ8yM4QD1TQANYGaNxl3orABh+kpcpFPvaOYjR3MKKn69XrvQEw+DCoEZ4IKgsxVCI53REVdZTa/QDEL46m8mnaJswqH7HJaZ+NlDx6e5gDK479GrzHSTzD8pjmw9idrN2djRJ01P+0jK7Zijvr9oE+kKXZGP/nPJD2jvEafrnQa3tV9jyhO5J5rTy4eGXF6TCb7Fry3yXE+5f//Zal+YMlnv8hdwUOYJ7nx70TUZMAa2rVX/aeLqXD2J9MIFTJP35QT5zUeWp+f859chgJoIywutc53tG3jB6Px/Nh/V9WAb9eL0u5k2r/d7Jr/7jDx4crbXA3HLgU///QNcXP3TCTxXitt+FZh5rr43QywV9XlqQg7tXH19Iy/vGnhkh3bKqzqOlaXHVxex1x4bVDIDYGvuem9xk9DJfBb3FfmaNkyO6tb1W+oNaTVDb5+EVwkxtXUuJLjx94qreijKg6mIoWdxSx5kJMcv+YBPlBYb6N8Ts7v0qyh9vNoQuh2KljQ2+dMPp0XqkGntraPtvEXgg7GfikeyrG9eApH9V1Glzkqj78nnci5DsDqzgYrvw+PAacwf/Cp6l/0Fq7JQlceLXSv7KCAvKP98hTf2X+hA93/OvWB+FiistVB7YHLz+6XH25PWEJRqnPsDcOmqZx/K1sOqykm/3K7msOdS2wUl9LCQVpNqqeMuSLeHMcUEcA4GCY0TS3/tWz8ovW2wvcmvhUWOr9tZZ/PNXbhxyrmIKNoAXCfUxyAi12NqQb5HdJOPtvDpfB5VNHOr5kgoNlfkdqzZ+H5HhlKBlyCVZW5oHr7WB1sndS2avRmpO28QxhE9NVX6n9qve/5e8h9S+v0PgQnMMWgFIezxCVdsJSnuT3jFwYgTvIT9BgBur37ev34EgjayYpMSNHFO1niOlVBoDhqP764YslNuyjJK5kPk3U9QwFwcL035SM4J+30rxjzYuRxXS2LCpcT+Q9z/UCD9B32aLcRnfOtHpZqmnnygf1R8xtyFSoldi3O35/P2LnFwIaw2ox1g/GcL5ZM0LBoiRozhIcnJgxJOpZA/jl1IpgIY3pADB/vGpBbrLAQzLlY8ED7FmG7pEXSr0QzbKV08zaqOoTybR+sWYqApSNPl7jPxHpW8Oy2EYJ3cGlQjjdAJJDcpuouz8AR/MjGg9lTKbW5gJ1JhlPPIprgVEPVohNm9JCVnd8T/wsPit36V/1JJSHuT77As5s/cEoPmWAIzXLWJpPhJhOvHzwHrB2kYc55oGF/ga/+3KZcA4Nnt5tYPI44YwKzacIAGkVm+gYa2CHX1RPYPZrO9ZMtpHsYFkWrSPpQySQeM205EzoiHCmOfU9Dk7Q+ItESCrvpvSsscIccJqeNpNieSrF3xdGZ9tAqb+91Qu7DiX4DNVDJH7vynTC6LLivMBRlHQtSsLjRerSv7viw05GuXFNFWRqQXaWixTSE9myiWCFAiwyhoDEqD3RtmkaFgze8cXOhBgFiTMzXbZspY/8z4lPfxypLVowpuBk8Uh9gqclGFAvTV5iiDeEQgYvf33qKUEsNVLrRNwzxuAH/dg6R2keQxu14Ucs4RYCt7FdW8TWA+OMwGxrRf305UEzBs9DrYC1aZeC0CiF5wST37cVJwkGKy1/6u/36hQCiNGZVXAuFW2cgO7FErYMcdrpF5enGzY8rKdmx4DSC1wovK/n3jrD8YrbfnxjheEZwxpLFcQWeV4MFLYIQAMtNPLFxeiAQjCmcrVkG1MrPZPwPYTzDJYo+86fme3ecE4GJ+V3OR6QptMCshoMCAVNxKJFWNqZDsLqQooDIwzwGuxTOpNLkuOQQcEWo6aFvPh48hOM1rt3K0gCYfBfvxniWEIXMtfEH3MWJpS9paETJTI0ErZ94Ltx7NXGHUSvCX34LLfOqXGrwMEKcCqJL5d77/doaNBwYZ3pj55FFF4cy8iKPWl2HbT8BdCilYPqxXcXSeqBuKdTjC3SC5Vg181WKI/XJh+MB0Wmq4CKX81BfD/ce3pdCUsxr8TTfhr98q6grOmiKIY170rSVUvXNE2Og+/M2yLPQ4vrLmZiz9jo3scjudIYzlDjPk/SIMe262q1Q86OztYr3OPGGegSoWxFtF3v3V1UBnsizv4VvXuiMBESzRyXk65ofgkuisawY4gZbFgoxMnDIv584+8FJ7REHmq7x3veNuLy4p+7wYi7CPQ7owFEbU4yIylVklvBm5pJ0yNBO5B63lxgH6+svSK2JdKPTm0eHf1RByCJrGYjrmi50L9AM0JgpDBBC4El0SIhKEAGO5MrjySZBgVLMqDnVNwOgzV6FhTm9VclFYZ9+9cj6LZF94H8ViV4s7bW/Paozmc6kPCDTXp9iNG7ZzOCaYB5jLo3yt21W0m6hTm+0Mm1798VWab4LIoF2zZJTw7OF9fExlcN2NB4Dd6trrPkK5crYhYP4VX0v5oWnr0A46/AzH8nDteaC09fQcctW6KPyJlnFAYklzKmEaAj2kA38rASI5h/y8KS6ucJ/PjnWQZ9bvGUFlBMp56ttmCTB7jRZgSLVp/Rm984wlnPI1sXa7HfHAk92yZJGPPcDXF3xSYa83OabmYCe05zjyPf9Koq2gxOEvo8+XQNxAemXyGm1ub0O9KNLb8r7Go9dVrBZoAP7Ua6Rvc4TjwlsFWbsgLgnhTXL3dISAZLyANmGjjgOd07KvDnX4wDmp3APqbitiRA9b1mxrXK1oJTRn4EBPe/NxsKYu9RZOoGZA47qKGXltNtCrRuZ2TFU8vULN1HIrB8aD/TpwmNYSlA7bpnleRHZ7L3AsLZC49+VAe7mHXqWb5sAo+osFUrhuZ7FVhTgom1k2FU8UEjufFnAwZfAB/deVu2pQYxUfJ70SxkHNdpBKbpaOMrj9AQVdZ///QJtrE7guOGgAIbobc18MOCvSQ+mm5yCeslbc2C3opNlAnTWY21mbyuuc8uTQmk7sFWk9oHXTCj1x9WUyKxIhamY9so8MC991cscgpII2nrQbItIMNUz/EEsUlHHcctOR8tg6tbPmJLBRNG8FsXlqYTHNG2yR8bYCWADE173pJY5gQRtiwrhi8pAevxRZMiPnnZh9IudAiW4Rmdicl659LAk9bgST8oHlwLkNOcRNkyLqcAgK/2zomiuszoZ3/HagFIjR+R8wi5TJiy+UG1XMIPyAmHOr2I3OS+AJygtE6xEiF8CYlvgalSYDUyzFyQLHgKiUgN2Qi0+mEAnUvNiBYoMl/0MvSffwIwgYIFvslRyJVTaLugtexRd6dsOW6xSrKT1/n63UnIHHb8/cr6iUk8MPpJrP1k6rU/Z35G23l/WiJvIbTsTTo/rOtat3CGp9OK5Qu29/+DkM72A8wzHH3w4oEFA0gFXEpkZtjrfKYKc2e5RALc06lJ+5nJKq1jd7+Xa4zHUVqA8c2ChWoDOh+OeMrjFcIrIp7lo4+N35faAijAPen6SHxOMVSRHkeic8ifdbHjakVlygsohtatJNm8lYEF0PntiWUiEbOv+clBvHM+3SQTpxcU3vdOvr9wwMCnkTEhLeSf/fEYkjkjWF+TAGuMx4E3xMa68wDcqXQ+jXs7osI2Ra6eHdm0ZpKjt7mCDcYB9+gEsDrQTuZlX5YAappYBh7AJj/GW+rG3qZl1reehM5Nn1dg86qZgnfc5l1gEbJE4zyRj0AfHz2Sm+qP9agHApGtLHcNXNTQi32x6l0WW/1s5iAN794RDeOHSIn18JIfE/8tTzaiGwxdjtQR70k7dPO943aulqBFf47TSK6+Pv2gD3WzXxK+D3jvGNuQ3qXPtRoIWNHg5oNjWzHRylhJYaFs9OTE3vABaoLJL+NaxEPkfK+95//4ACgkJ+yBPgdm50CzygOvn+JGvv8Z/MCLqraLcc4AggI1oocmY0qj5a0317CTH9jjAJ63fqsJc2HPfC5oqBwjhnwLGTo3+e89J5t+D874973HYJEXgBWoJZFzFsbKBupPPyXPoOFAEut6/tAPAVMhH+6hWe4C1PTdttFOpOGrsgmi7/38whzg3Xlhu1usw6sYrfOWG7cX9z/tzni2yuFOIrdw4qQKAAhf5AizWqLYa45l8nzjvIE+2mOLUgvAkpl8P3iOvsD3b6pRlNRGw8Qj7I10ru8dTotJGjYMjKLOx3NiMV3NJzQ3cho4kG3G6MKkw1W8/KS6Y5rwpowB9qbkxysCKK64E7cfzW4GvY/lEqDOwZ24PH/OBXgIuODL5OVrYMiATzAi8KSwnISf7l0yNa7WdkEC5sy8W8g3FLhDjGcsMQtE7I8JgdG36JYgogGW6fFlJO7wlRLuk4TTUkNaDPkG7UJACCHyIXQUxykfwN4IwLlWgt1KAXB+xBK5el2/wI254dp9Bp+WnaE+ywhi4pFemU47T1gNZELFvuei/BnlIBruxjGEqP3doRbHARrsiSzvXTgtly/ssXBU98lEae+GrV4ZQXcqYjyhcUEvlkHC/saNku60fpL1H/J0vDPZRa+Ufp/xlU4qs1R83CQJjXnr1FNwNt/dII9lr7u0ReBge80Q8LF7/WN8O8l3w29W+VP1DF/1+axbNFvxcNEdFw20AfkV4Dq4iVCifM/HMf9wgtgVU5k41r8SdTAL/NervlY3+3a2CCMd27d+/dQHnCLoAppqAx8iXUDmgH/V4H5jgDu1XL+gLvzv1L3XsqtYsC34S3jzCEIICSsk7BtWEsJ7+PqeiVbVOdFxu++50X3aVOyIqtprbwmmyRwjzcghuT2cctQ8uPzx3RvN2TBfmCHZL138LtV5RbYdOoyAB+OQBMylkiTrql73U+52Y0kNjxsI4wJOHdzX4J0WLwzPcuHEUi9X+9GX/ohfMC331ZiSh/CL6SNc/UzBd6sx+az2W3m2HUdkq+H8RMASz+a47hHpKt4bLRQv1qood3QRHowReDLXY0qig/NJT/PPJ4YZVCa9SNK/P0ceJyouZXZkaau+RNdac6OqbCL5ZOrrS4engF32jjl3FkwTtGfMGyHJ45fgc4hCc5g9csYqrMNVd+SznfohvvlwrnH0wtM+xCbDsjv9CQgrLd6jnlH5A3xe098C7UoLBqbqUGEHaBZBXFVyo2+pP8WNCCndEF8WdOZDR95p4cxbQXH5oKdokdsWMTgBUahHfdsH3qfnjBxY6OIXBQfd/IeDm6lOhPJr4KvmkCGoJ3aKvzfhDp5IHDEtIt7NcnlhzSg3n2unOi1d8uExh5DMvkShPuKIgLDDPqxm+vymp/ugLlYPtrNUghv1uP5bXf/Ur4//T8U0/1/9TmlRKdGqC3RaP3hMaOFIkCfSplZJbHSx4c9UODTaNbGpRvAQCjt/fibnTxBjT19Uxv+bmBmbMW3smL5DdpVYCAjFzyQU3OcwFzUAdAdxjEOHUbRyZMAh/oBz6H30lG6EaPVUnkxJ6MYfNajBlIcButQFvTB2zzdrqWrwh76/ZvLz2fjPyB/peEtRbrmkdOYR37k7Z/F0f6m/OUBVy2QKMPAB9OPh/m+j14uF+/tWhmrTGabehjOibC8hbQ2xwS4DcTWijpvFTVkoxQhbXVAaE6HN8gQfDyoLUPAP7ftvzHyJXi8X4m/6OXwpIshcfducy4xTvJo9LuejjoFjhlvUu5FufyyElUnV6K2wMORmvUS74Iq5j/FtFNXKALzIvqPbaaR+RDjp8xI+L4eGb9GwJk92yhmyNkerkxVIIvqjq47sjex281HMA+tKEzp2+XwnDQBl1QtTjbdvXm5aRFIPpYbKa9LoRPCKO9rYKN7vZwEidy53ta9Sw1QzAhGECTgAIcStKe309LGUKxQl0SWsw79RquJLm05nmQ9uLpY/Zc+byLJ9pUCozpHfwUdm5pBDdjo47S47IrbNInPYORkg/L7g+XG+bclXpAzX9xnv256fwOW58SBrqhCTZO/BKJ/cD+tBcVjvSlR8tQZLCnERd5xKzCzCgdAlhBYmN47Yfcr+JZLbq4eiLAsixZQiUAKvNHy1p4ipfiaecWA/Utb4rC9OO907NxsRuH+9HI3Q7PaLz1bOiL3JIxOOPmUQYTAdbxQ1McbspVmxf/ZYvOT+Su40xYNdHnpzP9QG1NM6hJfRY/NPIr2DgQgM9fFtceQcE7O4X2N087AQcc9PiLAkQueXE8yzSCc2+SDuSmlxHH/NHrevQBVqeiGIuBZNFv0nHWZtp75e+m4+s9yqMJgYfk/yXBeR/8Zl0Ce1cWkieyLe9PcVJhO9z13Z9Kfla0L0gaZpG1gmR5OzKmGYz89/0RXXXWO7xfDPEggyMdFksYLrftY0b4EdL/Z929TTFD9Owe4FAnhDK4/osa/V4hzSkGkp+OU0aRNb0V10afgT9M2Dd727TnB59+oXpm+KTB5rHGIaOg5OI5h9jjUMntPvCFAaiLl+4x1OyBeCa9kTObLbfvvuQvqhky0R4IzxVqtNWi7iL3yhhvtN/TTdphdXypAVBfe7SrLb88Dx/LrSmf/NhHALKv11KJu/ZTrhtfKzvysvy5oYkeNQfZwrxHkm1zeZruu+b+t5hArQX38yA3vbsvMxv+oLYwXlWhrJAvlRVrjMaDWobNok7Wk96MBBS7BukOeQ0LW7/UV/EaZ+24/OfXI8DKSWFfchw6x35aW8qwIHo/okTVC11UkfugPYXGMRtWOfLcZJez1ps0NExhXBTKFA96hZKmeD2D3gWdCEKYCzwSdr3+15JwwE8bHp5psck5h3SwBcTCZthxb7sF2gvi9yS1Y/2x07EcaEy5BBeTK06Ivqo+nj3BV8ly2oiL98bBvaLPJ2fwLilJ+EURy5m+pJ8+Zbr54noVW92mHqODW4/de6f28cAygsvkrVK5KWByHM968h3b1Xy6T1wyQCmHlkIy4X+6rlLK+3NdYJAkvVrQnlzxoAI6NShKv8lTcMKzmAqHBv1NP4YdON/8Pl6qdTU4SDpOy751Edy/GtGvjvaAkywjc6YEuF4baWJ97XDDGkZzEdLSEZFdOeafUyq9oagO3z2bTsTsK/l/VsL0lkXI44o46urZtMykm8Ypk5XCxFgqxW+UHuh7jiK5Yo1z2Mzfj9XnlPqBNKioMUInEIeOLB8x6BWkHazVKAHh/qMrJt3TQ/0Xo5mJWA5nsvY95cqw+H7zVOzRzsb5r7PBQJfWJWM20XVYMPrjV7rzRzukpH6GC1u+dAm3YlQJx93vnZNPp3NYqe6/qlE6APJtqO6U9kEn8o5eV2CEZjhJE7uPB8Gd+R/fc7Lw2s0/XPu1+tQ3JIZGM/MYx7IItxOQIKcKfZQrCivJFxRU2CkJiKJQZX3XjpEFiXtgBbyw0OsidIAoxJJNP2jVA1lVuvZbm9M5Z/4Wa2X78PY2J/ORjz6XSu2binbhv626WPF4RpVqXZr+fZRzRm6LWNrIvimVHZ7HRgSS/CcineFH+ahJV7DOUt8LahUIlDgN6k0ZH0YpwBmV+ZDGuizeAUhwudUJH6ebXIcMoy5CUwr8NxI/fhbGnnk3t7OmT9+TxSADPifoy5kC1Qg1JP35ZKHN8nnhnCDoB9N9gEo0UrUZn7GGfx2mq3Bo/WADHB/QXRKsvKE/jsZ0VXKu4NtbVz6Vfv5Q5/dOTbNS5T//e2qyZgTGrRzEVRKs3vS1y9XuWdGo9c2G1pHA3d4JnUEHr57RK9H3E//0NVMFYE13Jl577m7EXSneOGVzFblmkeUw7ysFcR+yp9smXM90DE4gdPyL1pgpTieZw0feXzNq5m7bAK2Iop8zwos12nlXjT1PWsEJrby1tq1hcJPRshcDxLwLShHd4Yi/hZFE+FlHQfztm6zxAhBkkG+z3Cshm3z+GFL2sz6v0Haax6prypeRshmusagBjlfkyLEea1Slbdf2EkkhwFsRxA3kV8CJNWscns76egV+6IjpwenfOxCvAOi1x/rzienU7K5YOfrQNBn1Ud+xz6F/d7/3n+dyPtfpEHo0VXkBif/hFTimIZjBOi6rFRnvJjMFdzG7b+jVgpwn8U/Wo16n6nKCXuyNyEuTR+SWVAKLc+/tIX2+tx1oAcgM3iazBtG+Htwx+85jIEr9VQuH4QvD56mmZfr3c4/PjfjW4We4FPhCuWT7fni6p0T0Ow8XnGEHnbdVm8exw/tv3f+Zctw1iyrfeuOhEju744svi4f2+aSHHejcnqhoKTHOiQA12J+4Zgi/wpz+PvPTCvUb3yDXEXyOW8KJB0ErnWm89i4rfrg+KSAAqyofoX4zP/zaBbgn0ggxJcMTfgTFfFEyjneJnI47c0snMtborcSZUfI8WPZU3EaEl2hD0RYwCyd/6tIX2OGm3jlGuOnEtYteVMCcNTWbeJL3zEOupqXJHBcOQ1eZ4h1R6h48ZZrFk0DWBjS9uSz+I9WL4snKCAWofy5rkq8pz4bsa7/THsaiEq8qYn/nlFMMndesheQHIZpuA9ZbRvsO1QOT5aCXle0W8i4586Uj7SAk58D52F21FOutH9fOTVvfJ1uzuyICyWVm60u4jXj1lU8S8eYh3xFjJHds13KVB9KLRAVNu7+uqYWYsY+TDRga3Y5HhO6Gqgv6lJhgs/rWEYjmZLWNL7hQ1+3Dt9tNuR+cTxo+QKLFNc+ci2wvf8YQMCEbEdZvmCvk7yfCWCWrjRGwD0qXqG8z36ybiJaUj4JZcpiGBd8zxPbbwML0lmKq5pwm2PDYar8ieWajlzWRtIKbouYhc9nhEwFZonzdC6eX6J9vIfVhBDevw/5YFItMkPqrTJIc212lfW9n2EJPmQZlnQk78PiGREHzgGM2jUacmIHSC9b8be+60gUSj2D5OydwHh7BBiEI57eyydLL33feo5/7K+rzEEYydi96KdyzVNww2gVlX4iXd6ICDD+pR2lnpp6Gw388IpQimoiLviExl33tQ31DG9JLqjh5Yw7/X9AaCUp2mRxs2VvpYP2mZ8sm9viJp1v+oQdHl2Ie6P6nbrvXKztUceP9M0wq/zmfqm6J6tOlrZCq3+CFlK9MbhMfNdZQ70VgPd4VaivBHe6ikFSN8jGzQU182UkJ1N9kuww5y0lqnaCOG5HpBuhMdQQnxbTPQA4Qtr1UftoFdeGEN4jxUZ29W7UW9ovZ50fjtOyJpCVaSoGCmYGvSXOLy6IvBbQTJQEMu0XpdEE5UszQiysBqb7TiwwTbeLnxbIMxgmP5RHZr6CDMNoJqfBQbBZTCZ6lo4yH5P4g1j0PVH7rnZdEmkeV4+7hNj374Ia09Zft248fmafCg/cPDUs4EXCAvHNbcHckzOMWmMxXuIpeI6mB/9cTvjtuuGl6we6KLYiarUyf8Blt87S6naT7CJ/9RX+OWOIfZqXsKQZt4DzJhurw/EN6M2fpR9BBD7js3zo9S2upQ35PZNWB2eHcV3fgp1Ilu8Dt0+lk7QUfLqEDfCy/0bH/Uwxny4BKcH5+yraS5hPuJh7510EEImy+2R5akwSr/hWiJtsaT272mm7+sKk0X223t5IRKYpynMDV61Y4ofj3Dpyt1Od8Qr2dyk9ssXcIXAsWyKjnZVPG6gqsVM/VGHBHPO1DzHICJElwGhPqobnB2o3AK1QFADhNyEgD5aWDWVdKMSsfCXO8/W+fKLQPOvlxrTlnT7HnTtgujBho1a0hHA1ATlpX/viSLuRot1tijGYr9ZRy0yA8PC+ArU5uI5GfO4NOeW0aBJiFx4tq1CImXZ4KvCe1/6vH6ZVkGR9bLck7Vy1gOV/yYrOK7trJdpnp1Qtu+g1IY/tr6flswvaV9psNOFfJSk9Foi6RWfFuSGo8tLvD6ceo10gef5veCr1J9tBB4toWH4hiCsY5JxdHkLUDpyKmLfSvwbhpiY+mJmucIiUVGgB0queeTDDQnxjXomYjW0ao45n2zjisDqBpGIWUOWDPettV1JMXFBueNs1nwcrNoJJrIP/lBL7zuUh9VF24YJwrr3BqzWNp9qdd/1sDdiVZCgq8xTDXsyPPztQITOv7gI8Fk8//KRFRXNUwLUNRnxXh2mHLNlO1cwDOOhDE+EGhJCG0mNnEn2g9B00+IMH62Rcf600TIjX4URxTnBed/lVmb4Pqj5LUrF145evbroA1/q9je6EKxQmtdUglqzPWPTafsOmnw/mZCu1axw13WowxCX9Z6NzI8NpQgRoqUxe9Lto75bpgJz3shPPGOrsUTkB6fNmj6Yh5xxhwfaLXhLEX6xz48lyYyLgTDg44wbkg0hdAkxCGsgtAsiY5QJM4XB5L+J2ok2JTFo3x+tSJsyKNWI9vkfZv4QWJgFPIPrTAAv0VPvdjilTXbAMRK5GxICX4k4EgkUOE967yHbSLHSCHF8lp/wZ12kuOQayKm5dKm4I0OMH+JyopQOfXUt9Vuo16a/U4Ny5aGS7y9Sf+d4XjwJBN4/5nKrv96uJDLt48jsgtaoMo8J+gOpzoRKw/44QdSAHUlOg5LPPvSUKCbEWRlk7O5acswZrugpOCUmIpYQhZWVZbkIHIkAXpdDlYXISe+FytMN2Vgjlnt8Yw/WYrpB+pJPayAklvS6xykDhVnJvN7xl5rpnnnBEDvzr2Mm6fHtu+X0+hOyEBeY/ccTxESF5otST+URSvBPKXRnpKpJxRvyiGVkU1SSRFN/0Dv0xI2rtpveq5fe30CVUalq0XQsEtAHZNI46oj8XVX0VMlDWXkLKrYgR4ijpf6GpzslRVqW/q/xuEQ4ZFnB1m+p5ZRttI3R6EFlzHD76rVCcRdlSIsB2Yv1zhzhjXxn6mdLfJBjPMs4z3199MbVhSQ4xN6YjJ7CemAva3kxllxFjosGL7PeffgW63TauCXig2HqJ/bIxCkRm7si3ssMX80IaY40RS3EhMAXIrKNKjamCNluYaL2XiHoZ89urU1KmYvXewixmu8+KTutH7GsjZ7iMujdH/fUkQ1EMLz31Ti9eP/e1CxQgCEWYsHbnQEIGJRPb48IOfbJZ1kd4kzAohdPXQcFWZ2JQSQQCvvsbgx7eDv99jYQz9vfUDvgayv1RchFhahSX+B4Od0+DbJr/GxjyQWhm8yZILRzgEv6mDnGi7d0QKSTMdnJHVvblRE8825vIr6VuRXtNeaBcZ1f46djSiVCZzrpHNW1Eqa4X4eeEgQYcQEzHQEcI/xThq5e7aHhObLa8ugluEAHc9mpXdf0iASj0wVppwSv8Ojt1nu7vkHV1a8SbYJI8lNG/vKB/kLTqB/0F9CbQanV+d1EW0WQZBTAzApx7w9LrRyWGm1DCqUo6aGGmoCyo/FwGk2iPGkkej9JDcNocPrgnxfal4NZDrDoNPYBaSKqgplvYh3is7SPKuguIu6FmC4P69d3PGIuYE9B0hkdYGKxRkpuJhkfQ28Rv8QcpqoiMGMf4VjqOzbUMT7On6tPetjIpoUh9jakwN2z/Y0Jj498Zn88WLswGaJbvcu7jZxL6bzP+dGy95pp799Ilynjf7XPq/5+SPh6PtTFdcP4785toScR2BcZj+RA+Jo8x/OhUdBwn9SqK5gBig8EGxskxTux8QNA9QOh1v7DJzJ1Lgb5BfnBoq3/LEmR54i8gmcTa1L4RZgfLsy8fBGPYFGMdoIKhnwmwT7sge4s1XkREBe+/EXVAELAeLT2QFgx+7xtSYnW3KPjxzJpQ/jVISoNudTrM54n6RUcLcyqlJDljrAYPBse6T6POAGTQRHh+S3cPQ2n9SfGWSHHJEE+E2z4RqArGjzp0h0eqd9tspYkKV2XZcGnC/0Xgau/nfppj8wBxoTGhQ4srHph3If1n9SrdxkaWUZRSOrr9txJXJa6VGoExKDjhdUsa6hnMq7RS4xSz0fGw4d97ow3Q1FR4YTqA5vaXt3PCFPQrJZGPXDcvmMn2kUGQA8b/tKUB2zpmQwbjWdBGH3kNZ32IUrgvrLJ5v85a5UReB5joSQgu0xNbadCFthljn7vI9cdIbukfQK4r69oIOiUmFS6hdoZ/bWwjjwzUxNLm+9rwVxvtNNQwhdR2/1v0l69DsZ7Rncai8f8djpJ5ywK0ugF2RKTOJovoSvAClg/EK4fvSDildZxs3rKigrzljmr73vafH45CxmRQdz0WaO4H0Z5QJREZN8QY5PFwGvGvAc7dVoEZNSIozq0O+IkAL6QMyJyFteQJ61vBDuuN98l0uGDfa4NKLODH6xvSzKyt/8TTt46RBZ2PIn+cdLQs2uleJMS5QtCY8C3r0eZVN0yPkM27MRWK8amJXo4tXA6HIqUxZcAk9wcEDaS888cR2Jvirfk6Ce8fYIvvBS+xxnUKtWPW+LfmwJh3Rc66sUSoIN8ZusR/XPveC8xycwEhuPXiM3E7F5nnM607ArK/MADwktaf2l0oa+SHExKCfIsYgU8qLguOvhgPZwNRQKsU6tR1X4v+P8i3wzEHYO2Qk1jef1Hwatwvw1kwSEQUbAUJVhZNg3jMliSFdy23/xXcLsQRya98e4qGQRmLHkWSNWmp6tMi6rdXF6LMZ0/plgLWHpe38Vtwr2gd4ggPQ/Yt4z34DGRnqt2QxfVR5rV+LRbF28JwIdalVV0ltzaeyjyiYqubTfcTo2KcUQpcOcGuRzvrT1fbThd4n6K0V9Zpm4nxUG+vJuqpWmr4j7AOC2sp/ndHHyJJW/myvny8NcGkYM2sI2lCliIyU/myCSnLFx/0QFg8lBf1Gin5Qy5ZeWOG88z2fE1uulsjfiNKod+YggQuVmsJyvE60i2hfwR09NHFjB2UZMy9GWIyZegXULG6Xz5jxmOH879NAivfTa0X8Me2NiqS5d/fxzFnYzAibMaJMvTJZt2+Iw4HIO1rIPcD7wbOcZE6r6NOSLqE+1DWY4m1vtKv5LXPZXXXIE4OmbO+GM67xdhPybBZ094KqjlLJ/UkcAD3gNzLq2XQ0Ek8DfTr93hYrHIcSb1ynAcrAicj9mKowjr8ymu6Nn6t6oIAd20IQm+jvIqkNq+uryyc14OFHZLNUDXj09m5y/g8DUbw2TnYnBfgfJmMtfmmDpBvxSbSF+IH9X0O3k9nG94XrtFHTDvJeRGaCE7p/2w/ey1/BB7uBy+k5ReuuumSwijaZQpvKBKkka4QeVyry/JnqPZHu9IKejPi15oH3elx9jDBIg4dt61uIIVeZDlev0+Ry0CcP1+vpiIeUOUuvXmTPRfjP48r4JhTMGtGdm9fQEjI0nMkW3fRnfrDLMhAEnAwMuBVAob6itIcgrzaFLT2MdJC0E63wVBjZZ3O9dGH+oXx1zji3SEH9Ur2iAySueYnoZ8ad62+dIegkJUA4c1fkbyukVeE16+f6+nv6jGhJwolzaGohEsaDQUuAY/hUacpvs0j2uNy2WlLMy5q18C8g/UmUMk7hD52z5XwuCzWsk2omI/d+voL7rmXX0+bfJZFdpGCBmLs8TFP1H+s0t3vzR7ryM8br5t2zBrF/sVNBqCXRiUbsipn5B/sx/zcPQGX5cqnPUF6ohI0t5posWqwlKowoapt0EsBQikGm5+KFKfZqhVXl+cw4QmjZs1YWVjV+VeJBVvW/jIJzJccRXGP6iVwWMRcof6ghlS0jX6BxsLiOBBLPGOzl4bYoD2daW2OEeNHyvk9L4CzGKoSYaLU3OcNq5iGVyQm1mm6TcZ+2z3nFZhXYa3fXpHw8ulAAsItyMbi7MuW5PN6qGv3BFnibKcG9AeM0U0u2ay0cHo8P3GzarDkzMl2KXXkb534Xp45zd6U0He6MQx/XcqQd0WQnJWt381LF5OdDp1TzXxbQwQsoxsU+H1ZMb8x5ur2WcbiqsuvvTqS9V/tecsCS5Wl35lA8Z+mHOhoOuDqc/98fvtQi0BFhvY23gmbjf6Gs1VrjAnJoNAzxVBZzj188x2EWJpJ24uqM/1dI0u70IIJPVRtrnymx9PpQ963yIT8JZXvqEzCHDN8rV2Li+4TPKRgcyUVwC5adKgHA2xe9Pbo/FaodPHb7z5tjlgZVqZMBbCK0rAQn7DJYJF/hgI1csnLLyOi9yN5ZjmOU103eeoW5v75qgNKSB+QyG7VNd9p+bsckSqdULPL4UNSOjzGvvQU/1gmR51t9ppHpozOjRtjJ6MgjnYVG9ZVmci2I9YIcP1637ddb5iUwD3Ob2rviUI0FdI5XmDiY0hbg9901sVcp4HdqEO5RMjeCA+r3QPYnxH0uKIY/zAlsln+JDjMqgumbJiBbXZqLDNlrRuFq+8EKZiC3T3BnRnHgi4QaCB7Cie4TP+PRiTVlBUpX3Icej1uQzqN3X5eSDsdlqajVReTicx+XMLEUKhpJuRX9qCERO1Xc0bWHTihV3KaPYLsnjO8u88q6/rB9E86PhEn6Xi4dBOC/zfR+NLp/nl5K434fRXySfKlx/LOKn3n+7t+fwS3T+m8ql/2rmieBVsYB4XBFS6v45Y+/HHXl5f4feNoq7krnA5RpvCnHKIAGvjIWgkEyu6JkGsBeV5O5iSen4JkwTTz/+NGdWFQtH7P4VwYqhx9vtQozBWIBpibtaRuQ72hSXvrPB5Oz2h4awBGbVgyCBn1TyC060H4xSTK1dbBZVJaM9XDgFyuZE/07wyHVrvZ8Hl0hPMIw1STR/h+gXC26yXK7qZD/sv6vBa7lZEjF3Tdf0p7tOnV3ZMZ8mnkyh3LiLyHwRxKajG5hQ1TI9mkrkLqlshsH6oCXfm1HfUVJyDAuICs+V7HmYjc3q7e2Wv/tvDiOOpgvzslEB2jVch5/tWb3S/KHEshdA12bAZ7ravJqdrgQLcaN5I07PJfezrNH6dYIxUg/6gGPdZj79u0JTpJlDCprI5OvxgIPQs3N+UJ+u3t07GPJNwueshPvvcHPuIz3ATJAYm+2i9G1ci2iEbCn3IUEEd8OW+V1z95XIFrzd0+oRSfDjd1bEp6bye7+rp1S4TTyAOnaCLCGjg/pmRV/hNSXaR48B4xV6SJ2Q3oJ8Eck3bURAN0CIpMKhGOsxWliGbwI4Em0GZ3FxzHMcjW/q+K9F0zGjO+p5lP22YZk2PPBPFmBLcKKxU0V1jJ3yk2egI2z8GIZ+jvWaP2oAy926fV3kkhgPiig7ccn5pH8YUlsTkzMfzydFUXON8nj4dXBIoU/1gUexGfl28RR+iIN4qNZnEIBOETCkCEM6oo92d/Znkpm3ft3YkawNOQub5TEaOLULrTlxOaNlWRXovyyVn8o2md9PfM+OJW7723a67L34CzfiKW9Jrlg5FAjF+WyTl8bstyrVftCHtBzqfFyrszVCyB+KoCNTzokHE4BTj2c7iLL+/McY4cd993OnXOo3rBNW8D+d9QweBllse+U7cklb9/tfQE4/QsSN0OLqibXrHdAkqM1ljIgv2tOhGH4PjOAqKJelQjar9PLs+mo5plTmK5cBU4uEi6ody7p5MoeXg8v0ivqKj2lVBEOqMkJWO6Fi4zT4VIH7YgYGCORfQLbz/4m6hYpPltv2eCnm825d7Xta5cba+Y8xJ+1Dj53dSoyKIzOJF67fWfFRkfjb45Kjd+XLK4UagahnEPE/VHLCZAfqdejDcNWSyGuftv7hcXsVXcMmvV+zyIhBqqNV9iSQB+s4vYXWDMDXPt/2jbqf4mP8zH5YKj/i0iQleaXnLUNkqqMQigzhJDTm9M9TpC5cdJr1HPn8LPfeLXMf7DsHcOh6rg/VCioaFevgJvReh3dA7W/kAnblhrtlOeTv5M8EKstAiwvZ/FeH3CcRMYUe5x2AhRGPZOJlX/lshNNM4+Q/IKZ6vpYNYQN1Sz79MXYBb33NUUOHv/2XV3xLoF1jEMvT8bv9AJwE20snjdmaRZxwYVjBHbCq+vkihH0iPfIQyI8JcPfGVKTU7RCzGzjafWRs2adUfxO+MpPbwMnwlHb51kKOEkHlgSi++GFOoYWSoxEOmoE94ti8nUkI4bkEQ6SND64ZoQe2yqIw8xMh2KAzsBDWr2q73tBjL5pm8Qscg49UtO8H5HEePaPsUmSz9Lj3j9hQh6NF8fl3FscfKgXbZs/lWGehfaPdZsyrc3tWULGG2w/bknzWYuoCnWqebXYRbhIKbR2CAHNcUpURZ1+BJZUzSLScEY9VT012Ki0xW2oNYkffhVpY8yuqRf7pPD5K6RNH0Xa8PUxpH2NrqqFPYoTd5bykEp6o9xMrr41cjdNTOmrz0YhBbdTjBjSZfKAWoUPXJmvly6Se36X22OQ47fNUFwitGd5aRU9jTIrhIUVwgK2wbztrxDvxUcR2RUcgT7vW4e8v8L01nz68kLMZRCAsiD9CJOf2xaqtHpvl+rYzlTisCjYy167aZcLmCqafzN7vTIXnYDIbQq8OWqfV415Pj/nETvHxwjFnRNCtkFUsn9hBXngFjvjthiM9rztOT83RIA7rH1ZOujtYDGz98tieubDsCoMrbMyiRJxU8Np3Ep2dNPnU0J3m8nLw/Q/5KJpJkjUbsXNJ7UZRzv76ftBsIiO0P4oSM8WvqkXFl6i8VIWsluRxi/oD4VhYZbghXpAipQVXidAyRH1l7J+9Fa5VdXLEVBhFRmQ7HeS4veIbl63+wg6tg/klFzTon6cjNMtQSz++gK9hjvNpslWSy4rCyeD6hL2GhIeRkd4bNPu/Wj00j/8lELwQH1ehStk08sRXXI2ej7fDNMmWBNgO0aCFzlOr9aAin2KiwDzoq4p95FYv30YffBMaFlcJYAxR7jS/cxB81TBVvAWeqMX4OH67ry8hyIVwlF2+e73tIPcSDh4Cdj/O19F5f74GEO1M1PZw7xHQGofviHWT8oVsIg7hR/iTc8uaXdObYZ1sSMOP6FIOTMGoBYlL1q6CUWudzM+jpLVGkcCSGp9vhCQ0WDBLLk4yAhNLwwPLR5pLdyujn6U0BKrV9KIQ6RdOnabRni/GFLn6ofMYYXSsJFw+9tUa4P4LewC/1uvo1ibtP9md2LyYz9YhhTM0HvDaUTZzhVgTfJ5iOGCMn9PX5vhZwfL8dM2hfrj7rCH9ASUHvQvshxsuhh6wD8qmuLMYeMTrT+kpKy/n8fJe4GdHo0R4BrFpC7ni9oCvihH3EjJtyFzZ9t0JQvG+m+1FdPHDyoImvJWv7iJShE8HDB+15onCoB37TiAFsNHPgQrEzIJtSJfiqG/WZquE92UTwJLcrnT0v6hNnCcuzy54ueoguo8v6gTaK8xdOOkHOBLgid4tUK5/IxKiG9ZwrGJ/4xjZwMzpTIEmhrxSDX15cW/T0jvYTfdo3RAYDkaQOz+a6PlfXUTo4jzqF6cEEXq/1L2goGp87aOwge4w5f/mJa/s3MeP+EOS/HMdJTX5TN4B0HFWCAaIm/W9yhyirv7zHCZGOz98kDtv+y528Tk4jpNIrg2aVx/xas98UVyjctiIwOVNchc+dpd/GnvgC8pPIXU34Mj1biuv8NcyRGTkinOvvosrrprCHngfTQR+daFyQU77/dbnn+NV+UNCv5RVYsjOP/Xz6B5v9T5nMMfvMz3LuyIc0vN88zis6AbUHMWZd4yAgGBLTXpLsezOKgDzi7W63BsuvBqBR5QLLIOMjObYulZtic/ltB3NbD7u+n5NLtN8jwdI2ri4YJkpuJ9yyAng1nk8TyA5ZhWLhMe4gZ/tJ8oKKkt8DerUwr7SlXRnkCDvd/hi3h/N1QGWG0s8SMfYR5AKXiiEdvI2m7o/rlk+Xu37ruhQN9cmroLkwQlpBY2YsI9qHI8su6+NcjjztczLwCe32kaSC/j0hKiJEiSzJQ7ekhcs2Jv9TTnQ6HFl1of0TDXmL4qA1AmHiRCwFMTIYCh9b5IwzyGZD3ClO4jmD5HPaDkbdMln//gtcNUWw0kcMA+43xPNCcuOR+5NDBECO+JYFl9nfzIxeTPlBE9UCEv5PyO2sPVt/m5yslZHNaK/F23K72E3UdFlNswovtgjECI9Xq9pnNaCED+KEsnh3KCVioRrNZ+1/bJlhU/ilIZonPiR5jq2+S4OQvCz/4bC3I1zsb+hrv8LXnD+aotkLTMhytei2BZWp+J18JYzCaeyCmjSKQ4x032n6pu/0aPnIKBvPOyG9KEOt8KinA8f3PwJp4InLkALVqczkdrEmPK7FFeIjhyaBNU8DVoa5z/G+T5LyP7j8eeFnjYJvQ9sqCHfliKW/7shHqHFP0xoItFovCk99F8SBVIu4vAPX9uQC4hszybpPXSbLNcumb2kWAwsj4q5HbKv+GEoxrFR8v72jy+v6MpHZufEF2Uctvkl3zrlez0HjhRJDQR1Be5RmVa1eQ2mOtmbGUaWFnI7cjC7a8/cAXQaImGwN0aUd+syjCjbPZ2T3A8RHRugDS0l/p6ggQ1aeYu2zK1u5ymt2oK0UlQYEYowtssA0gohDLyyC4Gs4+20ouM5XtLVv6Py8iFvAcYpCrkJ+KN9AHwrMWNb3htnaNM+H+vbdshu63bga2mh5/POaeOs//BdsK9D26rxUt2c+ny7ElP06RN7bTiTbBTG+RjvtZ+ovUfE4++COarLHWUVqsc1Mk51e6Bc/wwC/J/SFGnBlrFiiEumVCyM4OW3ksHhYf7f4U97lTFm5+noRhZB7FU4oRVXfXfc5HC/fp3Dj/xIZ36ygstFjsy6vEWI37lC6ptksiIkkufS6Z4jgpBPBZQzLEurqmUXHVJpWfgjrGKpGjEWYaO+kvD38gYh1Rbjhpo2viaJCmaE649sk74SwYEdW+QkKRQ0iT3jMHPTGLOyGf4IAgjwAwfmGMo0IjttC9nme2E+AKE42W/pa6XQVVvFOENWokiyyIvGfMZ5HhAkjA2EdAqbQqm32x98sA44xLQ7vDwfHNA7X152B/O69vXSClWO8dYpBqGS/3LBPgeXSMX2T2oJz9W0jnx5VPJ9XRlsTbUF+vwBFtTmtchKAQwXlzAri37zfPy7IpAan72YR3fO66aPYjffFlCqVJH6d1Fq5xSYZjU92nhC4NT+Ld4IlINkSS2NP/IqhF347A3GwY7rql0nMswzowhLSuE3P53kGb2pHl+51qhG86/Avura6Wx6l1oKoT5gMEa/PFXpgqvcYJ+5niEWaIwIiHtdrVjdMxEeDg0wEvpAHp57ozLp8mPZNPkajG6NG5UxjAzslvZZ43x5n3jrylDGxhX0NCn5xariB6PfyWwRpjEFRQ/y7Pgto3j960abEIrkMVOtAU8hEvFcT0M+yPRqdEbdG6gMWytWdZ2D6aokYG1kigwkm8Hu2h5jhTSslyWTiDE4N+14hHgjxQm5OwgxSfvZl1LcxcopQjY74vjgdhceP1hkP2aPfsaB5BDIj0VknSjlTirYzTDeqyx2/KCO6kwHyyd5lJ5y3/pSfOHWIcIx15sy2Tbe8mT67/J+YjVpv//Cc01zOd6Kd4i56N845dKMIMUyZ5QkKos5CaaaPBfyjovV4R7zoSUmxS0BUJKQuQmPcjkGBynsW41ugSaxypHzRLymSotYmmwMRnD3NaU58Q/utXTx39FLJriK8OTQkSW5FNKdmsNHx+F1bREw0YYtyD51KYVcHd5r0C0t5KgSnT8v3KqCjRzV6LzH+84EZgjCojxwQ5p4qStxiHxdYUWf+0RXJjuQ7iy96ekRfvbfdduLTwa2WzYgSDhh0kA2epRwjen0P3C8B1fBHpJ8xFeUjSmjtTwJuQGtG0peIUojubYbGQ8R6xr75QXe5/jGfjWvQsb+ITSR8IBYfee92ni35slh6o56QqY48mZ3oSf3AHHewfhBCtlbI/19sKjt0HeKE1ByHNp/lQPSPG2DaZH42Tg746UT7wKumlTCh7gRP+Ojk/+t72vvpRxH+Kve+oJ4AHdEckIQN8h/ZV6NIuEWQbYfek0d/kTYHtzWWpa4goFf6EWTbTf/ZnG88z78rhLKIriXtMqyi7adrImd28pWO2m1QaiP05XK7c9eDuQw9xdZ1PetswbkbqMlF6CN0+6VD94TQGj1BzgR7Ueq9JTTlV52kyheKvDMHJL2JHwYkqkXlHXjIKS0WYQQ+yY6kFKLPgUpBX96T3kJeVVrQlXzqmTnajXVbzJZUS/wzeL3T0RozLFOJIeu0vb5REeR+hz8tMxb+rOfgfeSjkunISMj+Fa3AUet0b8//Tdzg8/1N+oO0hftXJ3Vt/yb3oa84H9//+grq3/S/8397ZuT6P3hXW7BZ4YGIFHkoq3HJG7kNiDVBwKianfUa2EFX3c/aWTuBr2E3eW2iy1wQBGTp6vS8XK9h0P27UvrLGYX3n6DJUbbP9cja3+1zDjBgWIVPqr9nTVQ2UFpSpsUBJdS9uqt/Kqiny/2ifQ3E9qlcox21x0P18e3Ugzn97qwgf9j0gyPCryCWEk2+Vp9Ao+yDXNlN0vcvBCPFOg9Icfma7BQjbLTCXDIxl2pQhSysJ5my9ILYW+73JeTslRfng0DW+7VQgdFDl+ogb15U7DWQ3emOGRJvxUTQWyFoV0BvQ/lANu52+NqQfg6YoR8xBJH41etTWnlL7AecgLf2Z+anP6JXRfvg13tYs9uX5ho2QvZsXdj0tQkLlVjJv8QtB7W6ulioq9Lx9kDG07Msca5SP73aQlA83pOgrsntI18vLQhpLv/0el5MzJuIhJvJAyewp5BG13yw3o4Gelcd8rKk+sPDLU5adTVMJ1L53fsp7EYXQembYU3I5lcQLltB35O7/vtoV34gNFHEnxRO4mmWBV5swKnYIBMqaGKHP1pXQLugbRfvOx8TFcyrf/Dd4XZ9BFvgaDIpMPXjXt5yRdePEDzTFhKVSbABgonw2Tz3nYrfns6vZxcq5L6p8nDEhct0aeFAuzLlP1sYTJ3Pzuk+HVmXfdbDQkfmIECIMV5w2bDOtv4EKASG8RteogsYafTT5CEXEYuHW9V+oEeL/6nByTKbx0/ndhJ6hN+iNR4XRlk4pWFOL0lYrASxZw3cQZYl2zE2D/GZDO1HPOdzwsbjRgnOAi1LOkIWrIHWo59IrZJ2L0bu87mtomENAMkqUO/pecV27stFWKQ3lV2+iCs+a+gEk3t2O3uX/vvEnhDfEJUOR9jElR/Ql1SMRj2moNPIQaQmh4DbNM3qg5t/7NwvygyyLRDFwrwXpkg050nuR187I7f2dV0WXYK2W+NDIPSsm3GRxgN0lxsCVDbELInLUCOZdCvknEA1E9xZHMdsSbB2g3adTgZ5r7KZ3bfch55fZIyXOyiUPUn08DTNMJ+6hFwpnM2CZ4/lgjsLvJ4afwfqEIWuSMeu9RZ98TYXIlwbSkDXd7iPmxS4QVTdn+X8YTlz23emUyVsn+qZFSWSEhbEskQjm308M73H4h3ZseWkfqiRb79Tjo5oGKYE3kZu6RZ1MvuTD5Fe4VD9u1KBojrwfPu+/3SUsFR6QHQnwn5vB6HlouEsdf+CTpiY9xskaQThwJLL8poF+vT2ez61qh9M8jQXMaaN9w+pFZo++Wfncy8CSyavz4bJxp6gTftLp7zX4T6dIsoGyWpttjG87NHyli2686S201/yiCRcqKn6NIRhR5atS+e18Rai+nY9nms/5SWZna0J077JmBxto7mv8skU/ebyzMcoRgZj6er5xYxP8LmRUI2o7RkilVdBvNln2WF5toTq/e3NiQ7jVe2XZT1IVe/IVbTf1/UYEUAbZPTaU99CKO10544UB9jn9hiwbnPQfbyYz2PIakFNOt+wHrDLM9QyrSXUFXFQ2KHVLM8AnH2WdKqAzmqEjlix7a9XUsgMrtQs2LnJwbK02LoPWUGlGpNyW+HC4fKuHXjbVYrntJ9XdmoJTiJN2tesLv3XWEGU6YN7HzqZdOlFnUTEfh0BmDaX2s8nLj+cQYuglugWpgLd9W705mMJMoqUctsR9q6eRBDj9Ek7u8i7esG7TuoEFKnBdWIw4oPDAnLVn/oG1vKFWaDclB4V+40NRXMQi0gQqzJ8BE4RlGahNhcy/v8hvTNnbpreBPqtXX0Dn3jCYuuBy085+wVfckO+5HMpqZYUeAX0dKEbKuJ06BP7HbgalECgmhc99ZuqHfSaRyxJtlpn8j3NqAr/OqDzMYQqdOmLtKSsQ4gQFaKC7u2JwCbrHgyKJOpiyu7lKl+/E3OSq3MYeW2/sZwiLne/Hf5FxcgB81ZAmO9dA++LmYr0+codYxZX5kTv+jP3bzxFveqS5I3x22g3DAqNSWW6tFyg6A/qUz4AuxgGGKypqsusdqDDzJJuk1aaLTRp1dJKH9LDo39R4do13emD7tdEqNr3rI45sn5Jz4KjTi2CRBykN1aVt0TJvatuuYraF/BZFNgQLxJn8hzvbJzn3OD4PlN4RopPBs8jBA3Gif8NH5fbGO4jX1+yHE622BgCbOj+16l/WFU3x3kucXz0uqbQntLaJu++oLoRsQ7axS3DRPq+e+XAWHxSeqPvrln9pLnLDdjIV0+TE3vhs/tnlYdXMKwn/U96Z9+hAADUxJffb/zjmmwMdLfK6yPusxjqmgBVv5KvTXoQJMNOZ9oMqyO/cgyFnO02Hglmjed5HqbOjaZr0dBVhqD3xXar8PI8qsvF4uHfzZhZ1j9mATGZmOX5ckbwf1ag3hH0FwzAK4CyBOEO2eG/1dgt7hCzO7p1snu14oCcp6t9RYTJVBDTMHPr0EIGeSKIjkLv25YDrw7RBdH3Tg/tDN7ntn3bT/K3DPQKD9/aNVT2n4+48D9PiJlpRmLS99y9EwTEEJ8plqt49JFBjlRHj9lNTni2LQnDIA57dOVaFlQ8D+qbPsWKE91Wk8YeyxehU1nZSdLP4dlOC2fcECK8s5WPl7zbhf6/FVKws+ro9zSLf5QT+ury20OfDLWZxfsaXpzy4YwqRrKNU2jb+SQF/6L/7RQM/79iCf8PMCK0keg7IEp26L6KiI8a8onejNPXcLvVi3YtLI94tWifBVAIppI/ozmb+vL818zDwTu6YDP5htilyZIhQtUUe1m/MXSDCSoeDQHkney7I5/WX0br1lyFW66teUGZlrJy0IBcUJunWrZwQ1yby5/PnTc8+f0Ke6FHyAQx0v1P8acMAETbsuu6oKb/Pep/qOn2UqSVveNjeIEJAJBHxEbtYQeYf2/e94ZppyfCGSIordyK1QbpjOABsqJDd5RxWRCyr08s6apCyZym/sPo9kdv1UfF8WkYg/aGUIqRN7Qsy+IKiP9DrfSq54qGdb+aCigWuAwnxj/Rs7HOyA8bWpVIn4XwNor0KOGN6Bxj1i3n1yNk7W6teQM1LbWXs7Qf0zENSLPoOqbWK5AJmNnAjXo5tG62criVjYERpWJOAbJGK8x/QcEo2BHWAu9Ca0oRxUXIZErd/pupyNIH7j/WC3J+AvQmtM/X6XYKKqcU7y9jHtue4PNU+Rw1qdYXn6V7VPj7tj3yLz0FHQh0HYtUdz+3NzW9X/ft7dmwENipEUaH4LDVUqCCKnwZK6raJhJfiVL6DOZ9sHm2hBOsl2Dt7RPSP5+JHWMzZ3qgKJj6gimYPHvJoA+v++YIlFbc/OYMESEH3D+cxJhevYtd3yD+neVxGNIOAcCmOiqBNA0YIzYWwQbIVJBWLj+j7ZaEkAX4qNWVXlD803dxw8YyBav4wBM/8jvwBwRxciNXcyZtprG7vK/30+NLG3xR13FbMtI/ET5vlmjyadT7JBIT5OBPiEvd5Rco86TTEkDm69AH5Z+OKwQXsX9T3APkHe421JpD9wfk1D5fBuKt1bupbqccmVsE1GzBjvo8stk9j+dK/r8xu2DN+3LnaZpe8fItxb51RfyFYsP4EkMXjYOYwwfx8aOoDKHpneUpHrLYhjr2l2Ux34spdOqrgcrt/0plVbUzhVDdmoAkyfWJ8PDeR5hRciOCfd8beMl4EJxTja1nX+ay1mHyY/7T0RG0A3cUXPHpLJYA/ciACLDSMlzAeUuw/K/VQ9l5SRNsOM7WPE34a5D7QyX2tuXnXmL/97VfKUFP2q+Z4/CwLNTfFHOMoW2jSIp1jL9q+jhYXwF12Ba0ZkdbO/Dt4NBDON+gxwzOpOrP9Oq+9y5Fv4RMSS2L3S+euya7hZgo7veIiOMlS8cePolb7Mv/DRmCkJ2IV4M8ytvoXmpStV3nvXKcQwc/XxGxBe51tvtoG7wP5SNcl+3QJw44CPr/9wgRSRcjDyHAo8JEkz9MW5Cf0ugQkVIH6QnGU8gk8bXk+/bReSsl6qOIMO4V5ECTZ26UDqQFPkda4A7p9tvrv5AT8MaM3St/7nEZn+Sluzb1oneuuijc3JNqva+fgDCOyrILMvkAwIKYdXbLsYavpBwdD3KHVcSG2AhZ0pkHE2B2XRIF6IuGEQlN3zHVPJMsa6AtYQR+xVw58CEq4ro4754m+lRV2KFtDvXdQWyFIJHiWu57dDtxppit3LQ51fonOsg0XRGxWToZo4AXf8tQwXgrJZ009ieCy6dXMbOIxCnxTH5xaKkTMhCQEZ28NdHGiRTUkpBwH0hEHKiUvIfIpud5v44QDXjgVPGa5Wyb7qunraaPAGOFCfiD/bfeyuvvEHs1K5iEIWvGsT4N0ePPAhR/XRPPsITEKEKgR4MEdSPhhxTllL5fYzeqXCpT0FXeLWS2oVcKROIvJxU4UI1hpXRHd/Nbs9ngpzuhulqJP+mCYkzwuUdUGL4nGLz/lCUgWeMtQnUA6JNQemRcmEfVgppXf2gjP1Vh56IZGj2yemRBfDNAMDTN9mDITDtijZ2Jp6a7foixOLwRBM6OLoWfTgzgEPCv0ErRql4JOknx8uQUYVBP1RuGj7ATPavbt99+sm8IVTS8j8w9lduM/1RZBz+SBFI7EHGmdQi8JJbfObO2cNArk/VYNvHkkSRw77z5Ty1l83XaRRzIuHtAjVJElF151ZXv2iGuQ252705kN2naxs30P7NjHqAivEXPj5dlWRC7HZ5bf4YHlHEQfO/PEEG0q7FX+V+UBV3xaqhzdG4cdqU69fRlcqshxUCWNojGHo0MJvo8jp0tMdagQrGLiHH1QLVpjE/YNh3zesKBylKTTKbsV7UdFanV+sa9vowbmx6y9bsTcrm0rol/sQoF8XthgRLi+FCnDW6EQh89/lBNX2B/CQMry4q7n3C1xPj2RnNUKsjoLL/dzd/Zdyo14cUuxYa/LOh9uouf2eLeHr0ha3T1f4pjiC1/foj93r1v/+0o2tC94JpLC/QY0c5cHiDkUPAMz4XNSz2fyOYtsoPeDQdjnB4fUHOVT3ATpi6FvDIzzf3kI0cxqt631U7FG2MzMwrDNeDNWMYmxHShN8SGFk8yYpUA+ouj5WCLE3RbywV+rEKBsOevJeawgTDTAzoTQF71Dqc0QRAOP46uokCR3eChW1shL9FG965rOug7QLzuduhAQNZQFHjIMn26brhNI25EXt81R17Laz4CQrT2XHCH/C700X+OuHXp4x88ap0Hdz2mH12lH6L4g/xQYOTjfPb80pqIFq173R6T9+6YSYPYCuKRarzjeDme7W9wcuQ22mrEgp009W3kXOP6vHLJ/Oh/vYP6FeSFEFCubp/4ug+0J0M4RMCj0VcZ0+DnmIie0+p1RPA8/XPrx3VyNytPLPavLe2YRwS25dnl+xCfiYoiYFYPk5GTGyUfxbQXEyqG4j6Ns4C8hfptMD7jWJBaj14XVBqgH5OPjb2QBM4CfZVJqXe62WeDN/AjIk/vJ8fKGbbHDOEOHl8QP4b9EiFh4lCvz726IeDonEX4Fj7n1cY0ZXQq0SZCr1EjrEN8aV+kunNcrT8Vu91frCIwMIHqL45cxvF1OxcEO5LaTxe5ozqc8FaOG761r+GMa3vs7+RsQ48sr3LURBmOi4NUmCJClb9wQaDWvntyf/vtG0l9rjPDpDL+f1zdk7Q9NVmF6UsvAbqIo6MRA277BNVsLNbu3GpIj+9oltg0pMmt5BHYIh3cAKjyacZLhXslTVF3d0tIBNdik3/OTLLh+8aZGTPPz8eDtIl0PCYMgXVRivdqo4tz9ECk+YV4Jlj9Tw3z9XXaBtYIx2oJQWUY1DMwL+XjzFfLaE0mV3PpOjp0B04wHFxEjnVLWJOGujxZWS82ltPcMMyHfoh2WQenEaFDTZFGotAV8R7+RsyKVYme2FwJb3dwPt8JL8vR8Q030BemYaBMscJHFmM5hIN5kWBtJ23NLu8u+qozTlozWWBgs7/JdvsvY/Gb6WLmXL9eYHEp2FXkNt0S4Xzkk32Bii5tR82IHbAmE4mR9vYspSgQ9EgUaGi5PR28DC4nASYHIXCtKOsZVAmJdI6SnjcS9CJTlr/3I0CUmIGFkFFUY/TFKYXHi70yFrr12yfPiGeKw80W/ypu7fNiejcGomywuo/nk/mMfeStQ6j81hbaC64PbIr5xrm8qL88Vs2gQwnk4rNgLWN/E8VusKztGd4/fcens4KqkYFQfrpDBvvm/3oCDmM1wvu3R92J/6kFUFIHTY+wCqqeJYnqrUJn8p8Owu/rdtbtceI9Q6N4Eg6PoL4doFtluP+tvS/rVhZLtv01+XoHffMIgqDSiUjjG62K9J3Ar78r0P3ll1V16p66t87LHZUjc+feiIKLtSLmXBExo7YgNhYNNY44COY/OXeXkOgZI7N1edJ/W3vN/ZPa6909wsgzo/r7Ob69meTcIsjAXaeuiBu2TNHsXmF2z70jc2YYRUx7qv0MnKP0cIL34ZMpcX3eYnItSy85bALtm85VZk3DQK7zbCccjPWn++Pka0B5ote+iTxKPSZR20C0HVParUAp6LIIeieM0akEu0xOCMu7I4LOCoTHIONx4y70ONCgsidBnwshO4UFVP38pYZjQvc1vogHg0O0DTKZ0Cn5BR+q2y4VVtum3P3VVew+7HedSC4T++ATC3RSvQ2yTl4HwTgvZNhKP57hbjpmMBt6II67VpYVSD9zrViERKit1wtH7zLIdWXMdWiiLapNdG63RcbAGpE8a/zYrALvesWFBcl52h73krSN1c4NOtjOpFnkVe763UB8/kgpvl81Rx5RJHJzB8mRDyJ+6CF3jEfk5CCklnS/J1rpw06zvujPwIUiOOd0qZHnLJsnYlEusCoa4TgiyueagJggaGuGbjrH3YDWE4ccrhg9R2BT0Fhw/zRfIfS5XEENiS+Z5DKUPV3lM8WDFkt2LEDLvEgLC+bo/m2KS1vfhZpBdJtKldZTODu15wlCblAngr6d5ihUyTUZOSRfd3dUzi9d2hQx9ltZpFXpdmtUEs4WnYGc1Am9vhv9qK9Pz+YSjMlS2UGeUx7VDYzNE++9WVCHw/Voi7I4RcgaPyiz73arO+xc3amzEaqKoWMJqNUVwiHe294ejJJ6x90k45PyzkdSzSi5MnPp1nUD+9zblfPNNSAePSgZyjPCu3rYXXf9Mr3y+ZCqNavRsdYkOt2Fxb9Sa6KVSYPtyjjZ+UPaKHydAq9KS+xXhZxcS6a0rrDDXEH2/p47rMlIHu/EYk3CnXmxDmgM3cVrzuDcHoBr/9Z3wsruoX8prLrsZKVR2qYNaFY6zEKyrhy9iUhKl8nNTjfIR45C71FfT7TqFXUIOfxQiiy8JFwzS9o/JQLdKWdEE9kTLe2DSabpAt/UO5jAr+ePPfVkYVOXEaAXIYuPESmxfuRgw2HXGjH0gNxriyB9V263WneImfTuc5LeEP+Erwiu6oxAn3SpqZLNphc+RBecmVzm9nhivSY4d9BdaSsGstO2KMSL25G507zwE1kYtEoigAaaZv7KMCGyOBxGtlU04Wa53OLxOnwsWniZKS11CV5hr2hOtS+mHKDPqVc8Aky5I0tRzrfhy21lZ0eft4ZWo7PE9uf+R4gD9pXfuVCt3JM1s3soNa2K76tyeTXH60g/tWfd1CEx5luYN1v65gT149DUIFAe9e5giWeEHRXY/OC4c7DJskPQE7L8q4ZKAWXPDWQbSBELvNqUIBv4U+t9ibC9KFwQG/VtMsEN6MoJl8nR+94p7/cby5IEproyN3FKVM993cDjQG44+w36pORxiR/3TAWtMru05tXsrCrqCXmf+TMHku/3ucai5hSWwVYcs9J6K6WBQ/jMaiMeVOSHkO+cF2WW622gQCFvfvNpc+EmCdnaR8JMNsOSMZTKD65E/KmpwcENcNQDEATkLc+5ZVmyoTvCG9ZNjOiTC5ppmEEmwN22SvhspeaV9zpbUR6B99iqRt6wVkH1yp2htR1k290BxYywl/TNkrF0RN4udQDDm201DchnMh0vYsil6d9nCv8/tYbcga5Jvu32tuwrTsnQuM3m8beYakY/YAQpkdO2ks96eA60ajJ0hthvVZHzBb/y6H4yv8P5CvJ/lof5+mgN2Y1MhCv0As714kVNyG98QtVfHegI+bLusMTlLenSN840bos9LIdLeqOyEKjztl4joBQFu61Q0eqwZZWGrB+GyEU1MbefTkw69aEyj9AAQINMQGyA+KUji9I26lADRWMBXHAwf6vz563qeb5t2AEyYqArhNvSsZnqo3+DeIb01kXGelAX+aFn6XU0kL2/3xSQGis1JXGWCuNKxLtTYfEOK+8qR2A/gOVGPQ8IgLSnujWhS1fa5bDLDd0wAJU/g1FLibX3T7RzsIxgMaf27/h0xmc/OxLP8qVtUaydvDsRayl/ubWx+5+OUGkC+z7GiI2or4uhmmo2Ir7z/Eus6QimOGJKqLJ/gm5AC8li8Z5DAButEMR2tOPHX4nzV4lmk0V5GmIDm1TBAfJcHcObPFESCvncxVGeQd5jjrifPfKY+T7U7onfqgdBn/tXPqRcHp7X4oHcre56+eIhTtnBPjKine3gqsF4ek5al2c/VTWJS66v7lwkrmu7yIYpr2Z3gQwXmjMFMfLwwd27bhBl0QlZGz/5VHkYtrplfmydZwyWRM8K8vYNhNReW7ncym3JN/QLZv9uc/FUqj64ghizBSrW6rcC+OPkvKEPHnCR3VVswgui0lmcgpAe9KaUH1w2Ld+8/gcwk3Yl0hxa9zB8OlKkx2TU8o+iUfNWWCOdZQnjLQdRMx/2ZkPnGQ2bjnybwBKWPh2ybwgRYUxE4vbfqgdwE4SXdYMmiL+vlSkRd+efndNLVsG1j2487rjLHBTHi3uKzyCbBWVOgjDwg5GSE1v312338tk8JhEizzRC20GnzK+AU++cECMEDvX0912aZfvT8ZNRpR0BYzolXWn3tyALzFcuoO06EvRfsxr6pSFkAwQRrc388aaFHiwcqVYbrz0invVogOVBD83K0j657zkkP7zR9GmuBOT77Laudmc0k7tndaXUvb1BSQvHca6L0Ep8pQh+0AmycLgXZpCStAcV7N+DUrMuQLzw24HDOaxgVUkzAO0Ks2tDqDzd7uSNbOdp9+5vv5SY9ldbhsu5ObjEVyjWGslhD9OZgm3HOW2Ybx48aFRpMWQsgKrdH78q/t99jm4lgfgH4In3+w00FCdvnVtmZqQryTwaa5vk7eV1FHax84yzzBLEn9zk46XvnuwCJY6mCH2At1SHzB+80X31+5pKTA7Su87b3KZe0KP8HsiiVjDcIqPPutrIf62I/FUCfQqzTQvc2tx/d1p7UAUlEoQ0zltL2eUCSqPyo48YXN8UYrr2eRi14NdOFPrp3TEFxizf3Ry9pVMsmWKOhMApIsqgCQQZmmdl/zjYyC4zYXlEDtfKkE1Koa+KuY51KFKVQN3NihTIPJokRZO/+HJfk/crdVpGNLFi65TzE8GGRoIM2J6a9tD2fY8j1nUs55x+BopBA6ByNX7LaxzJjtSA2Xz6mPsEbFxn0xSRHNPutBQf0v0yXraO1iCYKNAIsYIuxabxmmQIix0rHdpWAQCq4C4gU/VEQtd1+w16OzDTs3PzhqfcseuydE5FIk/mXGkzL3gavr+e62uaEugO4EuB0OC3H+GWS9gNLBTLifpbdUDzjAvY0w0R2Z/IBbewAmSHWSW5OeK9CmpbFsKk7UpjZoNbCE/1rGCfnYzcoW9QHxYjd+9uUPMyQITTku0f8RZeTQefCWAve93RbP5woes7aE7BCgO1oK2DFsUMfjR59Eoi8DiqoHN6Uxy5W9eNw552fXflEB+V7U1P5WnrFXS24C+VgOG4BN7pwqccWFQRg55pwilK3pIdkZUvgL4ezCxgSe2zRZMB9EGhJztE4G+jpeTIwAJJnUCtTpyT69/U/7ON863/BwqvbIJBugqGJXRtsmFGSCzNyPwG/VJme/c0BP8laL1x45vzyI9MkE1nmtEeh7NMViwbxUwGYil76CnQE5EZW/7owatQnWK7e/tla50WHcwHZrgWcrtd8T5SFgKL1p/VMDze6OT1lUoGBYbZPR332OlwFZ2zkL8z8CtQXY1wbTWdbt7g1gOd+kWBiJi+Cu+zklRHSDQKT8zYdN8dVXEN+XgM1GML+BFhZRPZ06XeJ4tqGFA78uGCfYh8yft1fIYQQe3EsIvFzOYrkWqwBUKeVp9ykQtWrsd+ReOWnIFK5drVoQtxgwOkh8BNY9s3F2H+DvkgJnzW96PAX9amOJ6vgXVKKepKFOt8ueK6CBo11oRTBHOLEpzXyWIUNTHU1lWdiGm9Vsnzaw132E2Y3s2LiP7kV0uLaNz5yRf1P6jqZ2KqQBi36RwoZ2/AG2Y/tTO9QTtb1tw/rp2RLbs6oNl+3xNMIpcu7MzmNey4aGCpBh9Bkz9H4cqDssY1kISbfnyYvwA0OcHmWgAUA/n42+iJ6mrd/nlN/iikdYLDLhZgEt7KSKj6vbg0evqyLZ/fhuTJb0V+aGAHTMPg2TeDr+XrlUD/OmhkiyXIdHhuccyqrW1qzamTy1qQpYJWujlGWOOpoIT6xELbQNidLRhDyT97lSca1EqgLnfY/F7Xz3dNDj/Rsacb3TU31MJfcfW8cV3Xx/jMt3Eesa/9PZiRe//2BtyvDwmQU9CDFvf/Xd39AlIkvJ+XbnnrjiS7ma+VuI7peYtAA5+c7EYSQgmNAYJXNjwLkIZeszGdXyBuJz9A9wt2N0OiaO7xhDPQoQ7yO2Je3RTccOUZO2N6yRhNhPxqRewjuGn/VFxtFZbj5M6g0QNKDLqjzrO+KU1lgXf8G8YgFpN1bq7qi6leK1oB950DA3Z0VEyhXemZOGD5B7E2TjOC+51Spacfj2/L90+WFyzWcb1JyWN3QagdgjXa/3hm2QHAZHv+K+r3NRFKdCNE/v4G04v6DnHXjOK+dSuWYr3Xb0d4bvHp3JmfXFRBVnxiYglCTgYxzoQA9RC9OpHRHS2pR8Bv1UYvTHZUlienv88l0/a3NMfdmxdUKsxopQIwRYCBl+XzETLIICO4OV1ez/uojRHoMWBDhJC+6+0Rdq62QEUKMRzt2p46X8Y47h3Ikkid3IVZcT5z/fFU3QVBcJsXIiLuGbSQRbCZhCc83jIoXoOqyxWh3tQch4FCNFe4bCkaPI8cIdsyJmhtU6W19eK5fir8/NW/mwThrQDPzwQ/do4IXTNXc/8ONOsWS23Sr10ZQc7dWdClM2ljvCmRHu13Zw+28VrqwbiwwYoWwszduDVHfhu6iSLu373pLfV3cJ89qA5+d+/pWBvifEWINefw8k2cl8AJI0gsm1mtqnQ62zKGrc4shn0tQisv+dzk9x2o5F73onNPOtjV5bOf/aHszmUzl6ltCLUMZn6nyuPuLCFke6i13fz6zACWbxu1gS7FX4X27w72Gg0E7/OZhXDqtq1r7O7mbxXqF7ACvA0eDLoTg3IAbV4L2SYTNluILZjLFJsWgjlXFmG5beFCFguHuD7UIIcnUJez5jdy1Pt3LCKIRemvqqLXmbQ2GtA+m9bbbzQAIyBeIO12H77RNk/1TKlQ9Z5ZCONhTQR9ST59ouikqCrcDyczwyAChfFTdCGMvCa15CfKdge3CEACX5dSnyouzDuAFM7hZZeTdH170QGaKFyygGeI1nmpn13ck+2//YD1b9+ON/8tTVv6SGblKlaIKcdMFTCIxzoITRCa06Yb00FP8Ah5DTZmy+IekeHJYx51gAiv6RBRMqnE/hFEFxI5l4SMia1rkfkxwtwZt6/4zsow4jTH5hroF4S9BugxmYI6py4J85tLj3tr6uoDgSZLn5trEY7vN2IF8ibPAN8FmMHWqTJezbw7FdDOUVzi0jlSpZFn16aAVlCxs5+jH1dJIfMMeTkQHQ6Kr8j5IWLoTSnKoJFJ4G/c9IgFUU9ngo8SJpiD+6+8rY9SnSS8oSxDsBtDbKC1slu9MUUgwrWMV93Z0yzreIXlxCRMqSzLaB7hYdYmB8ZE4xe55AHWPeycpWFkAWQ8hETTCsaTSdIRm5jLCnGx1NrduclEwzls3eKgSzb0Nuw9Xys2mekbKG4hxv6kTxd5inribApOG+f/r8zgQid+As2gHAqP043+pcj2APYHJGv2SrzpxHzjf2G9Iw3LeRPwBLh5zA7Ihr2XzyafeJ0Kmg0J4y6dFgTIKwQ7tjh//XKOBPKZN5zcqtJVfZTuYhN60M4mAp/FJc/eETjLWgOcbMgUmBqXFU2MoCiDKIIb0qehCxEb2neFK6IvBFUk90AVoX7jMmdT8aaHKho8sOKkryWjaocaIgm2DAEWRE6zFf3H7J6KXEq8K1xpw3G9wSNrZEZGG3ZfIK+NTI58FA2D4zEKmo/3XUleBNxFwEC+osWD1upQnmbPeHKpo0cGQb0sh0hgx6lVTjyNPzJ/E2R6zgny77PT7MMOeQ1BpbMI2CLduOpJxdLzPZ95jHbv+7T35L19TZQN9B68gs8RBuBzcvIDUAp8xI/pHWNYciv/m9Ge4YpzCavab/PBNJTQzvFonwRAQsByNOwIOBWeV76Wac5TP9kI8DCux9NaM2WnzLr3JhRIvwib3G17yL4wx1p6adOeabyWAVHgddnkIu5RzYIocOtqoO34W9UkyCrdXT26PxZTXL4675deNuzHporjrOWyTshyIMaVIFvmWtFP9iSNGPXboAzPC1ciTYOBIFuzROZcOgsBsphbPCSpy/+6qn7TySvn0+VeCwPBJruyTuHeMI7uh19RmWSaiOgsud3YfJWA86V9I7P/gL4v6k5MPOkAO9mgPHzeteBwXAbIckXy04ffqLcIwvj61s0yInLwm4VysSwXJIs/2iRLjuzDyWh5in3+xiPE2GK59Mapt/1zwB8vMtvhV7WyeMuMtJGuOhjVdorRBRDWDK/7/BrmRPn6lUWYvXBxP5+vmKFdzlVCGjTC6lCyCBZsTg2p48+ImjOWw9ycKDwLyMog7/yCBBvESfmvoryARUa5WwkPsO2VMJrbxvhYg8nwf08d//Vfr+M3A3C18eyv/01V4RULjslHjeo5QahMLrZuVZUDT0YJJPHTaBenQJyKhM1McfZuLK5yMDNEz5ZCRd3FkliMUumZnqJbq67osl4eCGe8HV7KmdzVut+9no48V1X+Qv5xTrudbOvQHy+eZePOxOfsSTf3/i1IouKRtEFfDFw5ne/duaP9BHZAJjTUUqB0FjECWBnwc/dMIXI80sQz5MAU8xDKvozRgEYwKuogTsOKceLUWgjFtOgY4RFshlo2iM4u2bRSUC99yLM0VXQi4mnOBdcBOYKtZaky2PGqZuRHdSOyccqy1Dn2BLspmRW720r36xE037CBTcn6kcRj+Wxhf865aPsn3uYHLDHX6LPjY4ES2mtTGQU2ImGv5ZO/Da1Xw5fjvdwVRDVEK+lVZAU6hBCIjGQHHHCgFY/F9c217ok1Ni2sg129uTfROYj7uQk+g/ILzCdu/AaQ1uGoV36L7yDhSj0p7LgOiCYSN7NyW4xIbh1+2yY0epkZ2X6NU00++Nku7dLYqjAG8rJCb+iQBe+YdQhXThLOu5tVVes+nykDX9uRH5N5yjZ8V2ktfioRQbdfRGc37vq+6Mm6CtdQY97UW1AlvJuG5iJIAm4bd2F3v78FRJkPglgfEO7HBFE4h4JwP+iCcJUVQTjtJEHYiyKc+9YEdUSjbIRwLR6v7oElSGf22I24xkMsmKNzGM8lmmmOPZbrrVPSrdIjYxFOTxrKs96IrS/nn6gkrEMIHVQeGQ2jh5Axq9ErS47+SvRgDPii9d9qJZXrEb7XhaOo5ClZCXc39nf/qHF8uFXdht8RT/vOmdiUZ1lyADzupxmLPhRyoaH/76F4zsHAwdYJbDzzz/1u3qLL37dbOeKq/bJ1bkwvRylLkr2eZpYEWeLvQHcqgXoTFH3UUoaFlleWhzDODR7vlokaOh7ehGiZbZ2S95aVZfELPaqy5u+fK1QIWDKXzFI0n1jDTddwPbz1427KUhwa/+1pypIjBWKx/a9R2g8zmrnEl2OyLMcFUUQ42VSRt1Hd55CRWTCuVlBsnR0ku2lLBehydbDp2jxBYboL9s+fQro7WFYdkUVRjOFcc6l1a7U9aGaVEHEXJthMwAzVfqGJD9Y09TyCPRrgwek1vq3VLR79W/3Vds9VIroNUKiOTDGdgjaQXZ65t1KQju3m28MnGyaFZCbw/q/FqaArMZrYFtRZlBP1wblmeu+JzGpadOoMLZXyPqkG9EaN4kzl64WjtapYiIIz6dr/1FGaYAXBsOcT6Ee9OOTXH282eX5qmHHJhxDBwHp4GAIDXZHjJyFNQbTkLpqGFs9VyrA5Om7tubXcU7gWNFeeTXVluWHoEwfy6WFrGZmUcmlEVT0eX8vtWkOv2zPUmtKgor3ohEoI2NhGCQZjtybJw/Jfry10Dfv6XFZveny5dNTL3ousBbT6pMfWBLPbgGxYOM0aKRrOcOUpTdNn/Ymt9ba24IPjdni7HueVJfrLOG76mHbNl+hehm0rnMTn4fm63Dbxt63KzZqscvXGkECcrcSIyMivZrFkx09UoSc6t61WBqP5MVfIbMpJNGeTeOtgCTs/0E/vNvpGBXGPcmc3ITFpoPLxeCzjRDd4JX0KhHsiijsRocWImLH19np7WrEE9kzTjVkc3qkYTtNuD595cV2cPUI2N8ZHXjF++2NCvoxB6Q9ar5zldmxe23wZL/g7kskMJqWSrqwQWpdRFfi0L+0j21VVVa7JmF8hjwCGw1RUnWDjUV5CY/dCD5u89aWrwd0TEmzh3HKEqvQcml+unK5bN25By7p4UzJkqbfXj1IJMKPKTFjGUQiGoi5kNjJjt6WusETML1yq7bVvUxFLMspVfx7lJVve936if7Tviisie8/zD6/UubLYkSCBxAVDRhvIEiETsubDCuE7GpKz4KoSrFvmDFn2t1GTn1djN4J1BB8whjYa0SOkgkgPiit1NNP7KBSn7NxVQfKrA/h3du+3pn46IhGn/W7Vwcr4flU30HljGSunYT8cc5/Vj03va8qmlPW1x/sA/eF60oCaZh+GDREaNSLo/gUjQ9DSgTLWRwmz6LzLr64pfAxeNaOnd19uOMJ1r8cLOYC1sEcG/UO9lsSwLJpAi17uve5SM1B5aUENNloNZ+6qwCiweEtDW9l9zjYr+iNba3vlT9BqDbaBuL6wsukwkOQEtq/5gjLr9XS1Hs3R5ekcoTs2xndh2cL6adlkxNsHBOmRH8foZJyDCIwFjzxWccL5JlIsr9sXW093Ve1JtHKfsljlNJ92yKNd+CwpCVV6kCfSR2j4SnamitCvEllVQ6Db8LrcI9Eii7dGM9URvpa2VU5xPOzBLLDDSk+eXqq7h7rmCs9TBM4f7F67q1PPVo4Vc++9UjOBoKJhNLcUdQaYjeooTRPGL/Sdd1LgTjIozD+oNYnjGJnArr0g7MyD5q9IcDKIMm/7CPDUK56HhbVJ1zEU9Cx5xdSAaCltxEQJWYk9jhx06V8aefvumb8l1qK146/v+8z3kxXZOUljizqlyTAMcL2lRfaJoRsVupZdR2QPR6JTqnFUkS1BEwor13SSis1vUIk87j6e1JvnVEiwxLkrmV4ae0ytnHOwnxWsPh9lWnv1j+QwJRVaEtOKvfppk+1Op7Rqmb6urEk5wjc/sgglbsnr8A1ly+CwxALxUQoUEbfdLIyYJJu9WKpVOntTIAl6iNh1nitvoPhbFM3EwsbyTK93cVuKoVCtjuMkBaxo1xvpbtcnYfPmUujqJfIhPtEZsjKfTbxtrUwrVLvTQ4GOksgNmGvQe6em5StdOyErixvcdblIJFmfsWIhAt6fbMvvawZZiNgkYhaqLTJVPHFr9mRYZFG0R3VHHrPDJqs5s2FyekFfSLMd/I5jNruyPJGx1a++zy3QdXupPk+aOy6D18mPhTmfUhIhYMuKgoAi72675vNjmFb1F84CM428n/1amnPjJH0wwWsEhQxayqt3Krts4JV6dG/CnLJi03yXLHF+GvZEOi8r6ombnphkgPHPBvnw5SbOPKdvXUvGy1wRzevXIJ3jR9exuDfWrLjjW+RJwSDdpFEK6Bjav+3pVM8edn1CZvWpwGJJt06fWHtp2hF7kFt5pHLHDnc5JRG/IBGr45N2vYE3TbOpgz0T8zplxCtU1wV2vALZyk7CbFS/bmN38dmi4qc1O5hoRqziFZaK2pJ4t0cr8/Ba7F/jo6dlkjk47/lq/sCPXAMgF5aSep89eZqmxxO2Nzuryonos5tngiG+4n4H2I4E3BXKZ/MMUz7QLwb6HOSrEY6LebR80EFPFGeGoivzq1kzor/ZAxYayOogMDmt+fdxHaC/ZzxGeplBfTF/erWhtjyCyW/mb5FIVIDKNRGJmzg/skU0P1NcVADKJSKcTYjIrI7ltKGC7s0ypnjuPURI0RxiHmcqXYLYVEgVWTQIXuvP0Y+mC5kQyYhsv5EjDL2nMdjXoxmGZfsOPmgKETxgKYr+hIbZn7o1BL/TceuX0mz+R0nDqDsvpKWLdqvbu0xC9GpaQbOoOZn5gSaSKqpIsurXKGmxhPAjGLRIXyLoO6yhucwcfF9r6vahqiSGAWoP68VQnZ5ANmxaV8uyjuamURETZOh2/LjePCg8C579Aas85D+3MmuWGPiST8kkV1MEeGAaLrd4WjBZt/xMZ+y+CwdvctAVU+g+2bBA9Moi5nvoVKiDQIm9iWC+ldzBhsw3liNpmPnEYiC9GpfQuSg6cI2lkkyiIqgLQuINRC5v5HBkkL/b61W+0s8HxystjfOWjxs2/dR9xAz3Ktkf2g9tjKFbuYbmFLR2Jx6eFQnrNquC/oxomMRN+KYsBaFwOfiNmH1IXCAI9Ye37QQhRP8JhiCcZeUuHP5z7n/O/c+5/zn3P+f+m89F5vjOH6oTd1lsIBU7iJ6DEtqVlrvX8X6//0FK279iP3T1K93VRd3BAQJ5NfgHvfIH6GFiU9oN6by9ROCfQ03YpdXw2yFS/oPclbOS1mU6dIjjY983sLA1BG9ZPn9TDPf5+/1Mhsf3EzDic+yRPu+Pn4+FfQ04GPafA/dfnw0s7HNF2Buad2lR/NzA9juBPZPPe34uPoXFmH4O/UGLf0jYHyK3/ZT+kPA/OGr7Xd5+x7bfd9tPbDvC/JyPfkfj+jlh//MW9FPcXiK3n+x2hP758O1DaOlzF/2wFN+7SJN7evn+WXfDo77XVVjIfx4Vu3qskhS+B47+egxl8f01rRKh6+o3vLNJq8+R/RPGQIKHlqfDsFyeK3x0OA41OvTnFbS6br6f818/9qyuhn90HD3ybvHhMv+L/vkz+F718w3ha/3ziYJGoR67+HvWz7Eh7O7pz2n0P55QXVqEw3P66+f/o8nxfatVP9GVf01EBvbZf5uI5M9E/PmIzz183/XnFENjHS6/ndbACf0/uQ721+vQUCr358f9H8//ua//6nyW/afno18+d/zn+vg1hv+9JcP84yWD5ja+zWf8t5nP/7Ycfq0d7l9fI9xf3/h/sTa3n/+/LLR/32Ki/kfWEkH/dQ4S5P/MWsL5f20t/e35P/f1b1sb+N+vDTQV+H91otP/rxOdwL4L8vs51G9nEr9d+nO+8NvtEX+3Qv46/9+P55BemnCbVO8ubP66JsIu/s54apvAaDX8NoERZc9i7J9O+SKM0kIM49d9u+7PKVVdpf9kQYTF844WoBSj+Z92/x5kQuJ/RSY0Tv49MiGwv0cm1L8OTGB7pq6H3yceGtqHXicpnPG/AQ== \ No newline at end of file diff --git a/documentation/diagrams_sources/state_diagrams/motion_state_diagram.xml b/documentation/diagrams_sources/state_diagrams/motion_state_diagram.xml new file mode 100644 index 0000000..dbf7cc4 --- /dev/null +++ b/documentation/diagrams_sources/state_diagrams/motion_state_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/diagrams_sources/state_diagrams/servo_state_diagram.xml b/documentation/diagrams_sources/state_diagrams/servo_state_diagram.xml new file mode 100644 index 0000000..409b7b0 --- /dev/null +++ b/documentation/diagrams_sources/state_diagrams/servo_state_diagram.xml @@ -0,0 +1 @@ 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 \ No newline at end of file diff --git a/documentation/flow_of_events/api_change_flow_of_events.md b/documentation/flow_of_events/api_change_flow_of_events.md new file mode 100644 index 0000000..0f2f747 --- /dev/null +++ b/documentation/flow_of_events/api_change_flow_of_events.md @@ -0,0 +1,20 @@ +1. Пользователь выбирает другое API. +2. Если соединения нет + 2.1. Вывод об ошибке + 2.2. Переход к пункту 14 +3. Отправка команды отключения +4. Ожидание ответа о приеме команды +5. Если ответ ERROR + 5.1. Переход к пункту 2.1 +6. Ожидание ответа о выполнении команды +7. Если ответ ERROR + 7.1. Переход к пункту 2.1 +8. Отправка команды подключения с новым API +9. Ожидание ответа о приеме команды +10. Если ответ ERROR + 10.1. Переход к пункту 2.1 +11. Ожидание ответа о выполнении команды +12. Если ответ ERROR + 12.1. Переход к пункту 2.1 +13. Изменение GUI +14. Конец \ No newline at end of file diff --git a/documentation/flow_of_events/change_language_flow_of_events.md b/documentation/flow_of_events/change_language_flow_of_events.md new file mode 100644 index 0000000..11bfd92 --- /dev/null +++ b/documentation/flow_of_events/change_language_flow_of_events.md @@ -0,0 +1,4 @@ +1. Пользователь выбирает другой язык. +2. Установка нового языка. +3. Изменение GUI в соответствии с новым языком. +4. Конец \ No newline at end of file diff --git a/documentation/flow_of_events/motion_activity_flow_of_events.md b/documentation/flow_of_events/motion_activity_flow_of_events.md new file mode 100644 index 0000000..e231dd4 --- /dev/null +++ b/documentation/flow_of_events/motion_activity_flow_of_events.md @@ -0,0 +1,12 @@ +1. Пользователь нажимет на кнопку(вперед, назад, вправо, влево). +2. Если соединения нет + 2.1. Вывод об ошибке + 2.2. Переход к пункту 14 +3. Отправка команды движения вперед. +4. Ожидание ответа о приеме команды. +5. Если ответ ERROR. + 5.1. Переход к пункту 2.1. +6. Ожидание ответа о выполнении команды +7. Если ответ ERROR. + 7.1. Переход к пункту 2.1. +8. Конец \ No newline at end of file diff --git a/documentation/flow_of_events/sensors_activity_flow_of_events.md b/documentation/flow_of_events/sensors_activity_flow_of_events.md new file mode 100644 index 0000000..53289ea --- /dev/null +++ b/documentation/flow_of_events/sensors_activity_flow_of_events.md @@ -0,0 +1,13 @@ +1. Пользователь нажимает на кнопку обновления информации. +2. Если соединения нет + 2.1. Вывод об ошибке. + 2.2. Переход к пункту 14. +3. Отправка команды на получение информации. +4. Ожидание ответа о приеме команды. +5. Если ответ ERROR. + 5.1. Переход к пункту 2.1. +6. Ожидание ответа о выполнении команды. +7. Если ответ ERROR. + 7.1. Переход к пункту 2.1. +13. Отображение новой информации на экране. +14. Конец. \ No newline at end of file diff --git a/documentation/flow_of_events/servo_activity_flow_of_events.md b/documentation/flow_of_events/servo_activity_flow_of_events.md new file mode 100644 index 0000000..0cf35cc --- /dev/null +++ b/documentation/flow_of_events/servo_activity_flow_of_events.md @@ -0,0 +1,13 @@ +1. Пользователь нажимает на кнопку(вверх, вниз, вправо, влево). +2. Если соединения нет + 2.1. Вывод об ошибке + 2.2. Переход к пункту 14 +3. Отправка команды изменения состояния сервопривода. +4. Ожидание ответа о приеме команды +5. Если ответ ERROR + 5.1. Переход к пункту 2.1. +6. Ожидание ответа о выполнении команды +7. Если ответ ERROR + 7.1. Переход к пункту 2.1. +8. Изменение GUI. +9. Конец. \ No newline at end of file diff --git a/documentation/requirement.md b/documentation/requirement.md new file mode 100644 index 0000000..0ba5267 --- /dev/null +++ b/documentation/requirement.md @@ -0,0 +1,98 @@ +# Требования к проекту + +1. Введение +2. Требования пользователя + 1. Программные интерфейсы + 2. Интерфес пользователя + 3. Характреристики пользователей + 4. Предположения и зависимости +3. Системные требования + 1. Функциональные требования + 2. Нефункциональныые требования + +## Введение +Название проекта: Android приложение для аппаратной платформы trackPlatform (далее аппаратная платформа или просто платформа). +Вид проекта: программное обеспечение. +Назначение данного проекта - это создание приложения для управления аппаратной платформой trackPlatform. + +## Требования пользователя +### Программные интерфейсы +Приложение должно взаимодействовать с прошивкой аппаратной платформы по приведенному ниже протоколу. +Взаимодействие с прошивкой будет осуществлятся по беспроводной связи (через Bluetooth). +#### Протокол взаимодействия с аппаратной платформой +Для взаимодействия с платформой требуется реализовать протокол, который будет принимать команды и отвечать на них. +Формат любой посылки (на прием или передачу): +*<размер данных> <данные> <контрольная сумма>* + +| Элемент команды | Размер | Описание | +|:---|:---|:---| +| Размер данных | 1 байт | Размер данных в байтах (пересылается в двоичном виде) | +| Данные | До 255 байт включительно (ограничено возможностями поля "Размер данных") | Пересылаемые данные | +| Контрольная сумма | 2 байта | Контрольная сумма, рассчитанная по алгоритму CRC-16 IBM (полином версии 0x8005) | + +Формат данных команды (отправляется из приложения через API на устройство): +*<контроллер> <команда контролера> <параметры команды (если требуется командой)>* + +| Элемент команды | Описание | +|:---|:---| +| Контроллер | выбор контроллера (контроллер движения, датчиков, сервопривода или связи) | +| Команда контроллера | команда контроллеру (например: движение вперед) | +| Параметры команды | необязательный параметр, обычно одно или несколько чисел в виде строки (а не в двоичном виде), разделяемые символом-разделителем и которые прилагаются к команде | + +Формат данных ответа полностью зависит от команды, на которую платформа будет отправлять ответ. +Ответы также могут быть управляющими (синхронизирующими). Существует два вида управляющих ответов: +- OK +- ERROR + +Первый - утвердительный, второй - отрицательный. +При полном приеме команды от приложения будет сформирован ответ: +утвердительный - при принятии команды без повреждений, отрицательный - в случаях +повреждения посылки либо принятии команды с несоответствующим форматом. +При посылке отрицательного ответа на команду платформа переходит в режим ожидания команды. +Также, по завершению выполнения команды, будет возвращен один из управляющих ответов. +Только после этого настоятельно рекомендуется посылать следующую команду. + +### Интерфейс пользователя +![](user_interface/main_menu.png "Главное меню") +![](user_interface/motion_activity.png "Экран с управлением движением") +![](user_interface/sensors_activity.png "Экран с информацией о сенсорах") +![](user_interface/servo_activity.png "Эран для управления сервоприводами") +![](user_interface/settings_activity.png "Экран настроек") +### Характеристики пользователей +Данное приложение предназначено для пользователей, имеющих базовые знания операционной системы Android. +Пользователь должен уметь включать и отключать Bluetooth на своем устройстве, а также уметь подключиться +к определенному устройству через Bluetooth. Также пользователю необходимо иметь доступ к самой аппаратной +платформе. + +### Предположения и зависимости +На данные требования может повлиять поломка одного из модулей платформы. Это может привести к урезаню функционала +приложения или замене модуля на похожий или такой же модуль. Во втором случае, при замене на похожий моудуль, возможны +изменение функционала работы с данным модулем (его урезание или увеличение). + +## Системные требования + +### Функциональные требования +1. Поддержка беспроводной связи с платформой через Bluetooth. +2. Получение и вывод информации с датчиков линии. +3. Получение и вывод информации с датчиков расстояни. +4. Управление гусеницами платформы. + 1. Движение вперед. + 2. Движение назад. + 3. Поворот по часовой стрелке. + 4. Поворот против часовой стрелке. + 5. Полная остановка. +5. Управление сервоприводами платформы. + 1. Установка угла отклонения для плоскости xy. + 2. Установка угла отклонения для плоскости xz. + 3. Получение угла отклонения по плоскости xy. + 4. Получение угла отклонения по плоскости xz. +6. Выбор языка (русского или английского). +7. Выбор нескольких версии API для взаимодействия с платформой. + +### Нефункциональныые требования + +#### Атрибуты качества +Масштабируемость: должна быть возможность поддержки нескольких версий API (версия API будет выбираться в настройках); + +#### Системные требования +Версия Android не ниже 4.2. Наличие Bluetooth на телефоне. \ No newline at end of file diff --git a/documentation/test_cases.md b/documentation/test_cases.md new file mode 100644 index 0000000..ecdcf48 --- /dev/null +++ b/documentation/test_cases.md @@ -0,0 +1,187 @@ +# Проверка тестовых сценариев + +## Представление результатов + +Предоставление результатов требуется описать в следующем виде: + +1. Идентификатор +2. Назначение / название +3. Сценарий +4. Ожидаемый результат +5. Фактический результат (заполняется на этапе тестирования) +6. Оценка (заполняется на этапе тестирования) + +## Тестовые сценарии: + +#### Возможность подключения к платформе + +1. 1 +2. Возможность подключения к платформе +3. Произведите следующие шаги: + + 1. Включите платформу + + 2. Дождитесь загрузки платформы + + 3. Запустите приложение +4. В приложении появится надпись "Connected" +5. В приложении появилась надпись "Connected" +6. Выполнен + +#### Возможность принудительного отключения от платформы + +1. 2 +2. Возможность принудительного отключения от платформы по завершению работы с ней +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Нажать кнопку Exit в главном меню приложения + 3. Попробуйте заново подключиться к платформе +4. В приложении, появится надпись "Connected" +5. В приложении появилась надпись "Connected" +6. Выполнен + +#### Движение вперед + +1. 3 +2. Проверка движения платформы вперед +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "forward" +4. Платформа должна поехать вперед +5. Платформа поехала вперед +6. Выполнен + +#### Движение назад + +1. 4 +2. Проверка движения платформы назад +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "back" +4. Платформа должна поехать назад +5. Платформа поехала назад +6. Выполнен + +#### Разворот по направлению движения часовой стрелки + +1. 5 +2. Проверка возможности поворота платформы по часовой стрелке +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "right" +4. Платформа должна начать поворачиваться по часовой стрелке +5. Платформа начала поворачиваться по часовой стрелке +6. Выполнен + +#### Разворот против направления движения часовой стрелки + +1. 6 +2. Проверка возможности поворота платформы против часовой стрелки +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "left" +4. Платформа должна начать поворачиваться против часовой стрелки +5. Платформа начала поворачиваться против часовой стрелки +6. Выполнен + +#### Поворот сервоприводов в плоскости xy + +1. 7 +2. Проверка возможности поворота сервоприводов в плоскости xy +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Servo" + 3. Нажмите на кнопку right +4. Платформа должна изменить угол отклонения сервопривода +5. Сервопривод на платформе повернулся вправо +6. Выполнен + +#### Поворот сервоприводов в плоскости xz + +1. 8 +2. Проверка возможности поворота сервоприводов в плоскости xz +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Servo" + 3. Нажмите на кнопку "up" +4. Платформа должна поднять сервопривод вверх +5. Сервопривод на платформе повернулся вверх +6. Выполнен + +#### Получение информации с датчиков линии. Белый лист + +1. 9 +2. Получение информации с датчиков линии. Проверка корректного определения белого цвета +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Положите под платформу лист белой бумаги + 3. Нажмите на кнопку "Sensors" +4. В приложении напротив нумерации датчиков линии должно появиться значение 0 +5. Были значения как 0, так и 1 +6. Не выполнен + +#### Получение информации с датчиков линии. Черный лист + +1. 10 +2. Получение информации с датчиков линии. Проверка корректного определения черного цвета +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Положите под платформу лист черной бумаги + 3. Нажмите на кнопку "Sensors" +4. В приложении напротив нумерации датчиков линии должно появиться значение 1 +5. Были значения как 0, так и 1 +6. Не выполнен + +#### Получение информации с датчиков расстояния + +1. 11 +2. Получение информации с датчиков расстояния +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Подставьте перед центральным датчиком расстояния какой-нибудь непрозрачный предмет, например книгу, на расстоянии приблизительно 15 сантиметров + 3. Нажмите на кнопку "Sensors" +4. В приложении должно появится значение от 10 до 19 +5. В приложении появилось значение 21 напротив значения центрального датчика +6. Не выполнен + +#### Смена языка + +1. 12 +2. Смена языка интерфеса +3. Произведите следующие шаги: + 1. Нажмите на кнопку "Settings" в главном меню + 2. Измените язык +4. В приложении должен измениться язык интерфейса +5. Язык изменился +6. Выполнен + +#### Выбор другого API + +1. 13 +2. Смена API +3. Произведите следующие шаги: + 1. Нажмите на кнопку "Settings" в главном меню + 2. Выберите другой API +4. Приложение должно продолжать работу, все команды пользователя должны выполняться +5. Приложение аварийно завершает свою работу +6. Не выполнен + +### Выводы + +Выполняются пункты: 1-8, 12. + +| Функциональные требования | ID теста | Успешность прохождения тестов, % | +| ---------------------------------------- | :------: | :------------------------------: | +| Поддержка беспроводной связи с платформой через Bluetooth | 1-2 | 100 | +| Получение и вывод информации с датчиков линии | 9-10 | 0 | +| Получение и вывод информации с датчиков расстояни | 11 | 0 | +| Управление гусеницами платформы | 3-6 | 100 | +| Управление сервоприводами платформы | 7-8 | 100 | +| Выбор языка (русского или английского) | 12 | 100 | +| Выбор нескольких версии API для взаимодействия с платформой | 13 | 0 | + +Видно, что часть требований не выполняется вовсе. Например, не работает получение информации с датчиков и взаимодействие с несколькими версиями API. diff --git a/documentation/test_plan.md b/documentation/test_plan.md new file mode 100644 index 0000000..aff6314 --- /dev/null +++ b/documentation/test_plan.md @@ -0,0 +1,215 @@ +# План тестирования + +### Введение + +Данный план описывает тестирование приложения для управления аппаратной платформой. + +Требования, предъявляемые к тестировщику: + +* умение пользоваться устройством под управлением операционной системы Android(далее смартфон). +* умение подключать смартфон к другому устройству по интерфейсу Bluetooth. + +### Объекты тестирования + +* Приложение для операционной системы Android. + +Атрибуты качества приложения по ISO 25010: + +* функциональность + * функциональная полнота: приложение должно выполнять все возложенные на нее функции + * функциональная корректность: приложение должно выполнять все возложенные на нее функции корректно +* производительность + * временная характеристика: приложение должно открываться не медленнее чем за 30 секунд +* практичность + * защита от ошибок пользователей: приложение должно выводить сообщения об ошибках если пользователь произвел некорректное действие +* надежность + * доступность: приложение должно работать при автономной работе смартфомна не менее 5 минут +* сопровождаемость + * модульность: взаимодействие с платформой должно осуществляться через Connector, который при необходимости можно заменить +* мобильность + * устанавливаемость: приложение должно корректно работать на любом смартфоне с версией Android выше 4.2 и модулем Bluetooth. + +### Риски + +При некорректной работе приложения можно повредить аппаратную платформу. + +### Аспекты тестирования + +* возможность подключения к платформе; +* возможность принудительного отключения от платформы; +* управление гусеничной платформой (управление движением): + - движение вперед; + - движение назад; + - разворот по направлению движения часовой стрелки; + - разворот против направления движения часовой стрелки; +* взаимодействие с поворотной платформой: + - управление поворотной платформой: + - поворот в плоскости xy; + - поворот в плоскости xz; +* получение корректной информации с датчиков линии; +* получение корректной информации с датчиков расстояния; + +### Подходы к тестированию + +Для тестирования необходим смартфон под управлением операционной системы Android версии 4.2 и выше. В смартфоне должен находиться исправный модель Bluetooth. + +### Представление результатов + +Предоставление результатов требуется описать в следующем виде: + +1. Идентификатор +2. Назначение / название +3. Сценарий +4. Ожидаемый результат +5. Фактический результат (заполняется на этапе тестирования) +6. Оценка (заполняется на этапе тестирования) + +Тестовые сценарии: + +#### Возможность подключения к платформе + +1. 1 + +2. Возможность подключения к платформе + +3. Произведите следующие шаги: + + 1. Включите платформу + + 2. Дождитесь загрузки платформы + + 3. Запустите приложение + +4. В приложении появится надпись "Connected" + +#### Возможность принудительного отключения от платформы + +1. 2 +2. Возможность принудительного отключения от платформы по завершению работы с ней +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Нажать кнопку Exit в главном меню приложения + 3. Попробуйте заново подключиться к платформе +4. В приложении, появится надпись "Connected" + +#### Движение вперед + +1. 3 +2. Проверка движения платформы вперед +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "forward" +4. Платформа должна поехать вперед + +#### Движение назад + +1. 4 +2. Проверка движения платформы назад +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "back" +4. Платформа должна поехать назад + +#### Разворот по направлению движения часовой стрелки + +1. 5 +2. Проверка возможности поворота платформы по часовой стрелке +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "right" +4. Платформа должна начать поворачиваться по часовой стрелке + +#### Разворот против направления движения часовой стрелки + +1. 6 +2. Проверка возможности поворота платформы против часовой стрелки +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "left" +4. Платформа должна начать поворачиваться против часовой стрелки + +#### Поворот сервоприводов в плоскости xy + +1. 7 +2. Проверка возможности поворота сервоприводов в плоскости xy +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Servo" + 3. Нажмите на кнопку right +4. Платформа должна изменить угол отклонения сервопривода + +#### Поворот сервоприводов в плоскости xz + +1. 8 +2. Проверка возможности поворота сервоприводов в плоскости xz +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Servo" + 3. Нажмите на кнопку "up" +4. Платформа должна поднять сервопривод вверх + +#### Получение информации с датчиков линии. Белый лист + +1. 9 +2. Получение информации с датчиков линии. Проверка корректного определения белого цвета +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Положите под платформу лист белой бумаги + 3. Нажмите на кнопку "Sensors" +4. В приложении напротив нумерации датчиков линии должно появиться значение 0 + +#### Получение информации с датчиков линии. Черный лист + +1. 10 +2. Получение информации с датчиков линии. Проверка корректного определения черного цвета +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Положите под платформу лист черной бумаги + 3. Нажмите на кнопку "Sensors" +4. В приложении напротив нумерации датчиков линии должно появиться значение 1 + +#### Получение информации с датчиков расстояния + +1. 11 +2. Получение информации с датчиков расстояния +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Подставьте перед центральным датчиком расстояния какой-нибудь непрозрачный предмет, например книгу, на расстоянии приблизительно 15 сантиметров + 3. Нажмите на кнопку "Sensors" +4. В приложении должно появится значение от 10 до 19 + +#### Смена языка + +1. 12 +2. Смена языка интерфеса +3. Произведите следующие шаги: + 1. Нажмите на кнопку "Settings" в главном меню + 2. Измените язык +4. В приложении должен измениться язык интерфейса + +#### Выбор другого API + +1. 13 +2. Смена API +3. Произведите следующие шаги: + 1. Нажмите на кнопку "Settings" в главном меню + 2. Выберите другой API +4. Приложение должно продолжать работу, все команды пользователя должны выполняться + +### Вывод + +Данные тесты показывают выполнение функциональных требований. Соответствие функциональных требований и тестов: + +| Функциональные требования | ID теста | +| ---------------------------------------- | :------: | +| Поддержка беспроводной связи с платформой через Bluetooth | 1-2 | +| Получение и вывод информации с датчиков линии | 9-10 | +| Получение и вывод информации с датчиков расстояни | 11 | +| Управление гусеницами платформы | 3-6 | +| Управление сервоприводами платформы | 7-8 | +| Выбор языка (русского или английского) | 12 | +| Выбор нескольких версии API для взаимодействия с платформой | 13 | \ No newline at end of file diff --git a/documentation/tests.md b/documentation/tests.md new file mode 100644 index 0000000..df1783d --- /dev/null +++ b/documentation/tests.md @@ -0,0 +1,171 @@ +# Проверка тестовых сценариев + +## Представление результатов + +Предоставление результатов требуется описать в следующем виде: + +1. Идентификатор +2. Назначение / название +3. Сценарий +4. Ожидаемый результат +5. Фактический результат (заполняется на этапе тестирования) +6. Оценка (заполняется на этапе тестирования) + +## Тестовые сценарии: + +#### Возможность подключения к платформе + +1. 1 +2. Возможность подключения к платформе +3. Произведите следующие шаги: + + 1. Включите платформу + + 2. Дождитесь загрузки платформы + + 3. Запустите приложение +4. В приложении появится надпись "Connected" +5. В приложении появилась надпись "Connected" +6. Выполнен + +#### Возможность принудительного отключения от платформы + +1. 2 +2. Возможность принудительного отключения от платформы по завершению работы с ней +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Нажать кнопку Exit в главном меню приложения + 3. Попробуйте заново подключиться к платформе +4. В приложении, появится надпись "Connected" +5. В приложении появилась надпись "Connected" +6. Выполнен + +#### Движение вперед + +1. 3 +2. Проверка движения платформы вперед +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "forward" +4. Платформа должна поехать вперед +5. Платформа поехала вперед +6. Выполнен + +#### Движение назад + +1. 4 +2. Проверка движения платформы назад +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "back" +4. Платформа должна поехать назад +5. Платформа поехала назад +6. Выполнен + +#### Разворот по направлению движения часовой стрелки + +1. 5 +2. Проверка возможности поворота платформы по часовой стрелке +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "right" +4. Платформа должна начать поворачиваться по часовой стрелке +5. Платформа начала поворачиваться по часовой стрелке +6. Выполнен + +#### Разворот против направления движения часовой стрелки + +1. 6 +2. Проверка возможности поворота платформы против часовой стрелки +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Motion" + 3. Выберите в приложении "left" +4. Платформа должна начать поворачиваться против часовой стрелки +5. Платформа начала поворачиваться против часовой стрелки +6. Выполнен + +#### Поворот сервоприводов в плоскости xy + +1. 7 +2. Проверка возможности поворота сервоприводов в плоскости xy +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Servo" + 3. Нажмите на кнопку right +4. Платформа должна изменить угол отклонения сервопривода +5. Сервопривод на платформе повернулся вправо +6. Выполнен + +#### Поворот сервоприводов в плоскости xz + +1. 8 +2. Проверка возможности поворота сервоприводов в плоскости xz +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Перейти из главного меню в меню "Servo" + 3. Нажмите на кнопку "up" +4. Платформа должна поднять сервопривод вверх +5. Сервопривод на платформе повернулся вверх +6. Выполнен + +#### Получение информации с датчиков линии. Белый лист + +1. 9 +2. Получение информации с датчиков линии. Проверка корректного определения белого цвета +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Положите под платформу лист белой бумаги + 3. Нажмите на кнопку "Sensors" +4. В приложении напротив нумерации датчиков линии должно появиться значение 0 +5. Были значения как 0, так и 1 +6. Не выполнен + +#### Получение информации с датчиков линии. Черный лист + +1. 10 +2. Получение информации с датчиков линии. Проверка корректного определения черного цвета +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Положите под платформу лист черной бумаги + 3. Нажмите на кнопку "Sensors" +4. В приложении напротив нумерации датчиков линии должно появиться значение 1 +5. Были значения как 0, так и 1 +6. Не выполнен + +#### Получение информации с датчиков расстояния + +1. 11 +2. Получение информации с датчиков расстояния +3. Произведите следующие шаги: + 1. Подключитесь к платформе + 2. Подставьте перед центральным датчиком расстояния какой-нибудь непрозрачный предмет, например книгу, на расстоянии приблизительно 15 сантиметров + 3. Нажмите на кнопку "Sensors" +4. В приложении должно появится значение от 10 до 19 +5. В приложении появилось значение 21 напротив значения центрального датчика +6. Не выполнен + +#### Смена языка + +1. 12 +2. Смена языка интерфеса +3. Произведите следующие шаги: + 1. Нажмите на кнопку "Settings" в главном меню + 2. Измените язык +4. В приложении должен измениться язык интерфейса +5. В приложении измелися интерфейс +6. Выполнен + +#### Выбор другого API + +1. 13 +2. Смена API +3. Произведите следующие шани: + 1. Нажмите на кнопку "Settings" в главном меню + 2. Выберите дргой API +4. Приложение должно продолжать работу, все команды пользователя должны выполняться +5. Свзясь с платформой прервалась +6. Не выполнен \ No newline at end of file diff --git a/documentation/user_interface/main_menu.png b/documentation/user_interface/main_menu.png new file mode 100644 index 0000000..4bdeb46 Binary files /dev/null and b/documentation/user_interface/main_menu.png differ diff --git a/documentation/user_interface/motion_activity.png b/documentation/user_interface/motion_activity.png new file mode 100644 index 0000000..7146d4e Binary files /dev/null and b/documentation/user_interface/motion_activity.png differ diff --git a/documentation/user_interface/sensors_activity.png b/documentation/user_interface/sensors_activity.png new file mode 100644 index 0000000..aa851e8 Binary files /dev/null and b/documentation/user_interface/sensors_activity.png differ diff --git a/documentation/user_interface/servo_activity.png b/documentation/user_interface/servo_activity.png new file mode 100644 index 0000000..eef3253 Binary files /dev/null and b/documentation/user_interface/servo_activity.png differ diff --git a/documentation/user_interface/settings_activity.png b/documentation/user_interface/settings_activity.png new file mode 100644 index 0000000..68b23eb Binary files /dev/null and b/documentation/user_interface/settings_activity.png differ diff --git "a/documentation/\320\230\320\264\320\265\320\270 \320\264\320\273\321\217 \321\200\320\265\320\260\320\273\320\270\320\267\320\260\321\206\320\270\320\270.txt" "b/documentation/\320\230\320\264\320\265\320\270 \320\264\320\273\321\217 \321\200\320\265\320\260\320\273\320\270\320\267\320\260\321\206\320\270\320\270.txt" new file mode 100644 index 0000000..2b5750f --- /dev/null +++ "b/documentation/\320\230\320\264\320\265\320\270 \320\264\320\273\321\217 \321\200\320\265\320\260\320\273\320\270\320\267\320\260\321\206\320\270\320\270.txt" @@ -0,0 +1,3 @@ +Изменить реализацю API. Применить паттерн Stratagy для API. +Делайн по 4ой до 1 декабря. +С диаграммы компонентов можно все убрать. \ No newline at end of file