reorganized libraries into repo's
This commit is contained in:
2
.gitignore
vendored
2
.gitignore
vendored
@@ -3,3 +3,5 @@
|
||||
.vscode/c_cpp_properties.json
|
||||
.vscode/launch.json
|
||||
.vscode/ipch
|
||||
lib
|
||||
.DS_Store
|
||||
|
||||
Binary file not shown.
@@ -17,6 +17,15 @@ debug_tool = stlink
|
||||
board_build.f_cpu = 72000000L
|
||||
monitor_speed = 115200
|
||||
lib_deps =
|
||||
# danya0x07/NRF24L01_SimpleLibrary@^1.0.0
|
||||
http://192.168.2.3/Bonobo.Git.Server/rc-radio.git
|
||||
http://192.168.2.3/Bonobo.Git.Server/Radiohead.git
|
||||
http://192.168.2.3/Bonobo.Git.Server/MC34933.git
|
||||
https://github.com/br3ttb/Arduino-PID-Library/
|
||||
http://192.168.2.3/Bonobo.Git.Server/PWMFrequency.git
|
||||
http://192.168.2.3/Bonobo.Git.Server/Statusled.git
|
||||
|
||||
|
||||
build_flags =
|
||||
# -D DEBUG
|
||||
|
||||
|
||||
|
||||
@@ -2,6 +2,27 @@
|
||||
"folders": [
|
||||
{
|
||||
"path": "."
|
||||
},
|
||||
{
|
||||
"path": "../libs/Radiohead"
|
||||
},
|
||||
{
|
||||
"path": "../libs/MC34933"
|
||||
},
|
||||
{
|
||||
"path": "../libs/rc-radio"
|
||||
},
|
||||
{
|
||||
"path": "../RC-transmitter"
|
||||
},
|
||||
{
|
||||
"path": "../libs/Arduino_PID_Library"
|
||||
},
|
||||
{
|
||||
"path": "../libs/PWMFrequency"
|
||||
},
|
||||
{
|
||||
"path": "../libs/Statusled"
|
||||
}
|
||||
],
|
||||
"settings": {
|
||||
@@ -20,7 +41,16 @@
|
||||
"vector": "cpp",
|
||||
"ostream": "cpp",
|
||||
"*.tcc": "cpp",
|
||||
"ios": "cpp"
|
||||
"ios": "cpp",
|
||||
"bitset": "cpp",
|
||||
"iomanip": "cpp",
|
||||
"istream": "cpp",
|
||||
"limits": "cpp",
|
||||
"ratio": "cpp",
|
||||
"sstream": "cpp",
|
||||
"streambuf": "cpp",
|
||||
"functional": "cpp",
|
||||
"memory": "cpp"
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -2,7 +2,7 @@
|
||||
#include "MPU6050.h"
|
||||
#include <Wire.h>
|
||||
#include "vehicleConfig.h"
|
||||
//#include "radio.h"
|
||||
#include "balancing.h"
|
||||
|
||||
|
||||
|
||||
@@ -64,7 +64,7 @@ void writeDebug() {
|
||||
Serial.print(" R: ");
|
||||
Serial.print(angle_roll); //Print roll
|
||||
Serial.print(" Motor: ");
|
||||
Serial.println(angleOutput); //Print Motor output
|
||||
Serial.println(getAngleOut()); //Print Motor output
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
#include "vehicleConfig.h"
|
||||
#include "MPU6050.h"
|
||||
#include "radio.h"
|
||||
#include <../lib/Arduino-PID-Library/PID_v1.h> // https://github.com/br3ttb/Arduino-PID-Library/
|
||||
#include "PID_v1.h" // https://github.com/br3ttb/Arduino-PID-Library/
|
||||
#include "motors.h"
|
||||
|
||||
int speedPot;
|
||||
@@ -24,7 +24,10 @@ PID speedPid(&speedMeasured, &speedOutput, &speedTarget, 0.0, 0.0, 0.0, DIRECT);
|
||||
PID anglePid(&angleMeasured, &angleOutput, &angleTarget, 0.0, 0.0, 0.0, DIRECT); // Angle: inner, fast control loop
|
||||
|
||||
|
||||
|
||||
double getAngleOut( void )
|
||||
{
|
||||
return angleOutput;
|
||||
}
|
||||
//
|
||||
// =======================================================================================================
|
||||
// PID SETUP
|
||||
@@ -69,7 +72,7 @@ void balancing() {
|
||||
|
||||
// PID Parameters (Test)
|
||||
double speedKp = 0.9, speedKi = 0.03, speedKd = 0.0;
|
||||
double angleKp = data->pot1 / 8.0, angleKi = 25.0, angleKd = 0.12; // /You need to connect a potentiometer to the transmitter analog input A6
|
||||
double angleKp = data->pot / 8.0, angleKi = 25.0, angleKd = 0.12; // /You need to connect a potentiometer to the transmitter analog input A6
|
||||
|
||||
// PID Parameters (Working)
|
||||
//double speedKp = 0.9, speedKi = 0.03, speedKd = 0.0;
|
||||
@@ -109,8 +112,6 @@ void mrsc() {
|
||||
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
RcData* data = getDataptr();
|
||||
//MC34933* Motor1 = getMotorptr(MOTOR1);
|
||||
MC34933* Motor2 = getMotorptr(MOTOR2);
|
||||
|
||||
// Read sensor data
|
||||
readMpu6050Data();
|
||||
@@ -123,7 +124,7 @@ void mrsc() {
|
||||
// Compute steering compensation overlay
|
||||
int turnRateSetPoint = data->axis1 - 50; // turnRateSetPoint = steering angle (0 to 100) - 50 = -50 to 50
|
||||
int turnRateMeasured = Mpu6050_getyaw_rate() * abs(data->axis3 - 50); // degrees/s * speed
|
||||
int steeringAngle = turnRateSetPoint + (turnRateMeasured * data->pot1 / 100); // Compensation depending on the pot value
|
||||
int steeringAngle = turnRateSetPoint + (turnRateMeasured * data->pot / 100); // Compensation depending on the pot value
|
||||
|
||||
steeringAngle = constrain (steeringAngle, -50, 50); // range = -50 to 50
|
||||
|
||||
@@ -133,7 +134,7 @@ void mrsc() {
|
||||
#endif //CONFIG_HAS_SERVO
|
||||
// Control motor 2 (steering, not on "High Power" board type)
|
||||
if (!cfg->getHP()) {
|
||||
Motor2->drive((steeringAngle + 50), 0, cfg->getsteeringTorque(), 0, false); // The steering motor (if the original steering motor is reused instead of a servo)
|
||||
motordrive(MOTOR2, (steeringAngle + 50), 0, cfg->getsteeringTorque(), 0, false); // The steering motor (if the original steering motor is reused instead of a servo)
|
||||
}
|
||||
|
||||
// Control motors
|
||||
@@ -146,8 +147,6 @@ void driveMotorsBalancing()
|
||||
{
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
RcData* data = getDataptr();
|
||||
MC34933* Motor1 = getMotorptr(MOTOR1);
|
||||
MC34933* Motor2 = getMotorptr(MOTOR2);
|
||||
|
||||
// The steering overlay is in degrees per second, controlled by the MPU 6050 yaw rate and yoystick axis 1
|
||||
int steering = ((data->axis1 - 50) / 7) - Mpu6050_getyaw_rate(); // -50 to 50 / 8 = 7°/s - yaw_rate
|
||||
@@ -163,11 +162,11 @@ void driveMotorsBalancing()
|
||||
speed = constrain(speed, 7, 93); // same range as in setupPID() + 50 offset from above!
|
||||
|
||||
if (angleMeasured > -20.0 && angleMeasured < 20.0) { // Only drive motors, if robot stands upright
|
||||
Motor1->drive(speed - steering, cfg->getminPWM(), cfg->getmaxPWMfull(), 0, false); // left caterpillar, 0ms ramp! 50 = neutral!
|
||||
Motor2->drive(speed + steering, cfg->getminPWM(), cfg->getmaxPWMfull(), 0, false); // right caterpillar
|
||||
motordrive(MOTOR1, speed - steering, cfg->getminPWM(), cfg->getmaxPWMfull(), 0, false); // left caterpillar, 0ms ramp! 50 = neutral!
|
||||
motordrive(MOTOR2, speed + steering, cfg->getminPWM(), cfg->getmaxPWMfull(), 0, false); // right caterpillar
|
||||
}
|
||||
else { // keep motors off
|
||||
Motor1->drive(50, cfg->getminPWM(), cfg->getmaxPWMfull(), 0, false); // left caterpillar, 0ms ramp!
|
||||
Motor2->drive(50, cfg->getminPWM(), cfg->getmaxPWMfull(), 0, false); // right caterpillar
|
||||
motordrive(MOTOR1, 50, cfg->getminPWM(), cfg->getmaxPWMfull(), 0, false); // left caterpillar, 0ms ramp!
|
||||
motordrive(MOTOR2, 50, cfg->getminPWM(), cfg->getmaxPWMfull(), 0, false); // right caterpillar
|
||||
}
|
||||
}
|
||||
@@ -6,5 +6,7 @@ void driveMotorsBalancing( void );
|
||||
void setupPid( void );
|
||||
void mrsc();
|
||||
|
||||
double getAngleOut( void );
|
||||
|
||||
|
||||
#endif //BALANCINGH
|
||||
@@ -12,7 +12,7 @@ bool battSense;
|
||||
void checkBattery()
|
||||
{
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
ackPayload* payload = getPayloadptr();
|
||||
RcData* data = getDataptr();
|
||||
|
||||
if (cfg->getboardVersion() < 1.2) battSense = false;
|
||||
else battSense = true;
|
||||
@@ -31,15 +31,9 @@ void checkBattery()
|
||||
lastTrigger = millis();
|
||||
|
||||
// Read both averaged voltages
|
||||
payload->batteryVoltage = batteryAverage();
|
||||
payload->vcc = vccAverage();
|
||||
data->setVoltage(batteryAverage());
|
||||
//payload->vcc = vccAverage();
|
||||
|
||||
if (battSense) { // Observe battery voltage
|
||||
if (payload->batteryVoltage <= cfg->getcutoffVoltage()) payload->batteryOk = false;
|
||||
}
|
||||
else { // Observe vcc voltage
|
||||
if (payload->vcc <= cfg->getcutoffVoltage()) payload->batteryOk = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -3,8 +3,9 @@
|
||||
#include "radio.h"
|
||||
#include "vehicleConfig.h"
|
||||
#include "motors.h"
|
||||
#include "rc_board.h"
|
||||
|
||||
#include <../lib/statusLED/statusLED.h> // https://github.com/TheDIYGuy999/statusLED
|
||||
#include <statusLED.h> // https://github.com/TheDIYGuy999/statusLED
|
||||
|
||||
|
||||
// Headlight off delay
|
||||
@@ -54,6 +55,21 @@ unsigned long getMillisLightsOff( void )
|
||||
return millisLightOff;
|
||||
}
|
||||
|
||||
void setupLights( void )
|
||||
{
|
||||
#ifdef CONFIG_HAS_LIGHTS
|
||||
// LED setup
|
||||
if (vehicleType == 4 || vehicleType == 5 ) indicators = false; // Indicators use the same pins as the MPU-6050, so they can't be used in vehicleType 4 or 5!
|
||||
|
||||
if (tailLights) tailLight.begin(A1); // A1 = Servo 2 Pin
|
||||
if (headLights) headLight.begin(0); // 0 = RXI Pin
|
||||
if (indicators) {
|
||||
indicatorL.begin(A4); // A4 = SDA Pin
|
||||
indicatorR.begin(A5); // A5 = SCL Pin
|
||||
}
|
||||
if (beacons) beaconLights.begin(A3); // A3 = Servo 4 Pin
|
||||
#endif //CONFIG_HAS_LIGHTS
|
||||
}
|
||||
|
||||
//
|
||||
// =======================================================================================================
|
||||
@@ -109,7 +125,7 @@ void led()
|
||||
beaconLights.off(); // Beacons off
|
||||
}
|
||||
else {
|
||||
if (!cfg->getescBrakeLights() && ((!cfg->getHP() && getMotorptr(MOTOR1)->brakeActive()) || (cfg->getHP() && getMotorptr(MOTOR2)->brakeActive()) )) { // if braking detected from TB6612FNG motor driver
|
||||
if (!cfg->getescBrakeLights() && ((!cfg->getHP() && motorBrakeActive(MOTOR1)) || (cfg->getHP() && motorBrakeActive(MOTOR2)) )) { // if braking detected from TB6612FNG motor driver
|
||||
tailLight.on(); // Brake light (full brightness)
|
||||
}
|
||||
|
||||
|
||||
@@ -11,4 +11,6 @@ bool getLeft( void );
|
||||
bool getRight( void );
|
||||
bool getHazard( void );
|
||||
|
||||
void setupLights( void );
|
||||
|
||||
#endif //LIGHTSH
|
||||
113
src/main.cpp
113
src/main.cpp
@@ -10,26 +10,10 @@
|
||||
|
||||
const float codeVersion = 3.4; // Software revision (see https://github.com/TheDIYGuy999/Micro_RC_Receiver/blob/master/README.md)
|
||||
|
||||
//
|
||||
// =======================================================================================================
|
||||
// BUILD OPTIONS (comment out unneeded options)
|
||||
// =======================================================================================================
|
||||
//
|
||||
|
||||
//#define DEBUG // if not commented out, Serial.print() is active! For debugging only!!
|
||||
|
||||
//
|
||||
// =======================================================================================================
|
||||
// INCLUDE LIRBARIES
|
||||
// =======================================================================================================
|
||||
//
|
||||
|
||||
// Libraries
|
||||
#include <Wire.h> // I2C library (for the MPU-6050 gyro /accelerometer)
|
||||
//#include <RF24.h> // Installed via Tools > Board > Boards Manager > Type RF24
|
||||
#include <Servo.h>
|
||||
#include <Arduino.h>
|
||||
#include "vehicleConfig.h"
|
||||
// Tabs (header files in sketch directory)
|
||||
#include "readVCC.h"
|
||||
#include "steeringCurves.h"
|
||||
#include "tone.h"
|
||||
@@ -44,10 +28,8 @@ const float codeVersion = 3.4; // Software revision (see https://github.com/TheD
|
||||
#include "balancing.h"
|
||||
#include "lights.h"
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#define CLIENT_ADDRESS 1
|
||||
#define SERVER_ADDRESS 2
|
||||
|
||||
//
|
||||
// =======================================================================================================
|
||||
@@ -55,22 +37,25 @@ const float codeVersion = 3.4; // Software revision (see https://github.com/TheD
|
||||
// =======================================================================================================
|
||||
//
|
||||
|
||||
radio_c radio(CLIENT_ADDRESS,PIN_NRF_CE, PIN_NRF_CSN);
|
||||
|
||||
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
||||
setupConfig(STANDARDCAR);
|
||||
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
cfg->begin(COKECANCAR);
|
||||
|
||||
RcData* data = getDataptr();
|
||||
|
||||
#ifdef DEBUG
|
||||
Serial.begin(115200);
|
||||
printf_begin();
|
||||
serialCommands = false;
|
||||
#ifdef STM32F1xx
|
||||
USART1->BRR = 0x271;
|
||||
#endif
|
||||
//printf_begin();
|
||||
cfg->serialCommands = false;
|
||||
delay(3000);
|
||||
#endif
|
||||
|
||||
#ifndef DEBUG
|
||||
#else
|
||||
// If TXO pin or RXI pin is used for other things, disable Serial
|
||||
if (cfg->getTXO_momentary1() || cfg->getTXO_toggle1() || cfg->getheadLights())
|
||||
{
|
||||
@@ -80,59 +65,22 @@ void setup()
|
||||
#endif
|
||||
cfg->serialCommands = false;
|
||||
}
|
||||
else
|
||||
{ // Otherwise use it for serial commands to the light and sound controller
|
||||
|
||||
#ifdef CONFIG_HAS_SBUS
|
||||
SBUS* x8r = getSBUSptr();
|
||||
x8r->begin(); // begin the SBUS communication
|
||||
#else
|
||||
Serial.begin(115200); // begin the standart serial communication
|
||||
#endif
|
||||
cfg->serialCommands = true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_HAS_TONE
|
||||
if(cfg->gettoneOut())
|
||||
{
|
||||
R2D2_tell();
|
||||
}
|
||||
#endif
|
||||
//setup lights
|
||||
setupLights();
|
||||
|
||||
|
||||
// LED setup
|
||||
#ifdef CONFIG_HAS_LIGHTS
|
||||
if (vehicleType == 4 || vehicleType == 5 ) indicators = false; // Indicators use the same pins as the MPU-6050, so they can't be used in vehicleType 4 or 5!
|
||||
|
||||
if (tailLights) tailLight.begin(A1); // A1 = Servo 2 Pin
|
||||
if (headLights) headLight.begin(0); // 0 = RXI Pin
|
||||
if (indicators) {
|
||||
indicatorL.begin(A4); // A4 = SDA Pin
|
||||
indicatorR.begin(A5); // A5 = SCL Pin
|
||||
}
|
||||
if (beacons) beaconLights.begin(A3); // A3 = Servo 4 Pin
|
||||
#endif //CONFIG_HAS_LIGHTS
|
||||
|
||||
// Radio setup
|
||||
#ifdef CONFIG_HAS_NRF24
|
||||
setupRadio();
|
||||
#endif //CONFIG_HAS_NRF24
|
||||
// Radio setup
|
||||
radio.begin();
|
||||
|
||||
// Servo pins
|
||||
#ifdef CONFIG_HAS_SERVO
|
||||
servo1.attach(A0);
|
||||
if (!tailLights) servo2.attach(A1);
|
||||
if (!engineSound && !toneOut) servo3.attach(A2);
|
||||
if (!beacons) servo4.attach(A3);
|
||||
#endif //CONFIG_HAS_SERVO
|
||||
|
||||
// All axes to neutral position
|
||||
data->axis1 = 50;
|
||||
data->axis2 = 50;
|
||||
data->axis3 = 50;
|
||||
data->axis4 = 50;
|
||||
data->pot1 = 50; // Added in v3.32
|
||||
|
||||
|
||||
setupServos();
|
||||
|
||||
// Special functions
|
||||
if (cfg->getTXO_momentary1() || cfg->getTXO_toggle1()) pinMode(PIN_SPARE1, OUTPUT);
|
||||
@@ -140,8 +88,9 @@ void setup()
|
||||
// Motor driver setup
|
||||
setupMotors();
|
||||
|
||||
if (cfg->getvehicleType() == balancingthing || cfg->getvehicleType() == carwithMRSC) { // Only for self balancing vehicles and cars with MRSC
|
||||
// MPU 6050 accelerometer / gyro setup
|
||||
if (cfg->usesMPU()) // Only for self balancing vehicles and cars with MRSC
|
||||
{
|
||||
// setup MPU 6050 accelerometer / gyro setup
|
||||
setupMpu6050();
|
||||
|
||||
// PID controller setup
|
||||
@@ -157,7 +106,8 @@ void setup()
|
||||
// =======================================================================================================
|
||||
//
|
||||
|
||||
void digitalOutputs() {
|
||||
void digitalOutputs()
|
||||
{
|
||||
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
RcData* data = getDataptr();
|
||||
@@ -186,8 +136,6 @@ void digitalOutputs() {
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//
|
||||
// =======================================================================================================
|
||||
// MAIN LOOP
|
||||
@@ -196,7 +144,7 @@ void digitalOutputs() {
|
||||
|
||||
void loop() {
|
||||
// Read radio data from transmitter
|
||||
readRadio();
|
||||
radio.receiveData();
|
||||
|
||||
// Write the servo positions
|
||||
writeServos();
|
||||
@@ -214,12 +162,7 @@ void loop() {
|
||||
led();
|
||||
|
||||
// Send serial commands
|
||||
#ifdef CONFIG_HAS_SBUS
|
||||
// Serial commands are transmitted in SBUS standard
|
||||
sendSbusCommands();
|
||||
#else
|
||||
// Normal protocol (for ESP32 engine sound controller only)
|
||||
sendSerialCommands();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@@ -8,8 +8,8 @@
|
||||
#include "balancing.h"
|
||||
|
||||
|
||||
#include "../lib/MC34933/MC34933.h" // https://github.com/willumpie82/MC34933
|
||||
#include <../lib/PWMFrequency/PWMFrequency.h> // https://github.com/TheDIYGuy999/PWMFrequency
|
||||
#include "MC34933.h"
|
||||
#include "PWMFrequency.h"
|
||||
|
||||
bool isDriving; // is the vehicle driving?
|
||||
// Motor objects
|
||||
@@ -66,8 +66,8 @@ void setupMotors()
|
||||
|
||||
// SYNTAX: IN1, IN2, PWM, min. input value, max. input value, neutral position width
|
||||
// invert rotation direction true or false
|
||||
Motor1.begin(motor1_in1, motor1_in2, 0, 100, 4, false); // Drive motor
|
||||
Motor2.begin(motor2_in1, motor2_in2, 0, 100, 4, false); // Steering motor (Drive in "HP" version)
|
||||
Motor2.begin(motor1_in1, motor1_in2, 0, 100, 4, false); // Drive motor
|
||||
Motor1.begin(motor2_in1, motor2_in2, 0, 100, 4, false); // Steering motor (Drive in "HP" version)
|
||||
|
||||
// Motor PWM frequency prescalers (Requires the PWMFrequency.h library)
|
||||
// Differential steering vehicles: locked to 984Hz, to make sure, that both motors use 984Hz.
|
||||
@@ -84,15 +84,25 @@ void setupMotors()
|
||||
|
||||
MC34933* getMotorptr(motor_t motor)
|
||||
{
|
||||
if(motor==1)
|
||||
switch(motor)
|
||||
{
|
||||
return &Motor1;
|
||||
case MOTOR1:
|
||||
{
|
||||
return &Motor1;
|
||||
}
|
||||
break;
|
||||
|
||||
case MOTOR2:
|
||||
{
|
||||
return &Motor2;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
return &Motor2;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//
|
||||
@@ -101,6 +111,16 @@ MC34933* getMotorptr(motor_t motor)
|
||||
// =======================================================================================================
|
||||
//
|
||||
|
||||
void motordrive(motor_t motor, int controlValue, int minPWM, int maxPWM, int rampTime, bool neutralBrake)
|
||||
{
|
||||
getMotorptr(motor)->drive( controlValue, minPWM, maxPWM, rampTime, neutralBrake);
|
||||
}
|
||||
|
||||
bool motorBrakeActive(motor_t motor)
|
||||
{
|
||||
return getMotorptr(motor)->brakeActive();
|
||||
}
|
||||
|
||||
void drive()
|
||||
{
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
@@ -110,7 +130,6 @@ void drive()
|
||||
case car:
|
||||
{
|
||||
driveMotorsCar();
|
||||
|
||||
}
|
||||
break;
|
||||
|
||||
@@ -149,7 +168,7 @@ void driveMotorsCar() {
|
||||
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
RcData* data = getDataptr();
|
||||
ackPayload* payload = getPayloadptr();
|
||||
//ackPayload* payload = getPayloadptr();
|
||||
|
||||
int maxPWM;
|
||||
byte maxAcceleration;
|
||||
@@ -161,7 +180,7 @@ void driveMotorsCar() {
|
||||
maxPWM = cfg->getmaxPWMfull(); // Full
|
||||
}
|
||||
|
||||
if (!payload->batteryOk && cfg->getliPo()) data->axis3 = 50; // Stop the vehicle, if the battery is empty!
|
||||
if (!data->batteryOk && cfg->getliPo()) data->axis3 = 50; // Stop the vehicle, if the battery is empty!
|
||||
|
||||
// Acceleration & deceleration limitation (ms per 1 step input signal change)
|
||||
if (data->mode2) {
|
||||
@@ -178,7 +197,7 @@ void driveMotorsCar() {
|
||||
if (Motor1.drive(data->axis3, cfg->getminPWM(), maxPWM, maxAcceleration, true) ) { // The drive motor (function returns true, if not in neutral)
|
||||
UpdatemillisLightOff(); // Reset the headlight delay timer, if the vehicle is driving!
|
||||
}
|
||||
if (cfg->getvehicleType() != 5) { // If not car with MSRC stabilty control
|
||||
if (cfg->getvehicleType() != carwithMRSC) { // If not car with MSRC stabilty control
|
||||
Motor2.drive(data->axis1, 0, cfg->getsteeringTorque(), 0, false); // The steering motor (if the original steering motor is reused instead of a servo)
|
||||
}
|
||||
}
|
||||
@@ -199,7 +218,7 @@ void driveMotorsForklift() {
|
||||
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
RcData* data = getDataptr();
|
||||
ackPayload* payload = getPayloadptr();
|
||||
//ackPayload* payload = getPayloadptr();
|
||||
|
||||
int maxPWM;
|
||||
byte maxAcceleration;
|
||||
@@ -211,7 +230,7 @@ void driveMotorsForklift() {
|
||||
maxPWM = cfg->getmaxPWMfull(); // Full
|
||||
}
|
||||
|
||||
if (!payload->batteryOk && cfg->getliPo()) data->axis3 = 50; // Stop the vehicle, if the battery is empty!
|
||||
if (!data->batteryOk && cfg->getliPo()) data->axis3 = 50; // Stop the vehicle, if the battery is empty!
|
||||
|
||||
// Acceleration & deceleration limitation (ms per 1 step input signal change)
|
||||
if (data->mode2) {
|
||||
@@ -254,7 +273,7 @@ void driveMotorsSteering() {
|
||||
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
RcData* data = getDataptr();
|
||||
ackPayload* payload = getPayloadptr();
|
||||
//ackPayload* payload = getPayloadptr();
|
||||
|
||||
// The steering overlay
|
||||
int steeringFactorLeft=0;
|
||||
@@ -312,7 +331,7 @@ void driveMotorsSteering() {
|
||||
pwm[0] = map(pwm[0], 100, -100, 100, 0); // convert -100 to 100% to 0-100 for motor control
|
||||
pwm[1] = map(pwm[1], 100, -100, 100, 0);
|
||||
|
||||
if (!payload->batteryOk && cfg->getliPo()) { // Both motors off, if LiPo battery is empty!
|
||||
if (!data->batteryOk && cfg->getliPo()) { // Both motors off, if LiPo battery is empty!
|
||||
pwm[0] = 0;
|
||||
pwm[1] = 0;
|
||||
}
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#ifndef MOTORSH
|
||||
#define MOTORSH
|
||||
|
||||
#include "../lib/MC34933/MC34933.h" // https://github.com/willumpie82/MC34933
|
||||
#include "MC34933.h"
|
||||
|
||||
typedef enum motor_e
|
||||
{
|
||||
@@ -9,6 +9,9 @@ typedef enum motor_e
|
||||
MOTOR2
|
||||
}motor_t;
|
||||
|
||||
// motor wrapper functions
|
||||
void motordrive(motor_t motor, int controlValue, int minPWM, int maxPWM, int rampTime, bool neutralBrake);
|
||||
bool motorBrakeActive(motor_t motor);
|
||||
|
||||
// Motors
|
||||
bool getIsDriving();
|
||||
@@ -20,6 +23,8 @@ void driveMotorsForklift();
|
||||
void driveMotorsSteering();
|
||||
void drive();
|
||||
|
||||
MC34933* getMotorptr(motor_t motor);
|
||||
|
||||
|
||||
//MC34933* getMotorptr(motor_t motor);
|
||||
|
||||
#endif //MOTORSH
|
||||
217
src/radio.cpp
217
src/radio.cpp
@@ -1,217 +0,0 @@
|
||||
#include <arduino.h>
|
||||
#include "radio.h"
|
||||
#include "lights.h"
|
||||
#include "vehicleConfig.h"
|
||||
#include "rc_board.h"
|
||||
|
||||
#include "../../lib/SBUS/src/SBUS.h"
|
||||
|
||||
// Hardware configuration: Set up nRF24L01 radio on hardware SPI bus & pins 8 (CE) & 7 (CSN)
|
||||
#ifdef CONFIG_HAS_NRF24
|
||||
RF24 radio(8, 7);
|
||||
#endif
|
||||
|
||||
// SBUS object
|
||||
#ifdef CONFIG_HAS_SBUS
|
||||
#ifndef DEBUG
|
||||
SBUS x8r(Serial);
|
||||
|
||||
SBUS* getSBUSptr( void ){return &x8r;}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
RcData data;
|
||||
|
||||
RcData* getDataptr(void)
|
||||
{
|
||||
return &data;
|
||||
}
|
||||
// Radio channels (126 channels are supported)
|
||||
byte chPointer = 0; // Channel 1 (the first entry of the array) is active by default
|
||||
const byte NRFchannel[] {
|
||||
1, 2
|
||||
};
|
||||
|
||||
// the ID number of the used "radio pipe" must match with the selected ID on the transmitter!
|
||||
// 10 ID's are available @ the moment
|
||||
const uint64_t pipeIn[] = {
|
||||
0xE9E8F0F0B1LL, 0xE9E8F0F0B2LL, 0xE9E8F0F0B3LL, 0xE9E8F0F0B4LL, 0xE9E8F0F0B5LL,
|
||||
0xE9E8F0F0B6LL, 0xE9E8F0F0B7LL, 0xE9E8F0F0B8LL, 0xE9E8F0F0B9LL, 0xE9E8F0F0B0LL
|
||||
};
|
||||
const int maxVehicleNumber = (sizeof(pipeIn) / (sizeof(uint64_t)));
|
||||
|
||||
ackPayload payload;
|
||||
|
||||
ackPayload* getPayloadptr( void )
|
||||
{
|
||||
return &payload;
|
||||
}
|
||||
|
||||
//
|
||||
// =======================================================================================================
|
||||
// RADIO SETUP
|
||||
// =======================================================================================================
|
||||
//
|
||||
|
||||
void setupRadio() {
|
||||
#ifdef CONFIG_HAS_NRF24
|
||||
|
||||
radio.begin();
|
||||
radio.setChannel(NRFchannel[chPointer]);
|
||||
|
||||
// Set Power Amplifier (PA) level to one of four levels: RF24_PA_MIN, RF24_PA_LOW, RF24_PA_HIGH and RF24_PA_MAX
|
||||
radio.setPALevel(RF24_PA_HIGH); // HIGH
|
||||
|
||||
radio.setDataRate(RF24_250KBPS);
|
||||
radio.setAutoAck(pipeIn[vehicleNumber - 1], true); // Ensure autoACK is enabled
|
||||
radio.enableAckPayload();
|
||||
radio.enableDynamicPayloads();
|
||||
radio.setRetries(5, 5); // 5x250us delay (blocking!!), max. 5 retries
|
||||
//radio.setCRCLength(RF24_CRC_8); // Use 8-bit CRC for performance
|
||||
|
||||
#ifdef DEBUG
|
||||
radio.printDetails();
|
||||
delay(3000);
|
||||
#endif
|
||||
|
||||
radio.openReadingPipe(1, pipeIn[vehicleNumber - 1]);
|
||||
radio.startListening();
|
||||
#endif
|
||||
}
|
||||
|
||||
//
|
||||
// =======================================================================================================
|
||||
// READ RADIO DATA
|
||||
// =======================================================================================================
|
||||
//
|
||||
|
||||
void readRadio() {
|
||||
#ifdef CONFIG_HAS_NRF24
|
||||
|
||||
static unsigned long lastRecvTime = 0;
|
||||
byte pipeNo;
|
||||
|
||||
if (radio.available(&pipeNo)) {
|
||||
radio.writeAckPayload(pipeNo, &payload, sizeof(struct ackPayload) ); // prepare the ACK payload
|
||||
radio.read(&data, sizeof(struct RcData)); // read the radia data and send out the ACK payload
|
||||
hazard = false;
|
||||
lastRecvTime = millis();
|
||||
#ifdef DEBUG
|
||||
Serial.print(data.axis1);
|
||||
Serial.print("\t");
|
||||
Serial.print(data.axis2);
|
||||
Serial.print("\t");
|
||||
Serial.print(data.axis3);
|
||||
Serial.print("\t");
|
||||
Serial.print(data.axis4);
|
||||
Serial.println("\t");
|
||||
#endif
|
||||
}
|
||||
|
||||
// Switch channel
|
||||
if (millis() - lastRecvTime > 500) {
|
||||
chPointer ++;
|
||||
if (chPointer >= sizeof((*NRFchannel) / sizeof(byte))) chPointer = 0;
|
||||
radio.setChannel(NRFchannel[chPointer]);
|
||||
payload.channel = NRFchannel[chPointer];
|
||||
}
|
||||
|
||||
if (millis() - lastRecvTime > 1000) { // set all analog values to their middle position, if no RC signal is received during 1s!
|
||||
data.axis1 = 50; // Aileron (Steering for car)
|
||||
data.axis2 = 50; // Elevator
|
||||
data.axis3 = 50; // Throttle
|
||||
data.axis4 = 50; // Rudder
|
||||
hazard = true; // Enable hazard lights
|
||||
payload.batteryOk = true; // Clear low battery alert (allows to re-enable the vehicle, if you switch off the transmitter)
|
||||
#ifdef DEBUG
|
||||
Serial.println("No Radio Available - Check Transmitter!");
|
||||
#endif
|
||||
}
|
||||
|
||||
if (millis() - lastRecvTime > 2000) {
|
||||
setupRadio(); // re-initialize radio
|
||||
lastRecvTime = millis();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
//
|
||||
// =======================================================================================================
|
||||
// SBUS COMMANDS TO LIGHT- & SOUND CONTROLLER (if not DEBUG, not TXO_momentary1, not TXO_toggle1, not headLights)
|
||||
// =======================================================================================================
|
||||
//
|
||||
|
||||
void sendSbusCommands()
|
||||
{
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
|
||||
static unsigned long lastSbusTime;
|
||||
uint16_t channels[16];
|
||||
|
||||
// See: https://github.com/TheDIYGuy999/Rc_Engine_Sound_ESP32
|
||||
|
||||
if (cfg->serialCommands) { // only, if we are in serial command mode
|
||||
if (millis() - lastSbusTime > 14) { // Send the data every 14ms
|
||||
lastSbusTime = millis();
|
||||
|
||||
// Fill SBUS packet with our channels
|
||||
|
||||
// Proportional channels
|
||||
channels[0] = map(data.axis1, 0, 100, 172, 1811);
|
||||
channels[1] = map(data.axis2, 0, 100, 172, 1811);
|
||||
channels[2] = map(data.axis3, 0, 100, 172, 1811);
|
||||
channels[3] = map(data.axis4, 0, 100, 172, 1811);
|
||||
channels[4] = map(data.pot1, 0, 100, 172, 1811);
|
||||
|
||||
// Switches etc.
|
||||
if (data.mode1) channels[5] = 1811; else channels[5] = 172;
|
||||
if (data.mode2) channels[6] = 1811; else channels[6] = 172;
|
||||
if (data.momentary1) channels[7] = 1811; else channels[7] = 172;
|
||||
if (getHazard()) channels[8] = 1811; else channels[8] = 172;
|
||||
if (getLeft()) channels[9] = 1811; else channels[9] = 172;
|
||||
if (getRight()) channels[10] = 1811; else channels[10] = 172;
|
||||
|
||||
// write the SBUS packet
|
||||
#ifdef CONFIG_HAS_SBUS
|
||||
x8r.write(&channels[0]);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// =======================================================================================================
|
||||
// SERIAL COMMANDS TO LIGHT- & SOUND CONTROLLER (if not DEBUG, not TXO_momentary1, not TXO_toggle1, not headLights)
|
||||
// =======================================================================================================
|
||||
//
|
||||
|
||||
void sendSerialCommands()
|
||||
{
|
||||
vehicleConfig* cfg = getConfigptr();
|
||||
|
||||
static unsigned long lastSerialTime;
|
||||
|
||||
// '\n' is used as delimiter (separator of variables) during parsing on the sound controller
|
||||
// it is generated by the "println" (print line) command!
|
||||
// See: https://github.com/TheDIYGuy999/Rc_Engine_Sound_ESP32
|
||||
|
||||
if (cfg->serialCommands) { // only, if we are in serial command mode
|
||||
if (millis() - lastSerialTime > 20) { // Send the data every 20ms
|
||||
lastSerialTime = millis();
|
||||
Serial.print('<'); // Start marker
|
||||
Serial.println(data.axis1);
|
||||
Serial.println(data.axis2);
|
||||
Serial.println(data.axis3);
|
||||
Serial.println(data.axis4);
|
||||
Serial.println(data.pot1);
|
||||
Serial.println(data.mode1);
|
||||
Serial.println(data.mode2);
|
||||
Serial.println(data.momentary1);
|
||||
Serial.println(getHazard());
|
||||
Serial.println(getLeft());
|
||||
Serial.println(getRight());
|
||||
Serial.print('>'); // End marker
|
||||
}
|
||||
}
|
||||
}
|
||||
44
src/radio.h
44
src/radio.h
@@ -1,44 +0,0 @@
|
||||
#ifndef RADIOH
|
||||
#define RADIOH
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "../../lib/SBUS/src/SBUS.h"
|
||||
|
||||
|
||||
|
||||
|
||||
// The size of this struct should not exceed 32 bytes
|
||||
struct RcData {
|
||||
byte axis1; // Aileron (Steering for car)
|
||||
byte axis2; // Elevator
|
||||
byte axis3; // Throttle
|
||||
byte axis4; // Rudder
|
||||
bool mode1 = false; // Mode1 (toggle speed limitation)
|
||||
bool mode2 = false; // Mode2 (toggle acc. / dec. limitation)
|
||||
bool momentary1 = false; // Momentary push button
|
||||
byte pot1; // Potentiometer
|
||||
};
|
||||
|
||||
|
||||
// This struct defines data, which are embedded inside the ACK payload
|
||||
struct ackPayload {
|
||||
float vcc; // vehicle vcc voltage
|
||||
float batteryVoltage; // vehicle battery voltage
|
||||
bool batteryOk = true; // the vehicle battery voltage is OK!
|
||||
byte channel = 1; // the channel number
|
||||
};
|
||||
|
||||
|
||||
|
||||
// Function prototypes
|
||||
ackPayload* getPayloadptr( void );
|
||||
RcData* getDataptr(void);
|
||||
void readRadio( void );
|
||||
void setupRadio( void );
|
||||
|
||||
void sendSerialCommands( void );
|
||||
SBUS* getSBUSptr( void );
|
||||
void sendSbusCommands( void );
|
||||
|
||||
|
||||
#endif // RADIOH
|
||||
@@ -2,8 +2,8 @@
|
||||
#define RCBOARDH
|
||||
|
||||
//#define CONFIG_HAS_TONE
|
||||
//#define CONFIG_HAS_NRF24
|
||||
#define CONFIG_HAS_SBUS
|
||||
#define CONFIG_HAS_NRF24
|
||||
//#define CONFIG_HAS_SBUS
|
||||
//#define CONFIG_HAS_LIGHTS
|
||||
//#define CONFIG_HAS_SERVO
|
||||
|
||||
|
||||
@@ -7,6 +7,16 @@
|
||||
// =======================================================================================================
|
||||
//
|
||||
|
||||
void setupServos( void )
|
||||
{
|
||||
#ifdef CONFIG_HAS_SERVO
|
||||
servo1.attach(A0);
|
||||
if (!tailLights) servo2.attach(A1);
|
||||
if (!engineSound && !toneOut) servo3.attach(A2);
|
||||
if (!beacons) servo4.attach(A3);
|
||||
#endif //CONFIG_HAS_SERVO
|
||||
}
|
||||
|
||||
void writeServos()
|
||||
{
|
||||
#ifdef CONFIG_HAS_SERVO
|
||||
|
||||
@@ -1,6 +1,7 @@
|
||||
#ifndef SERVOSH
|
||||
#define SERVOSH
|
||||
|
||||
void writeServos();
|
||||
void writeServos( void );
|
||||
void setupServos( void );
|
||||
|
||||
#endif //SERVOSH
|
||||
@@ -89,14 +89,19 @@ vehicleConfig* getConfigptr( void )
|
||||
return &cfg;
|
||||
}
|
||||
|
||||
void setupConfig(vehicleconfig_t type)
|
||||
{
|
||||
cfg.begin(type);
|
||||
}
|
||||
|
||||
void vehicleConfig::begin(vehicleconfig_t vehicle)
|
||||
{
|
||||
switch (vehicle)
|
||||
{
|
||||
case COKECANCAR:
|
||||
{
|
||||
setBasicParams(true,3.6,1.3,false,6,carwithMRSC,false,false);
|
||||
setIndicators(false,false,true,false,false);
|
||||
setBasicParams(false,3.6,1.3,false,6,carwithMRSC,false,false);
|
||||
setIndicators(false,false,false,false,false);
|
||||
setServoLimits(45,135,45,135,45,135,75,105,45,135);
|
||||
setMotorConfig(255,170,0,3,12,0,160,1);
|
||||
}
|
||||
|
||||
@@ -2,6 +2,7 @@
|
||||
#ifndef vehicleConfig_h
|
||||
#define vehicleConfig_h
|
||||
|
||||
|
||||
typedef enum vehicleconfig_e
|
||||
{
|
||||
STANDARDCAR,
|
||||
@@ -175,9 +176,12 @@ public:
|
||||
bool getengineSound(){ return m_engineSound;}
|
||||
bool gettoneOut(){ return m_toneOut;}
|
||||
|
||||
bool usesMPU( void ){return (getvehicleType() == balancingthing || getvehicleType() == carwithMRSC); }
|
||||
|
||||
}; //class vehicleConfig
|
||||
|
||||
vehicleConfig* getConfigptr( void );
|
||||
void setupConfig(vehicleconfig_t type);
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
Reference in New Issue
Block a user