diff --git a/.gitignore b/.gitignore index d1a0593..f7eedb9 100644 --- a/.gitignore +++ b/.gitignore @@ -45,6 +45,9 @@ TestResult.xml [Rr]eleasePS/ dlldata.c +# Benchmark Results +BenchmarkDotNet.Artifacts/ + # .NET Core project.lock.json project.fragment.lock.json @@ -186,6 +189,7 @@ AppPackages/ BundleArtifacts/ Package.StoreAssociation.xml _pkginfo.txt +*.appx # Visual Studio cache files # files ending in .cache can be ignored @@ -281,6 +285,9 @@ __pycache__/ # tools/** # !tools/packages.config +# Tabs Studio +*.tss + # Telerik's JustMock configuration file *.jmconfig @@ -288,4 +295,8 @@ __pycache__/ *.btp.cs *.btm.cs *.odx.cs -*.xsd.cs \ No newline at end of file +*.xsd.cs + +# AJIOB_Exclude +Output +Build* diff --git a/.gitmodules b/.gitmodules index a89bce8..77d47f2 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,9 +1,9 @@ [submodule "cxx_serial_support"] - path = code/c++/cxx-api/serial_support + path = cxx-api/serial_support url = https://github.com/wjwwood/serial.git [submodule "cxx_gamepad_support"] - path = code/c++/cxx-gamepad-app/gamepad_support + path = cxx-gamepad-app/gamepad_support url = https://github.com/AJIOB/libstem_gamepad.git [submodule "cxx_libcrc"] - path = code/c++/cxx-api/libcrc + path = cxx-api/libcrc url = https://github.com/lammertb/libcrc.git diff --git a/README.md b/README.md index a464d86..d658e41 100644 --- a/README.md +++ b/README.md @@ -10,11 +10,10 @@ Используемые модули: - Wi-Fi (ESP8266) -- Bluetooth (HC-05) +- Bluetooth (HC-06) - Драйвер двигателя (L298N) - Поворотная платформа - -Для отладки требуется небольная модификация исходников Arduino IDE в соответствии с [этой](https://playground.arduino.cc/Main/Printf) статьей. +- Одноцветный OLED дисплей 128x64 на основе контроллера SSD1306 Датчики расстояния объеденены в модуль, который несложно снимается, что позволяет заменить датчики. В модуле 5 датчиков расстояния, расположенных под различными углами для улучшения ориентирования на местности. Так же углы поворота датчиков можно настраивать в небольшом диапазоне. Расположены спереди платформы. diff --git a/code/Arduino/RCa03124 b/code/Arduino/RCa03124 deleted file mode 100644 index 6c82d6d..0000000 Binary files a/code/Arduino/RCa03124 and /dev/null differ diff --git a/code/Arduino/config/Constants.cpp b/code/Arduino/config/Constants.cpp deleted file mode 100644 index 552ad65..0000000 --- a/code/Arduino/config/Constants.cpp +++ /dev/null @@ -1,73 +0,0 @@ -#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 deleted file mode 100644 index 8fb74e1..0000000 --- a/code/Arduino/config/Constants.h +++ /dev/null @@ -1,65 +0,0 @@ -#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 deleted file mode 100644 index 12211f7..0000000 --- a/code/Arduino/connection/Bluetooth.cpp +++ /dev/null @@ -1,16 +0,0 @@ -#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 deleted file mode 100644 index 1af7003..0000000 --- a/code/Arduino/connection/Bluetooth.h +++ /dev/null @@ -1,19 +0,0 @@ -#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 deleted file mode 100644 index 27a0c14..0000000 --- a/code/Arduino/connection/ConnectionManager.cpp +++ /dev/null @@ -1,292 +0,0 @@ -#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 deleted file mode 100644 index 059e5f2..0000000 --- a/code/Arduino/connection/ConnectionManager.h +++ /dev/null @@ -1,50 +0,0 @@ -#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 deleted file mode 100644 index 7b48f33..0000000 --- a/code/Arduino/connection/DebugSerial.cpp +++ /dev/null @@ -1,82 +0,0 @@ -#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 deleted file mode 100644 index 4d8d300..0000000 --- a/code/Arduino/connection/DebugSerial.h +++ /dev/null @@ -1,87 +0,0 @@ -#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 deleted file mode 100644 index 3ea0cab..0000000 --- a/code/Arduino/connection/IConnector.cpp +++ /dev/null @@ -1,52 +0,0 @@ -#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 deleted file mode 100644 index a1ee0c4..0000000 --- a/code/Arduino/connection/IConnector.h +++ /dev/null @@ -1,21 +0,0 @@ -#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 deleted file mode 100644 index 1c4bbff..0000000 --- a/code/Arduino/connection/USB.cpp +++ /dev/null @@ -1,16 +0,0 @@ -#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 deleted file mode 100644 index c5beae0..0000000 --- a/code/Arduino/connection/USB.h +++ /dev/null @@ -1,19 +0,0 @@ -#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 deleted file mode 100644 index 2c9a97d..0000000 --- a/code/Arduino/connection/WiFi_my.cpp +++ /dev/null @@ -1,259 +0,0 @@ -#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 deleted file mode 100644 index bf00ec2..0000000 --- a/code/Arduino/connection/WiFi_my.h +++ /dev/null @@ -1,55 +0,0 @@ -#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 deleted file mode 100644 index 7325e4b..0000000 --- a/code/Arduino/management/CommandManager.cpp +++ /dev/null @@ -1,257 +0,0 @@ -#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 deleted file mode 100644 index 35efe92..0000000 --- a/code/Arduino/management/CommandManager.h +++ /dev/null @@ -1,50 +0,0 @@ -#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 deleted file mode 100644 index 759c863..0000000 --- a/code/Arduino/management/MainManager.cpp +++ /dev/null @@ -1,85 +0,0 @@ -#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 deleted file mode 100644 index 581ca4a..0000000 --- a/code/Arduino/management/MainManager.h +++ /dev/null @@ -1,21 +0,0 @@ -#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 deleted file mode 100644 index 5a7ef36..0000000 --- a/code/Arduino/peripheral/ConnectionController.cpp +++ /dev/null @@ -1,180 +0,0 @@ -#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 deleted file mode 100644 index b51bfe5..0000000 --- a/code/Arduino/peripheral/ConnectionController.h +++ /dev/null @@ -1,33 +0,0 @@ -#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 deleted file mode 100644 index 245dbe2..0000000 --- a/code/Arduino/peripheral/DistanceSensorManager.cpp +++ /dev/null @@ -1,54 +0,0 @@ -#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 deleted file mode 100644 index 8f908de..0000000 --- a/code/Arduino/peripheral/DistanceSensorManager.h +++ /dev/null @@ -1,29 +0,0 @@ -#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 deleted file mode 100644 index 1c4b0ec..0000000 --- a/code/Arduino/peripheral/EngineManager.cpp +++ /dev/null @@ -1,78 +0,0 @@ -#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 deleted file mode 100644 index 4bd410f..0000000 --- a/code/Arduino/peripheral/EngineManager.h +++ /dev/null @@ -1,40 +0,0 @@ -#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 deleted file mode 100644 index 5407e49..0000000 --- a/code/Arduino/peripheral/IBasicSensorManager.h +++ /dev/null @@ -1,14 +0,0 @@ -#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 deleted file mode 100644 index 70e20d2..0000000 --- a/code/Arduino/peripheral/LineSensorManager.cpp +++ /dev/null @@ -1,53 +0,0 @@ -#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 deleted file mode 100644 index f96e036..0000000 --- a/code/Arduino/peripheral/LineSensorManager.h +++ /dev/null @@ -1,19 +0,0 @@ -#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 deleted file mode 100644 index 084fb63..0000000 --- a/code/Arduino/peripheral/SensorManager.cpp +++ /dev/null @@ -1,49 +0,0 @@ -#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 deleted file mode 100644 index 9efba59..0000000 --- a/code/Arduino/peripheral/SensorManager.h +++ /dev/null @@ -1,25 +0,0 @@ -#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 deleted file mode 100644 index bb9668e..0000000 --- a/code/Arduino/peripheral/ServoManager.cpp +++ /dev/null @@ -1,49 +0,0 @@ -#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 deleted file mode 100644 index 120b261..0000000 --- a/code/Arduino/peripheral/ServoManager.h +++ /dev/null @@ -1,23 +0,0 @@ -#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 deleted file mode 100644 index 3a68633..0000000 --- a/code/Arduino/peripheral/SharpIR.cpp +++ /dev/null @@ -1,151 +0,0 @@ -/* - 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 deleted file mode 100644 index d5f6788..0000000 --- a/code/Arduino/peripheral/SharpIR.h +++ /dev/null @@ -1,40 +0,0 @@ -/* - 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/resource.h b/code/Arduino/resource.h deleted file mode 100644 index 976e8c7..0000000 --- a/code/Arduino/resource.h +++ /dev/null @@ -1,14 +0,0 @@ -//{{NO_DEPENDENCIES}} -// Microsoft Visual C++ generated include file. -// Used by trackPlatform.rc - -// -// -#ifdef APSTUDIO_INVOKED -#ifndef APSTUDIO_READONLY_SYMBOLS -#define _APS_NEXT_RESOURCE_VALUE 101 -#define _APS_NEXT_COMMAND_VALUE 40001 -#define _APS_NEXT_CONTROL_VALUE 1001 -#define _APS_NEXT_SYMED_VALUE 101 -#endif -#endif diff --git a/code/Arduino/trackPlatform.ino b/code/Arduino/trackPlatform.ino deleted file mode 100644 index 573f1f4..0000000 --- a/code/Arduino/trackPlatform.ino +++ /dev/null @@ -1,29 +0,0 @@ -#include -#include -#include -#include -#include -#include "connection/DebugSerial.h" -#include "management/MainManager.h" -#include "management/CommandManager.h" -#include "connection/ConnectionManager.h" - -void setup() -{ - 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"); - - // First init of static fields - MainManager::get_manager(); - ConnectionManager::get_manager(); - CommandManager::getManager(); - - DEBUG_PRINTLN("Arduino was started"); -} - -void loop() -{ - MainManager::get_manager()->run(); -} diff --git a/code/Arduino/trackPlatform.rc b/code/Arduino/trackPlatform.rc deleted file mode 100644 index bbb3f98..0000000 Binary files a/code/Arduino/trackPlatform.rc and /dev/null differ diff --git a/code/Arduino/trackPlatform.sln b/code/Arduino/trackPlatform.sln deleted file mode 100644 index b6a6526..0000000 --- a/code/Arduino/trackPlatform.sln +++ /dev/null @@ -1,22 +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.vcxproj", "{C5F80730-F44F-4478-BDAE-6634EFC2CA88}" -EndProject -Global - GlobalSection(SolutionConfigurationPlatforms) = preSolution - Debug|x86 = Debug|x86 - Release|x86 = Release|x86 - EndGlobalSection - GlobalSection(ProjectConfigurationPlatforms) = postSolution - {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Debug|x86.ActiveCfg = Debug|Win32 - {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Debug|x86.Build.0 = Debug|Win32 - {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Release|x86.ActiveCfg = Release|Win32 - {C5F80730-F44F-4478-BDAE-6634EFC2CA88}.Release|x86.Build.0 = Release|Win32 - EndGlobalSection - GlobalSection(SolutionProperties) = preSolution - HideSolutionNode = FALSE - EndGlobalSection -EndGlobal diff --git a/code/Arduino/trackPlatform.vcxproj b/code/Arduino/trackPlatform.vcxproj deleted file mode 100644 index 6fa02b7..0000000 --- a/code/Arduino/trackPlatform.vcxproj +++ /dev/null @@ -1,147 +0,0 @@ - - - - - Debug - Win32 - - - Release - Win32 - - - - {C5F80730-F44F-4478-BDAE-6634EFC2CA88} - - - trackPlatform - 8.1 - - - - Application - true - - - Unicode - - - Application - false - - - true - MultiByte - - - - - - - - - - - - - - - Level3 - Disabled - true - 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=10804;ARDUINO_AVR_MEGA2560;ARDUINO_ARCH_AVR;__cplusplus=201103L;_VMICRO_INTELLISENSE;%(PreprocessorDefinitions) - - - true - - - - - Level3 - Disabled - true - true - true - 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=10804;ARDUINO_AVR_MEGA2560;ARDUINO_ARCH_AVR;__cplusplus=201103L;_VMICRO_INTELLISENSE;%(PreprocessorDefinitions) - - - true - true - true - - - - - - - - CppCode - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - VisualMicroDebugger - - - - - - - - - - \ No newline at end of file diff --git a/code/Arduino/trackPlatform.vcxproj.filters b/code/Arduino/trackPlatform.vcxproj.filters deleted file mode 100644 index f27af4b..0000000 --- a/code/Arduino/trackPlatform.vcxproj.filters +++ /dev/null @@ -1,202 +0,0 @@ - - - - - {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 - - - {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 - - - - - - - - Header Files - - - Header Files - - - Header Files - - - utils\header - - - utils\header - - - peripheral\header - - - peripheral\header - - - peripheral\header - - - peripheral\header - - - peripheral\header - - - peripheral\header - - - 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 - - - - - utils\source - - - peripheral\source - - - peripheral\source - - - peripheral\source - - - peripheral\source - - - peripheral\source - - - config\source - - - management\source - - - connection\source - - - connection\source - - - connection - - - connection\source - - - connection\source - - - utils\source - - - management\source - - - utils\source - - - connection\source - - - peripheral\source - - - - - Resource Files - - - \ No newline at end of file diff --git a/code/Arduino/utils/Converter.cpp b/code/Arduino/utils/Converter.cpp deleted file mode 100644 index ae59695..0000000 --- a/code/Arduino/utils/Converter.cpp +++ /dev/null @@ -1,53 +0,0 @@ -#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 deleted file mode 100644 index 3c560b1..0000000 --- a/code/Arduino/utils/Converter.h +++ /dev/null @@ -1,13 +0,0 @@ -#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 deleted file mode 100644 index 5c747e1..0000000 --- a/code/Arduino/utils/ErrorManager.cpp +++ /dev/null @@ -1,35 +0,0 @@ -#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 deleted file mode 100644 index 7f76567..0000000 --- a/code/Arduino/utils/ErrorManager.h +++ /dev/null @@ -1,19 +0,0 @@ -#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 deleted file mode 100644 index 95a81cb..0000000 --- a/code/Arduino/utils/Timer.cpp +++ /dev/null @@ -1,102 +0,0 @@ -#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 deleted file mode 100644 index 77379b8..0000000 --- a/code/Arduino/utils/Timer.h +++ /dev/null @@ -1,68 +0,0 @@ -#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 deleted file mode 100644 index 09a18b9..0000000 --- a/code/Arduino/utils/Vector.h +++ /dev/null @@ -1,90 +0,0 @@ -#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/API/ConnectedThread.java b/code/Java/Mobile/API/ConnectedThread.java deleted file mode 100755 index dad14fd..0000000 --- a/code/Java/Mobile/API/ConnectedThread.java +++ /dev/null @@ -1,88 +0,0 @@ -package com.example.yuras.trackplatformapi; - -import android.bluetooth.BluetoothSocket; -import android.os.Bundle; -import android.os.Handler; -import android.os.Message; -import android.util.Log; - -import java.io.IOException; -import java.io.InputStream; -import java.io.OutputStream; - -public class ConnectedThread extends Thread implements Constants { - private final InputStream mmInStream; - private final OutputStream mmOutStream; - private final Handler handler; - private BluetoothSocket socket; - - public ConnectedThread(BluetoothSocket socket, Handler handler) { - InputStream tmpIn = null; - OutputStream tmpOut = null; - this.handler = handler; - this.socket = socket; - - try { - tmpIn = socket.getInputStream(); - } catch (IOException e) { - Log.e(TAG, "Error occurred when creating input stream", e); - } - try { - tmpOut = socket.getOutputStream(); - } catch (IOException e) { - Log.e(TAG, "Error occurred when creating output stream", e); - } - - mmInStream = tmpIn; - mmOutStream = tmpOut; - } - - public void run() { - byte[] buffer = new byte[1024]; - int numBytes; - - while (true) { - try { - numBytes = mmInStream.read(buffer); - Message readMsg = handler.obtainMessage(Constants.MESSAGE_READ, numBytes, -1, buffer); - readMsg.sendToTarget(); - } catch (IOException e) { - Log.d(TAG, "Input stream was disconnected", e); - break; - - } - } - } - - public void write(String message) { - Log.d("BLUETOOTH", "Data to send: " + message); - byte[] msgBuffer = message.getBytes(); - try { - mmOutStream.write(msgBuffer); - Message writtenMsg = handler.obtainMessage( - Constants.MESSAGE_WRITE, -1, -1, msgBuffer); - writtenMsg.sendToTarget(); - - } catch (IOException e) { - Log.e(TAG, "Error occurred when sending data", e); - - Message writeErrorMsg = - handler.obtainMessage(Constants.MESSAGE_TOAST); - Bundle bundle = new Bundle(); - bundle.putString("toast", - "Couldn't send data to the other device"); - writeErrorMsg.setData(bundle); - handler.sendMessage(writeErrorMsg); - - } - } - - public void cancel() { - try { - socket.close(); - } catch (IOException e) { - Log.e(TAG, "Could not close the connect socket", e); - } - } - -} diff --git a/code/Java/Mobile/API/Constants.java b/code/Java/Mobile/API/Constants.java deleted file mode 100755 index 2e7d657..0000000 --- a/code/Java/Mobile/API/Constants.java +++ /dev/null @@ -1,10 +0,0 @@ -package com.example.yuras.trackplatformapi; - -public interface Constants { - String TAG = "BLUETOOTH"; - String BLUETOOTH_MAC = "20:16:04:11:37:56"; - - int MESSAGE_READ = 0; - int MESSAGE_WRITE = 1; - int MESSAGE_TOAST = 2; -} diff --git a/code/Java/Mobile/API/MainActivity.java b/code/Java/Mobile/API/MainActivity.java deleted file mode 100644 index 2c84f60..0000000 --- a/code/Java/Mobile/API/MainActivity.java +++ /dev/null @@ -1,48 +0,0 @@ -package com.example.yuras.trackplatformapi; - -import android.support.v7.app.AppCompatActivity; -import android.os.Bundle; -import android.view.View; -import android.widget.Button; -import android.widget.EditText; -import android.widget.TextView; - -public class MainActivity extends AppCompatActivity { - private TrackPlatform trackPlatform; - - private TextView textView; - private EditText editText; - private Button button; - - @Override - protected void onCreate(Bundle savedInstanceState) { - super.onCreate(savedInstanceState); - setContentView(R.layout.activity_main); - - trackPlatform = new TrackPlatform(this); - - textView = (TextView) findViewById(R.id.text_from_bt); - editText = (EditText) findViewById(R.id.edit_text); - button = (Button) findViewById(R.id.send_button); - - button.setOnClickListener(new View.OnClickListener() { - @Override - public void onClick(View view) { - trackPlatform.send(editText.getText().toString()); - } - }); - } - - @Override - protected void onResume() { - super.onResume(); - trackPlatform.connect(); - } - - @Override - public void onPause() { - super.onPause(); - trackPlatform.disconnect(); - } - -} diff --git a/code/Java/Mobile/API/MovingCommands.java b/code/Java/Mobile/API/MovingCommands.java deleted file mode 100755 index e0d487a..0000000 --- a/code/Java/Mobile/API/MovingCommands.java +++ /dev/null @@ -1,19 +0,0 @@ -package com.example.yuras.trackplatformapi; - -enum MovingCommands { - FORWARD('\001'), - LEFT('\002'), - RIGHT('\003'), - BACK('\004'), - STOP('\005'); - - private final char value; - - MovingCommands(char value) { - this.value = value; - } - - public char getValue() { - return value; - } -} diff --git a/code/Java/Mobile/API/TrackPlatform.java b/code/Java/Mobile/API/TrackPlatform.java deleted file mode 100755 index b206d56..0000000 --- a/code/Java/Mobile/API/TrackPlatform.java +++ /dev/null @@ -1,98 +0,0 @@ -package com.example.yuras.trackplatformapi; - -import android.app.Activity; -import android.bluetooth.BluetoothAdapter; -import android.bluetooth.BluetoothDevice; -import android.bluetooth.BluetoothSocket; -import android.content.Intent; -import android.os.Handler; -import android.util.Log; -import android.widget.Toast; - -import java.io.IOException; -import java.lang.reflect.Method; - -public class TrackPlatform implements Constants { - private Activity activity; - - private Handler handler; - private BluetoothAdapter btAdapter = null; - private BluetoothSocket btSocket = null; - private ConnectedThread connectedThread; - - public TrackPlatform(Activity activity, Handler handler) { - btAdapter = BluetoothAdapter.getDefaultAdapter(); - this.handler = handler; - - this.activity = activity; - } - - public void connect() { - checkBtState(); - BluetoothDevice device = btAdapter.getRemoteDevice(Constants.BLUETOOTH_MAC); - try { - btSocket = createBluetoothSocket(device); - } catch (IOException e) { - Log.d(TAG, e.getMessage()); - } - - btAdapter.cancelDiscovery(); - try { - btSocket.connect(); - Log.d(TAG, "Connecting: Ok"); - } catch (IOException e) { - try { - btSocket.close(); - } catch (IOException e2) { - errorExit("Fatal Error", "In onResume(): to close socket during connection failure" + e2.getMessage() + "."); - } - } - - connectedThread = new ConnectedThread(btSocket, handler); - connectedThread.start(); - } - - public void disconnect() { - try { - btSocket.close(); - connectedThread.cancel(); - } catch (IOException e) { - errorExit("Fatal Error", "In onPause() and failed to close socket." + e.getMessage() + "."); - } - } - - public void send(String msg) { - connectedThread.write(msg); - } - - private void checkBtState() { - if(btAdapter == null) { - errorExit("Fatal Error", "Bluetooth not support"); - } else { - if (btAdapter.isEnabled()) { - Log.d(Constants.TAG, "...Bluetooth ON..."); - } else { - Intent enableBtIntent = new Intent(BluetoothAdapter.ACTION_REQUEST_ENABLE); - activity.startActivityForResult(enableBtIntent, 1); - } - } - } - - private void errorExit(String title, String message){ - Toast.makeText(activity.getBaseContext(), title + " - " + message, Toast.LENGTH_LONG).show(); - activity.finish(); - } - - 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; - } -} diff --git a/code/Java/Mobile/Application2.0/.gitignore b/code/Java/Mobile/Application2.0/.gitignore deleted file mode 100644 index bd1302f..0000000 --- a/code/Java/Mobile/Application2.0/.gitignore +++ /dev/null @@ -1,18 +0,0 @@ -*.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/Application2.0/app/.gitignore b/code/Java/Mobile/Application2.0/app/.gitignore deleted file mode 100644 index 796b96d..0000000 --- a/code/Java/Mobile/Application2.0/app/.gitignore +++ /dev/null @@ -1 +0,0 @@ -/build diff --git a/code/Java/Mobile/Application2.0/app/build.gradle b/code/Java/Mobile/Application2.0/app/build.gradle deleted file mode 100644 index 6978f68..0000000 --- a/code/Java/Mobile/Application2.0/app/build.gradle +++ /dev/null @@ -1,32 +0,0 @@ -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/Application2.0/app/proguard-rules.pro b/code/Java/Mobile/Application2.0/app/proguard-rules.pro deleted file mode 100644 index ce3149c..0000000 --- a/code/Java/Mobile/Application2.0/app/proguard-rules.pro +++ /dev/null @@ -1,25 +0,0 @@ -# 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/Application2.0/app/src/androidTest/java/com/example/kimentii/application20/ExampleInstrumentedTest.java b/code/Java/Mobile/Application2.0/app/src/androidTest/java/com/example/kimentii/application20/ExampleInstrumentedTest.java deleted file mode 100644 index 6c71eb3..0000000 --- a/code/Java/Mobile/Application2.0/app/src/androidTest/java/com/example/kimentii/application20/ExampleInstrumentedTest.java +++ /dev/null @@ -1,26 +0,0 @@ -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 deleted file mode 100644 index 3aefa4b..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/AndroidManifest.xml +++ /dev/null @@ -1,37 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - \ 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 deleted file mode 100644 index 8ea9c9c..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/MainActivity.java +++ /dev/null @@ -1,164 +0,0 @@ -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 deleted file mode 100644 index d2f13bc..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/MotionActivity.java +++ /dev/null @@ -1,117 +0,0 @@ -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 deleted file mode 100644 index 4e77542..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/SensorsActivity.java +++ /dev/null @@ -1,173 +0,0 @@ -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 deleted file mode 100644 index a8805cf..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/ServoActivity.java +++ /dev/null @@ -1,103 +0,0 @@ -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 deleted file mode 100644 index 51551a8..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/activities/SettingsActivity.java +++ /dev/null @@ -1,131 +0,0 @@ -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 deleted file mode 100644 index 0b5e998..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API.java +++ /dev/null @@ -1,47 +0,0 @@ -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 deleted file mode 100644 index 5d64887..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API1.java +++ /dev/null @@ -1,82 +0,0 @@ -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 deleted file mode 100644 index f92df56..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API2.java +++ /dev/null @@ -1,81 +0,0 @@ -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 deleted file mode 100644 index a4ee745..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API3.java +++ /dev/null @@ -1,81 +0,0 @@ -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 deleted file mode 100644 index 99e71c2..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/API4.java +++ /dev/null @@ -1,169 +0,0 @@ -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 deleted file mode 100644 index 260f943..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/api/CRC16Modbus.java +++ /dev/null @@ -1,71 +0,0 @@ -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 deleted file mode 100644 index bea6d52..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/connectors/BluetoothConnector.java +++ /dev/null @@ -1,210 +0,0 @@ -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 deleted file mode 100644 index d482db4..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/constants/Constants.java +++ /dev/null @@ -1,128 +0,0 @@ -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 deleted file mode 100644 index 3d4c5e7..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/MotionController.java +++ /dev/null @@ -1,39 +0,0 @@ -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 deleted file mode 100644 index 8e79524..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/SensorsController.java +++ /dev/null @@ -1,21 +0,0 @@ -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 deleted file mode 100644 index 8da389d..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/ServoController.java +++ /dev/null @@ -1,55 +0,0 @@ -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 deleted file mode 100644 index e4d0a5e..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/controllers/SettingsController.java +++ /dev/null @@ -1,15 +0,0 @@ -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 deleted file mode 100644 index a6dd562..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/language_resources/EnglishLanguage.java +++ /dev/null @@ -1,74 +0,0 @@ -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 deleted file mode 100644 index 5d1c7d8..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/language_resources/RussianLanguage.java +++ /dev/null @@ -1,73 +0,0 @@ -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 deleted file mode 100644 index 722c6f3..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/settings/Settings.java +++ /dev/null @@ -1,53 +0,0 @@ -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 deleted file mode 100644 index 260b64b..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/java/com/example/kimentii/application20/wrappers/LanguageWrapper.java +++ /dev/null @@ -1,66 +0,0 @@ -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 deleted file mode 100644 index 29b1eba..0000000 --- a/code/Java/Mobile/Application2.0/app/src/main/res/layout/activity_main.xml +++ /dev/null @@ -1,58 +0,0 @@ - - - - - - - -