近藤さんプログラム集

近藤さんプログラム集

Arduino IDEのESP32ボードマネージャ3.0で動作確認したもの。
VScode(PlatformIO)の場合は「4輪駆動車のプログラム集」参照。


1.BLEリモコン(リモコン側)

// === ESP32 BLE Server sample skech === #include <BLEDevice.h> #include <BLEServer.h> #include <BLEUtils.h> #include <BLE2902.h> #include <Ticker.h> Ticker ticker; BLEServer *pServer = NULL; BLECharacteristic *pTxCharacteristic; bool deviceConnected = false; bool oldDeviceConnected = false; // See the following for generating UUIDs: Access the link (Ctrl + click) // https://www.uuidgenerator.net/ // Server and Client RX TX cross #define SERVICE_UUID "7a00b9b5-23f3-4fd7-9271-96aee32da1a3" #define CHARACTERISTIC_UUID_RX "8b165c5d-ce72-452f-af50-67cb23484128" #define CHARACTERISTIC_UUID_TX "16da53f0-7116-4d54-b676-b81a86e3f407" #define SERVER_NAME "esp32ble" // I/O configuration #define potX 14 // connect ESP32 Board 14 pin to joystick VRy #define potY 12 // connect ESP32 Board 12 pin to joystick VRx #define joyK 13 // connect ESP32 Board 13 pin to joystick Button #define BuiltinLED 2 uint16_t neutral_potX; uint16_t neutral_potY; uint16_t potX_val; uint16_t potY_val; uint16_t potX_data; uint16_t potY_data; uint16_t Txflag_F; uint16_t button_K; uint16_t data0 = 0; String rx_Data; class MyServerCallbacks : public BLEServerCallbacks { void onConnect(BLEServer *pServer) { deviceConnected = true; }; void onDisconnect(BLEServer *pServer) { deviceConnected = false; } }; class MyCallbacks : public BLECharacteristicCallbacks { void onWrite(BLECharacteristic *pCharacteristic) { String rxValue = pCharacteristic->getValue(); if (rxValue.length() > 0) { for (int i = 0; i & lt; rxValue.length(); i++) rx_Data = rx_Data + rxValue[i]; } } }; // LED Blinker void ledBlink() { volatile static int led = HIGH; digitalWrite(BuiltinLED, led); led = !led; } void setup() { Serial.begin(115200); pinMode(potX, INPUT); pinMode(potY, INPUT); pinMode(joyK, INPUT_PULLUP); pinMode(BuiltinLED, OUTPUT); analogReadResolution(12); neutral_potX = map(analogRead(potX), 0, 4095, 0, 255); neutral_potY = map(analogRead(potY), 0, 4095, 0, 255); ticker.attach(0.1, ledBlink); Serial.println("BLE_Server_start"); delay(1000); // Create the BLE Device BLEDevice::init(SERVER_NAME); // Create the BLE Server BLEServer *pServer = BLEDevice::createServer(); pServer->setCallbacks(new MyServerCallbacks()); // Create the BLE Service BLEService *pService = pServer->createService(SERVICE_UUID); // Create a BLE Characteristic pTxCharacteristic = pService->createCharacteristic( CHARACTERISTIC_UUID_TX, BLECharacteristic::PROPERTY_NOTIFY); pTxCharacteristic->addDescriptor(new BLE2902()); BLECharacteristic *pRxCharacteristic = pService->createCharacteristic( CHARACTERISTIC_UUID_RX, BLECharacteristic::PROPERTY_WRITE); pRxCharacteristic->setCallbacks(new MyCallbacks()); // Start the service pService->start(); // Start advertising pServer->getAdvertising()->start(); Serial.println("Waiting a client connection to notify..."); } void loop() { analogReadResolution(12); Txflag_F = 1; // Flag data potX_val = map(analogRead(potX), 0, 4095, 0, 255); // Pot_x data potY_val = map(analogRead(potY), 0, 4095, 0, 255); // Pot_y data button_K = !digitalRead(joyK); // Joystick Button data // convert potX neutral value if (neutral_potX >= potX_val) { potX_data = map(potX_val, neutral_potX, 0, 128, 0); } else if (neutral_potX & lt; potX_val) { potX_data = map(potX_val, neutral_potX, 255, 128, 255); } // convert potY neutral value if (neutral_potY >= potY_val) { potY_data = map(potY_val, neutral_potY, 0, 128, 0); } else if (neutral_potY & lt; potY_val) { potY_data = map(potY_val, neutral_potY, 255, 128, 255); } if (deviceConnected) { // char buffer[10]; char buffer[20]; // Send data write sprintf(buffer, "F:%d,X:%03d,Y:%03d,K:%d", Txflag_F, potX_data, potY_data, button_K); pTxCharacteristic->setValue(buffer); pTxCharacteristic->notify(); Serial.printf("*** NOTIFY: F:%d,X:%03d,Y:%03d,K:%d ***\n", Txflag_F, potX_data, potY_data, button_K); // Receive data read String Rxdata = rx_Data.c_str(); String str(Rxdata); String subf = str.substring(0, 1); data0 = subf.toInt(); // receive flag // Serial.printf("%s", rx_Data.c_str()); // delay(1000); } else { data0 = 0; } // Connected LED if (data0 == 1) { digitalWrite(BuiltinLED, HIGH); } // disconnecting if (!deviceConnected && oldDeviceConnected) { delay(500); // give the bluetooth stack the chance to get things ready pServer->startAdvertising(); // restart advertising Serial.println("start advertising"); oldDeviceConnected = deviceConnected; } // connecting if (deviceConnected && !oldDeviceConnected) { // do stuff here on connecting oldDeviceConnected = deviceConnected; } // Serial monitor // Serial.print(F("\n\rTxflag: ")); // Serial.print(Txflag_F); // Serial.print(F("\tpotX_data: ")); // Serial.print(potX_val); // Serial.print(F("\tpotY_data: ")); // Serial.print(potY_val); // Serial.print(F("\tbutton_K: ")); // Serial.print(button_K); }

2.BLEリモコン(本体側)

// === ESP32 BLE Client sample skech === #include <Arduino.h> #include <BLEDevice.h> #include <ESP32Servo.h> #include <Ticker.h> Ticker ticker; Servo myServo; // See the following for generating UUIDs: Access the link (Ctrl + click) // https://www.uuidgenerator.net/ // Server and Client UUID TX RX cross #define SERVICE_UUID "7a00b9b5-23f3-4fd7-9271-96aee32da1a3" #define CHARACTERISTIC_UUID_TX "8b165c5d-ce72-452f-af50-67cb23484128" #define CHARACTERISTIC_UUID_RX "16da53f0-7116-4d54-b676-b81a86e3f407" #define SERVER_NAME "esp32ble" #define Tx_value '1' // send to Server "1" // Board Using pin #define builtinLED 2 // Onboard Blue LED #define SERVO_PIN 13 // Servo Orange Wire #define LEDR 27 // Red LED #define LEDG 17 // Green LED #define LEDB 16 // Blue LED #define LEDC_in1 25 // PWM pin #define LEDC_in2 26 // PWM pin #define LEDC_in3 32 // PWM pin #define LEDC_in4 33 // PWM pin #define LEDC_channel_0 5 // Channel 5 #define LEDC_channel_1 6 // Channel 6 #define LEDC_channel_2 7 // Channel 7 #define LEDC_channel_3 8 // Channel 8 #define LEDC_freq 1000.0 // Career frequency 8kHz #define LEDC_resolution 8 // Resolution 8bit(0-255) int Rx_flag = 0; // received flag int Joystick_neutral; // Joystick neutral int xAxis = 512; // Joystick X-Nutral Value int yAxis = 512; // Joystick Y-Nutral Value int speedLeft = 100; // inverted data Min:100 Max:0 int speedRight = 100; int stop_speed = 255; // DC Motor Stop Value int data0, data1, data2, data3; // Receive data 0-3 unsigned long previoustime0 = 0; unsigned long previoustime1 = 0; unsigned long previoustime2 = 0; static BLEUUID serviceUUID(SERVICE_UUID); static BLEUUID charUUID_RX(CHARACTERISTIC_UUID_RX); static BLEUUID charUUID_TX(CHARACTERISTIC_UUID_TX); static BLEAddress* pServerAddress; static boolean doConnect = false; static boolean connected = false; static BLERemoteCharacteristic* pRemoteCharacteristicRX; static BLERemoteCharacteristic* pRemoteCharacteristicTX; static void notifyCallback( BLERemoteCharacteristic* pBLERemoteCharacteristic, uint8_t* pData, size_t length, bool isNotify) { Serial.print("Notify callback for characteristic "); Serial.print(pBLERemoteCharacteristic->getUUID().toString().c_str()); Serial.print(" of data length "); Serial.println(length); Serial.print("data: "); Serial.println((char*)pData); } class MyClientCallback : public BLEClientCallbacks { void onConnect(BLEClient* pclient) { } void onDisconnect(BLEClient* pclient) { connected = false; Serial.println("onDisconnect"); } }; bool connectToServer(BLEAddress pAddress) { Serial.print("Forming a connection to "); Serial.println(pAddress.toString().c_str()); BLEClient* pClient = BLEDevice::createClient(); Serial.println(" - Created client"); pClient->setClientCallbacks(new MyClientCallback()); // Connect to the remove BLE Server pClient->connect(pAddress); Serial.println(" - Connected to server"); pClient->setMTU(517); //set client to request maximum MTU from server BLERemoteService* pRemoteService = pClient->getService(serviceUUID); Serial.print(" - Connected to server :"); Serial.println(serviceUUID.toString().c_str()); if (pRemoteService == nullptr) { Serial.print("Failed to find our service UUID: "); Serial.println(serviceUUID.toString().c_str()); pClient->disconnect(); return false; } // Get the reference of the characteristic for Receive pRemoteCharacteristicRX = pRemoteService->getCharacteristic(charUUID_RX); if (pRemoteCharacteristicRX == nullptr) { Serial.print("Failed to find characteristic RX ID: "); Serial.println(charUUID_RX.toString().c_str()); pClient->disconnect(); return false; } Serial.print(" - Found characteristic RX ID: "); Serial.println(charUUID_RX.toString().c_str()); // Get the reference of the characteristic for Send pRemoteCharacteristicTX = pRemoteService->getCharacteristic(charUUID_TX); if (pRemoteCharacteristicTX == nullptr) { Serial.print("Failed to find characteristic TX ID "); Serial.println(charUUID_TX.toString().c_str()); pClient->disconnect(); return false; } Serial.print(" - Found characteristic TX ID: "); Serial.println(charUUID_TX.toString().c_str()); // Read the value of the characteristic if (pRemoteCharacteristicRX->canRead()) { String value = pRemoteCharacteristicRX->readValue(); Serial.print("The characteristic value was: "); Serial.println(value.c_str()); } if (pRemoteCharacteristicRX->canNotify()) // pRemoteCharacteristicRX->registerForNotify(notifyCallback); // Serial.println("End of notify"); return true; } class MyAdvertisedDeviceCallbacks : public BLEAdvertisedDeviceCallbacks { void onResult(BLEAdvertisedDevice advertisedDevice) { Serial.print("BLE Advertised Device found: "); Serial.println(advertisedDevice.toString().c_str()); Serial.println(advertisedDevice.getName().c_str()); if (advertisedDevice.getName() == SERVER_NAME) { Serial.println(advertisedDevice.getAddress().toString().c_str()); advertisedDevice.getScan()->stop(); pServerAddress = new BLEAddress(advertisedDevice.getAddress()); doConnect = true; } } }; void get_scan() { BLEScan* pBLEScan = BLEDevice::getScan(); Serial.println("getScan"); pBLEScan->setAdvertisedDeviceCallbacks(new MyAdvertisedDeviceCallbacks()); Serial.println("setAdvertisedDeviceCallbacks"); pBLEScan->setActiveScan(true); pBLEScan->start(10); Serial.println(""); Serial.println("End of scan"); } // LEDC Setup Attach Channel void ledc_attach_channel() { ledcAttachChannel(LEDC_in1, LEDC_freq, LEDC_resolution, LEDC_channel_0); ledcAttachChannel(LEDC_in2, LEDC_freq, LEDC_resolution, LEDC_channel_1); ledcAttachChannel(LEDC_in3, LEDC_freq, LEDC_resolution, LEDC_channel_2); ledcAttachChannel(LEDC_in4, LEDC_freq, LEDC_resolution, LEDC_channel_3); } void ledBlink() { volatile static int led = HIGH; digitalWrite(builtinLED, led); led = !led; } void setup() { Serial.begin(115200); pinMode(LEDR, OUTPUT); pinMode(LEDG, OUTPUT); pinMode(LEDB, OUTPUT); pinMode(builtinLED, OUTPUT); Serial.println("BLE_Cliant_start"); BLEDevice::init(""); get_scan(); Serial.println("BLE End of setup"); ticker.attach(0.1, ledBlink); myServo.attach(SERVO_PIN); ledc_attach_channel(); delay(500); } void loop() { unsigned long currenttime = millis(); if (doConnect == true) { if (connectToServer(*pServerAddress)) { Serial.println("We are now connected to the BLE Server."); connected = true; } else { Serial.println("We have failed to connect to the server; there is nothin more we will do."); connected = false; } doConnect = false; } if (connected) { // Connection Handling ticker.detach(); digitalWrite(builtinLED, HIGH); // Receive data read String Rxvalue = pRemoteCharacteristicRX->readValue(); String Rxdata = Rxvalue.c_str(); // copy str(value) String str(Rxdata); String subf = str.substring(2, 3); // Flag String subx = str.substring(6, 9); // potX data String suby = str.substring(12, 15); // potY data String subk = str.substring(18, 19); // buttonK data // Convert int flag xyAxis and buttonK data0 = subf.toInt(); // receive flag data1 = subx.toInt(); // joystick X value data2 = suby.toInt(); // joystick Y value data3 = subk.toInt(); // joystick button // Serial Monitor Received Data char buffer[20]; sprintf(buffer, "F:%d X:%03d Y:%03d K:%d", data0, data1, data2, data3); // Serial.println(buffer); // to Server Send data pRemoteCharacteristicTX->writeValue(Tx_value); // Serial.println(Tx_value); // delay(1000); } else { digitalWrite(builtinLED, LOW); ticker.attach(0.1, ledBlink); // reconnecting Serial.println("Not connected"); doConnect = false; get_scan(); } // Connected Receive Flag if (data0 == 1) { // Pot data Numeric Replace xAxis = map(data1, 0, 255, 0, 1023); yAxis = map(data2, 0, 255, 0, 1023); // Joystick neutral if ((yAxis > 470 && yAxis < 550) && (xAxis > 470 && xAxis < 550)) { Joystick_neutral = HIGH; }else { Joystick_neutral = LOW; } if (Joystick_neutral == HIGH) { speedLeft = stop_speed; speedRight = stop_speed; ledcWrite(LEDC_in1, stop_speed); ledcWrite(LEDC_in2, stop_speed); ledcWrite(LEDC_in3, stop_speed); ledcWrite(LEDC_in4, stop_speed); } // Without exept Joystick neutral if (Joystick_neutral == LOW) { // Forward if (yAxis > 550) { speedLeft = map(yAxis, 510, 1023, 100, 0); speedRight = map(yAxis, 510, 1023, 100, 0); if (xAxis > 470 && xAxis < 550) { ledcWrite(LEDC_in1, speedLeft); ledcWrite(LEDC_in2, stop_speed); ledcWrite(LEDC_in3, speedRight); ledcWrite(LEDC_in4, stop_speed); } } // Backward if (yAxis < 470) { speedLeft = map(yAxis, 510, 0, 100, 0); speedRight = map(yAxis, 510, 0, 100, 0); if (xAxis > 470 && xAxis < 550) { ledcWrite(LEDC_in1, stop_speed); ledcWrite(LEDC_in2, speedLeft); ledcWrite(LEDC_in3, stop_speed); ledcWrite(LEDC_in4, speedRight); } } // Pivot Left turn if (yAxis > 470 && yAxis < 550 && xAxis < 470) { speedLeft = map(xAxis, 510, 0, 100, 0); speedRight = map(xAxis, 510, 0, 100, 0); ledcWrite(LEDC_in1, stop_speed); ledcWrite(LEDC_in2, speedLeft); ledcWrite(LEDC_in3, speedRight); ledcWrite(LEDC_in4, stop_speed); } // Left turn else if (xAxis < 470) { int xMapped = map(xAxis, 510, 0, 100, 0); speedLeft = speedLeft - xMapped; speedRight = speedRight + xMapped; if (speedLeft < 0) { speedLeft = 0; } if (speedRight > 100) { speedRight = 100; } // Forward Left turn if (yAxis > 550) { ledcWrite(LEDC_in1, speedLeft); ledcWrite(LEDC_in2, stop_speed); ledcWrite(LEDC_in3, speedRight); ledcWrite(LEDC_in4, stop_speed); } // Backward Left turn if (yAxis < 470) { ledcWrite(LEDC_in1, stop_speed); ledcWrite(LEDC_in2, speedLeft); ledcWrite(LEDC_in3, stop_speed); ledcWrite(LEDC_in4, speedRight); } } // Pivot Right turn if (yAxis > 470 && yAxis < 550 && xAxis > 550) { speedLeft = map(xAxis, 510, 1023, 100, 0); speedRight = map(xAxis, 510, 1023, 100, 0); ledcWrite(LEDC_in1, speedLeft); ledcWrite(LEDC_in2, stop_speed); ledcWrite(LEDC_in3, stop_speed); ledcWrite(LEDC_in4, speedRight); } // Right turn else if (xAxis > 550) { int xMapped = map(xAxis, 510, 1023, 100, 0); speedLeft = speedLeft + xMapped; speedRight = speedRight - xMapped; if (speedLeft > 100) { speedLeft = 100; } if (speedRight < 0) { speedRight = 0; } // Forward Right turn if (yAxis > 550) { ledcWrite(LEDC_in1, speedLeft); ledcWrite(LEDC_in2, stop_speed); ledcWrite(LEDC_in3, speedRight); ledcWrite(LEDC_in4, stop_speed); } // Backward Right turn if (yAxis < 470) { ledcWrite(LEDC_in1, stop_speed); ledcWrite(LEDC_in2, speedLeft); ledcWrite(LEDC_in3, stop_speed); ledcWrite(LEDC_in4, speedRight); } } } // joystick button pressed LED and Servo if (data3 == 1) { digitalWrite(LEDB, HIGH); myServo.write(145); } else { digitalWrite(LEDB, LOW); myServo.write(50); } // Motor Drive LED if (speedLeft < 95 || speedRight < 95) { digitalWrite(LEDG, HIGH); } else { digitalWrite(LEDG, LOW); } } else { data0 = 0; xAxis = 510; yAxis = 510; data3 = 0; } // Serial monitor // ボードの処理速度に影響するためコメント化してある。 // Serial.print(F("\r\nconnect: ")); // Serial.print(data0); // Serial.print(F("\txAxis: ")); // Serial.print(xAxis); // Serial.print(F("\tyAxis: ")); // Serial.print(yAxis); // Serial.print(F("\tJoystick_Button: ")); // Serial.print(data3); // Serial.print(F("\tJoystick_neutral: ")); // Serial.print(Joystick_neutral); // Serial.print(F("\tspeedLeft: ")); // Serial.print(speedLeft); // Serial.print(F("\tspeedRight: ")); // Serial.print(speedRight); }