fixes, debug, radio loop
This commit is contained in:
parent
b3ea8f4758
commit
3f7ea70f75
6 changed files with 82 additions and 32 deletions
|
@ -1,5 +1,4 @@
|
||||||
|
|
||||||
|
|
||||||
// RC Config
|
// RC Config
|
||||||
#define myId 0x01
|
#define myId 0x01
|
||||||
#define myChannel 1
|
#define myChannel 1
|
||||||
|
@ -14,6 +13,20 @@
|
||||||
// RC lib
|
// RC lib
|
||||||
#include "juRCReceiver.h"
|
#include "juRCReceiver.h"
|
||||||
|
|
||||||
|
TaskHandle_t RadioTaskHandle;
|
||||||
|
|
||||||
|
void RadioTask(void* parameter) {
|
||||||
|
for (;;) {
|
||||||
|
jRadioLoop();
|
||||||
|
if (rc_serial_available()) {
|
||||||
|
String got = rc_serial_read();
|
||||||
|
Serial.println("received serial: " + got);
|
||||||
|
rc_serial_write("got: " + got);
|
||||||
|
}
|
||||||
|
taskYIELD();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void onConnect() {}
|
void onConnect() {}
|
||||||
void onDisconnect(bool expected) {}
|
void onDisconnect(bool expected) {}
|
||||||
|
|
||||||
|
@ -24,17 +37,16 @@ void setup() {
|
||||||
Serial.println("setup");
|
Serial.println("setup");
|
||||||
delay(1000);
|
delay(1000);
|
||||||
jSetup();
|
jSetup();
|
||||||
|
xTaskCreatePinnedToCore(RadioTask, /* Function to implement the task */
|
||||||
|
"RadioTask", /* Name of the task */
|
||||||
|
10000, /* Stack size in words */
|
||||||
|
NULL, /* Task input parameter */
|
||||||
|
0, /* Priority of the task */
|
||||||
|
&RadioTaskHandle, /* Task handle. */
|
||||||
|
0); /* Core where the task should run */
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
jSensorLoop();
|
jSensorLoop();
|
||||||
|
|
||||||
// fly
|
// fly
|
||||||
}
|
}
|
||||||
/*void loop1() {
|
|
||||||
jRadioLoop();
|
|
||||||
if (rc_serial_available()) {
|
|
||||||
String got = rc_serial_read();
|
|
||||||
rc_serial_write("got: " + got);
|
|
||||||
}
|
|
||||||
}*/
|
|
||||||
|
|
|
@ -12,12 +12,15 @@
|
||||||
#define debug false
|
#define debug false
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef debugReceive
|
||||||
|
#define debugReceive false
|
||||||
|
#endif
|
||||||
|
|
||||||
#include <Preferences.h>
|
#include <Preferences.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include "pthread.h"
|
|
||||||
#include <jqueue.h>
|
|
||||||
#include <jmutex.h>
|
#include <jmutex.h>
|
||||||
|
#include <jqueue.h>
|
||||||
|
|
||||||
//
|
//
|
||||||
|
|
||||||
|
@ -91,12 +94,27 @@ void jSensorLoop() {
|
||||||
last = now;
|
last = now;
|
||||||
avg = avg * 0.9 + delta * 0.1;
|
avg = avg * 0.9 + delta * 0.1;
|
||||||
#if debug
|
#if debug
|
||||||
Serial.println("Sensor Loop, avg = " + String(avg));
|
if ((dcounterxy) % 100 == 0)
|
||||||
|
Serial.println("Sensor Loop, avg = " + String(avg));
|
||||||
#endif
|
#endif
|
||||||
MPULoop();
|
MPULoop();
|
||||||
GNSSLoop();
|
GNSSLoop();
|
||||||
COMPLoop();
|
COMPLoop();
|
||||||
}
|
}
|
||||||
void jRadioLoop() { handleRC(); }
|
void jRadioLoop() {
|
||||||
|
#if debug
|
||||||
|
unsigned long now = millis();
|
||||||
|
static long unsigned last = 0;
|
||||||
|
static long unsigned delta = 0;
|
||||||
|
static long unsigned radioLoopCount = 0;
|
||||||
|
static float avg = 2.;
|
||||||
|
delta = now - last;
|
||||||
|
last = now;
|
||||||
|
avg = avg * 0.9 + delta * 0.1;
|
||||||
|
if ((radioLoopCount++) % 200 == 0)
|
||||||
|
Serial.println("Radio Loop, avg = " + String(avg));
|
||||||
|
#endif
|
||||||
|
handleRC();
|
||||||
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
10
rcserial.h
10
rcserial.h
|
@ -2,10 +2,11 @@
|
||||||
#define _RC_SERIAL_H
|
#define _RC_SERIAL_H
|
||||||
#define jType_RC_SERIAL 1
|
#define jType_RC_SERIAL 1
|
||||||
|
|
||||||
|
#include <jmutex.h>
|
||||||
|
#include <jqueue.h>
|
||||||
|
|
||||||
#include "JuSDK.h" //https://jusax.de/git/jusax23/JuSDK
|
#include "JuSDK.h" //https://jusax.de/git/jusax23/JuSDK
|
||||||
#include "juRCReceiver.h"
|
#include "juRCReceiver.h"
|
||||||
#include "jqueue.h"
|
|
||||||
#include "jmutex.h"
|
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
byte type = 0x01;
|
byte type = 0x01;
|
||||||
|
@ -59,7 +60,7 @@ String rc_serial_read() {
|
||||||
bool rc_serial_write(String inn) {
|
bool rc_serial_write(String inn) {
|
||||||
mutex_enter_blocking(&serial_mut);
|
mutex_enter_blocking(&serial_mut);
|
||||||
size_t len = inn.length();
|
size_t len = inn.length();
|
||||||
if (len + 1 < serialRFBufSize - queue_get_level(&serial_write_queue)) {
|
if (len + 1 > serialRFBufSize - queue_get_level(&serial_write_queue)) {
|
||||||
#if defined(debug) && debug
|
#if defined(debug) && debug
|
||||||
Serial.println("<rfSerial>BufOverflow");
|
Serial.println("<rfSerial>BufOverflow");
|
||||||
#endif
|
#endif
|
||||||
|
@ -94,7 +95,8 @@ void _handle_serial_send() {
|
||||||
rcSerial.data + (rcSerial.command++));
|
rcSerial.data + (rcSerial.command++));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (jSendNRF(&rcSerial, sizeof(rcSerial))) rcSerial.command = 0;
|
if (rcSerial.command > 0)
|
||||||
|
if (jSendNRF(&rcSerial, sizeof(rcSerial))) rcSerial.command = 0;
|
||||||
mutex_exit(&serial_mut);
|
mutex_exit(&serial_mut);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -8,7 +8,7 @@ typedef struct {
|
||||||
|
|
||||||
void RCMulticastTask() {
|
void RCMulticastTask() {
|
||||||
if (random(25) == 1) {
|
if (random(25) == 1) {
|
||||||
#ifdef debug
|
#if debug
|
||||||
Serial.println("Multicast!");
|
Serial.println("Multicast!");
|
||||||
#endif
|
#endif
|
||||||
radio.stopListening();
|
radio.stopListening();
|
||||||
|
@ -17,11 +17,11 @@ void RCMulticastTask() {
|
||||||
nrfMulticast data;
|
nrfMulticast data;
|
||||||
data.pipe = myPipe;
|
data.pipe = myPipe;
|
||||||
data.channel = myChannel;
|
data.channel = myChannel;
|
||||||
#ifdef jNAME
|
#ifdef jName
|
||||||
char nameMult[16] = jNAME;
|
char nameMult[16] = jName;
|
||||||
strncpy(data.name, nameMult, 16);
|
strncpy(data.name, nameMult, 16);
|
||||||
#endif
|
#endif
|
||||||
radio.write(&data, sizeof(data), true);
|
radio.write(&data, sizeof(data));
|
||||||
radio.setChannel(myChannel);
|
radio.setChannel(myChannel);
|
||||||
radio.startListening();
|
radio.startListening();
|
||||||
}
|
}
|
||||||
|
|
|
@ -3,11 +3,11 @@
|
||||||
#define maxLastRcPackage 2500
|
#define maxLastRcPackage 2500
|
||||||
|
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
#include <jmutex.h>
|
||||||
|
#include <jqueue.h>
|
||||||
|
|
||||||
#include "../structsAndDefines.h"
|
#include "../structsAndDefines.h"
|
||||||
#include "RF24.h"
|
#include "RF24.h"
|
||||||
#include "jqueue.h"
|
|
||||||
#include "jmutex.h"
|
|
||||||
#include "nRF24L01.h"
|
#include "nRF24L01.h"
|
||||||
|
|
||||||
mutex_t radioAccess;
|
mutex_t radioAccess;
|
||||||
|
@ -27,8 +27,13 @@ void initRC() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
radio.enableDynamicPayloads();
|
radio.enableDynamicPayloads();
|
||||||
|
radio.setPALevel(RF24_PA_HIGH);
|
||||||
|
radio.setDataRate(RF24_1MBPS);
|
||||||
radio.setRetries(5, 15);
|
radio.setRetries(5, 15);
|
||||||
radio.setChannel(myChannel);
|
radio.setChannel(myChannel);
|
||||||
|
radio.enableDynamicPayloads();
|
||||||
|
radio.disableAckPayload();
|
||||||
|
radio.setAutoAck(false);
|
||||||
radio.openReadingPipe(0, myPipe);
|
radio.openReadingPipe(0, myPipe);
|
||||||
radio.startListening();
|
radio.startListening();
|
||||||
mutex_exit(&radioAccess);
|
mutex_exit(&radioAccess);
|
||||||
|
@ -50,16 +55,16 @@ bool jSendNRF(const void* buf, uint8_t length) {
|
||||||
#include "multicast.h"
|
#include "multicast.h"
|
||||||
#include "rc_data.h"
|
#include "rc_data.h"
|
||||||
|
|
||||||
#ifdef debug
|
#if debugReceive
|
||||||
const String b16 = "0123456789abcdef";
|
const String b16 = "0123456789abcdef";
|
||||||
|
|
||||||
String SensorDataBuffer = "";
|
String SensorDataBuffer = "";
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void receiveRC() {
|
bool receiveRC() {
|
||||||
mutex_enter_blocking(&radioAccess);
|
mutex_enter_blocking(&radioAccess);
|
||||||
if (radio.available()) {
|
if (radio.available()) {
|
||||||
#ifdef debug
|
#if debugReceive
|
||||||
Serial.println("Radio available!");
|
Serial.println("Radio available!");
|
||||||
#endif
|
#endif
|
||||||
uint8_t payloadSize = radio.getDynamicPayloadSize();
|
uint8_t payloadSize = radio.getDynamicPayloadSize();
|
||||||
|
@ -67,7 +72,7 @@ void receiveRC() {
|
||||||
jLastRCData = millis();
|
jLastRCData = millis();
|
||||||
radio.read(&jRCbuff, payloadSize);
|
radio.read(&jRCbuff, payloadSize);
|
||||||
mutex_exit(&radioAccess);
|
mutex_exit(&radioAccess);
|
||||||
#ifdef debug
|
#if debugReceive
|
||||||
SensorDataBuffer = "data: ";
|
SensorDataBuffer = "data: ";
|
||||||
for (size_t i = 0; i < payloadSize; i++) {
|
for (size_t i = 0; i < payloadSize; i++) {
|
||||||
SensorDataBuffer += b16[(jRCbuff[i] >> 4) & 0xf];
|
SensorDataBuffer += b16[(jRCbuff[i] >> 4) & 0xf];
|
||||||
|
@ -92,26 +97,36 @@ void receiveRC() {
|
||||||
COMPradioTask();
|
COMPradioTask();
|
||||||
} break;
|
} break;
|
||||||
}
|
}
|
||||||
} else
|
return true;
|
||||||
|
} else {
|
||||||
mutex_exit(&radioAccess);
|
mutex_exit(&radioAccess);
|
||||||
} else
|
return false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
mutex_exit(&radioAccess);
|
mutex_exit(&radioAccess);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleRC() {
|
void handleRC() {
|
||||||
receiveRC();
|
while (receiveRC())
|
||||||
|
;
|
||||||
if (millis() - jLastRCData > maxLastRcPackage) { // no connection
|
if (millis() - jLastRCData > maxLastRcPackage) { // no connection
|
||||||
if (jLastStatus == 1) {
|
if (jLastStatus == 1) {
|
||||||
if (_j_on_disconnect != nullptr) _j_on_disconnect(true);
|
if (_j_on_disconnect != nullptr) _j_on_disconnect(true);
|
||||||
jLastStatus = 3;
|
jLastStatus = 3;
|
||||||
|
radio.setAutoAck(false);
|
||||||
}
|
}
|
||||||
|
RCMulticastTask();
|
||||||
} else { // connection
|
} else { // connection
|
||||||
if (jLastStatus != 1) {
|
if (jLastStatus != 1) {
|
||||||
if (_j_on_connect != nullptr) _j_on_connect();
|
if (_j_on_connect != nullptr) _j_on_connect();
|
||||||
radio.openWritingPipe(myPipe);
|
radio.openWritingPipe(myPipe);
|
||||||
|
radio.setAutoAck(true);
|
||||||
radio.startListening();
|
radio.startListening();
|
||||||
jLastStatus = 1;
|
jLastStatus = 1;
|
||||||
}
|
}
|
||||||
|
_handle_serial_send();
|
||||||
}
|
}
|
||||||
// todo: multicast, send serial
|
// todo: multicast, send serial
|
||||||
}
|
}
|
||||||
|
|
|
@ -49,8 +49,11 @@ void initMPU() {
|
||||||
preferences.getFloat("mpuOffAccY", 0.0),
|
preferences.getFloat("mpuOffAccY", 0.0),
|
||||||
preferences.getFloat("mpuOffAccZ", 0.3));*/
|
preferences.getFloat("mpuOffAccZ", 0.3));*/
|
||||||
|
|
||||||
//mpu6050.setGyroOffsets(-7.8, 2.32, -0.22);
|
mpu6050.setGyroOffsets(-7.8, 2.32, -0.22);
|
||||||
//mpu6050.setAccXoffset(0.03, 0.0, 0.3);
|
#if debug
|
||||||
|
Serial.println("set mpu6050 gyro");
|
||||||
|
#endif
|
||||||
|
mpu6050.setAccXoffset(0.03, 0.0, 0.3);
|
||||||
|
|
||||||
#if debug
|
#if debug
|
||||||
Serial.println("set mpu6050 offsets");
|
Serial.println("set mpu6050 offsets");
|
||||||
|
|
Loading…
Reference in a new issue