Skip to content

Commit

Permalink
v9.11.0: LS3 Defender etc.
Browse files Browse the repository at this point in the history
  • Loading branch information
TheDIYGuy999 committed Dec 31, 2022
1 parent 6020a51 commit 3d2b6ed
Show file tree
Hide file tree
Showing 21 changed files with 39,128 additions and 33 deletions.
Binary file modified .DS_Store
Binary file not shown.
5 changes: 5 additions & 0 deletions documentation/Changelog.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
# Changelog

### 9.11.0:
- LS3 Engine added, used in James Bond Spectre Defender: Defender62LS3.h
- Changes in ESP32 trailer sketch. Mac addresses which are not working (causing engine revving issues) were discovered thanks to FrikkieBester. Unfortunately I still don't know why.
- In 7_adjustmentsServos.h: NO_WINCH_DELAY option added, servo signal for wincn is changed immediately in this case

### 9.10.0:
- First quick and dirty STEAM_LOCOMOTIVE_MODE implementation (see vehicles/Adler.h). Note, that you need to disable VIRTUAL_3_SPEED
- Steam whistle on horn channel
Expand Down
2 changes: 1 addition & 1 deletion platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ lib_deps =
https://github.com/TheDIYGuy999/rcTrigger
https://github.com/bmellink/IBusBM
https://github.com/Bodmer/TFT_eSPI/archive/refs/tags/2.3.70.tar.gz ; 2.3.70 is confirmed to be working properly
https://github.com/FastLED/FastLED
https://github.com/FastLED/FastLED ; the current version of FastLED may not work for all users, use version below in this case
;https://github.com/FastLED/FastLED/archive/refs/tags/3.3.3.tar.gz ; Some users are reporting, that they have to use v3.3.3
https://github.com/madhephaestus/ESP32AnalogRead
https://github.com/lbernstone/Tone32
10 changes: 6 additions & 4 deletions src/10_adjustmentsTrailer.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,15 +11,17 @@

// IMPORTANT!! Replace the addresses below with your trailers MAC addresses!! --------------------------
// Trailer 1
uint8_t broadcastAddress1[] = {0x4C, 0xEB, 0xD6, 0x7C, 0x02, 0x74}; // Bruder Low Loader
//uint8_t broadcastAddress1[] = {0x4C, 0xEB, 0xD6, 0x7C, 0x02, 0x74}; // Bruder Low Loader
uint8_t broadcastAddress1[] = {0xAC, 0x67, 0xB2, 0x37, 0xF3, 0x7C}; // SCANIA S1 (this address is causing engine revving issues, if used in combination with the trailer 2 Scania address!)
//uint8_t broadcastAddress1[] = {0x4C, 0xEB, 0xD6, 0x7C, 0x1E, 0x10}; // US flatbed
//uint8_t broadcastAddress1[] = {0xAC, 0x67, 0xB2, 0x12, 0x30, 0x28}; // white board
//uint8_t broadcastAddress1[] = {0xA0, 0x20, 0xA6, 0x10, 0x46, 0x3B}; // D1 Mini ESP8266

// Trailer 2
//#define TRAILER_2 // Uncomment this, if you want to use a 2nd trailer
//uint8_t broadcastAddress2[] = {0x4C, 0xEB, 0xD6, 0x7C, 0x02, 0x74}; // Bruder Low Loader
uint8_t broadcastAddress2[] = {0xA0, 0x20, 0xA6, 0x10, 0x46, 0x3B}; // D1 Mini ESP8266
#define TRAILER_2 // Uncomment this, if you want to use a 2nd trailer
uint8_t broadcastAddress2[] = {0x4C, 0xEB, 0xD6, 0x7C, 0x02, 0x74}; // Bruder Low Loader
//uint8_t broadcastAddress2[] = {0x34, 0x86, 0x5D, 0x3A, 0xF1, 0x5C}; //SCANIA S2
//uint8_t broadcastAddress2[] = {0xA0, 0x20, 0xA6, 0x10, 0x46, 0x3B}; // D1 Mini ESP8266

// Trailer 3 (EXPERIMENTAL, causing engine RPM issues!)
//#define TRAILER_3 // Uncomment this, if you want to use a 3rd trailer
Expand Down
3 changes: 2 additions & 1 deletion src/1_adjustmentsVehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@
//#include "vehicles/DefenderV8OpenPipe.h" // Land Rover Defender 90 V8 manual, open pipes (optimised for smaller speakers)
//#include "vehicles/DefenderV8CrawlerAutomatic.h" // Land Rover Defender 90 V8 automatic crawler
//#include "vehicles/DefenderTd5.h" // Land Rover Defender 90 Td5 R5 Diesel
#include "vehicles/Defender62LS3.h" // Land Rover Defender "Spectre" with Chevy LS3 V8

// Asian SUV --------
//#include "vehicles/LandcruiserFJ40.h" // Landcruiser Fj40 with inline 6 petrol engine
Expand All @@ -95,7 +96,7 @@
//#include "vehicles/HiluxDiesel.h" // Hilux Diesel with inline 6 12H Turbo Diesel engine (for HG-P407)

// EU locomotives --------
#include "vehicles/Adler.h" // German Adler steam locomotive
//#include "vehicles/Adler.h" // German Adler steam locomotive

// US locomotives --------
//#include "vehicles/UnionPacific2002.h" // Union Pacific 2002 SD70M locomotive with enormous, low revving 16 cylinder Diesel
Expand Down
11 changes: 5 additions & 6 deletions src/2_adjustmentsRemote.h
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
#include <Arduino.h>

// Select (remove //) the remote configuration profile you have:
//#define FLYSKY_FS_I6X // <------- Flysky FS-i6x
#define FLYSKY_FS_I6X // <------- Flysky FS-i6x
//#define FLYSKY_FS_I6S_EXCAVATOR // <------- Flysky FS-i6s for KABOLITE K336 hydraulic excavator (use IBUS communication setting)
//#define FLYSKY_GT5 // <------- Flysky GT5 / Reely GT6 EVO / Absima CR6P
//#define RGT_EX86100 // <------- MT-305 remote delivered with RGT EX86100 crawler (use PWM communication setting)
//#define GRAUPNER_MZ_12 // <------- Graupner MZ-12 PRO
#define MICRO_RC // <------- The car style DIY "Micro RC" remote. Don't use this with standard remotes!
//#define MICRO_RC // <------- The car style DIY "Micro RC" remote. Don't use this with standard remotes!
//#define MICRO_RC_STICK // <------- The stick based DIY "Micro RC" remote. Don't use this with standard remotes!

// For testing only!
Expand All @@ -19,15 +19,14 @@
// COMMUNICATION SETTINGS ********************************************************************************************************************
// Choose the receiver communication mode (never uncomment more than one!) !!! ADJUST THEM BEFORE CONNECTING YOUR RECEIVER AND ESC !!!

// PWM servo signal communication (CH1 - CH4, 35, PPM headers, 6 channels) --------
// PWM mode active, if SBUS, IBUS, and PPM are disabled (// in front of #define)
// PWM servo signal communication (CH1 - CH6 headers, 6 channels) --------
// PWM mode active, if SBUS, IBUS, SUMD and PPM are disabled (// in front of #define)

// SBUS communication (RX header, 13 channels. This is my preferred communication protocol)--------
/* NOTE! SBUS is causing weird issues with Flysky remotes. Use IBUS instead! */
#define SBUS_COMMUNICATION // control signals are coming in via the SBUS interface (comment it out for classic PWM RC signals)
// NOTE: "boolean sbusInverted = true / false" was moved to the remote configuration profiles, so you don't have to change it
uint32_t sbusBaud = 100000; // Standard is 100000. Try to lower it, if your channels are coming in unstable. Working range is about 96000 - 104000.
#define EMBEDDED_SBUS // SBUS library not used, if defined (let me know, if Flysky remotes are still unstable)
#define EMBEDDED_SBUS // Embedded SBUS code is used instead of SBUS library, if defined (recommended)
uint16_t sbusFailsafeTimeout = 100; // Failsafe is triggered after this timeout in milliseconds (about 100)

// IBUS communication (RX header, 13 channels not recommended, NO FAILSAFE, if bad contact in iBUS wiring!) --------
Expand Down
12 changes: 6 additions & 6 deletions src/3_adjustmentsESC.h
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ const uint16_t escTakeoffPunch = 0;
const uint16_t escReversePlus = 0;

// Brake margin: (Experimental!)
// This setting prevents the ESC from going completely back to zero / neutral as long as the braker trigger is pulled.
// This setting prevents the ESC from going completely back to zero / neutral as long as the brake trigger is pulled.
// This prevents the vehicle from rolling back as long as brake is applied. 0 = no effect, ca. 20 = strong effect.
// How it works? Prevents the ESC from entering the "drag brake range"
// Warning: vehicle may be unable to stop, if too high, especially when driving downhill! NEVER more than 20!
Expand All @@ -119,21 +119,21 @@ const uint16_t brakeMargin = 0; // For RZ7886 motor driver and 370 motor = 10
const uint8_t crawlerEscRampTime = 10; // about 10 (15 for Jeep), less = more direct control = less virtual inertia

// Allows to scale vehicle file dependent acceleration
uint16_t globalAccelerationPercentage = 70; // about 100 - 200% (200 for Jeep) Experimental, may cause automatic transmission shifting issues!
uint16_t globalAccelerationPercentage = 150; // about 100 - 200% (200 for Jeep, 150 for 1/8 Landy) Experimental, may cause automatic transmission shifting issues!

/* Battery low discharge protection (only for boards with voltage divider resistors):
* IMPORTANT: Enter used resistor values in Ohms (Ω) and THEN adjust DIODE_DROP, until your readings match the actual battery voltage! */
//#define BATTERY_PROTECTION // This will disable the ESC output, if the battery cutout voltage is reached
#define BATTERY_PROTECTION // This will disable the ESC output, if the battery cutout voltage is reached
const float CUTOFF_VOLTAGE = 3.3; // Usually 3.3 V per LiPo cell. NEVER below 3.2 V!
const float FULLY_CHARGED_VOLTAGE = 4.2; // Usually 4.2 V per LiPo cell, NEVER above!
const float RECOVERY_HYSTERESIS = 0.2; // around 0.2 V
/* Note on resistor values: These values will be used to calculate the actual ratio between these two resistors (which is also called a "voltage divider").
* When selecting resistors, always use two of the same magnitude: Like, for example, 10k/2k, 20k/4k or 100k/20k. NEVER exceed a ratio LOWER than (4:1 = 4)!
* WARNING: If the ratio is too LOW, like 10k/5k (2:1 = 2), the battery voltage will most likely DAMAGE the controller permanently!
* Example calculation: 2000 / (2000 + 10000) = 0.166 666 666 7; 7.4 V * 0.167 = 1.2358 V (of 3.3 V maximum on GPIO Pin). */
uint32_t RESISTOR_TO_BATTTERY_PLUS = 99900; // Value in Ohms (Ω), for example 10000
uint32_t RESISTOR_TO_GND = 19800; // Value in Ohms (Ω), for example 2000. Measuring exact resistor values before soldering, if possible is recommended!
float DIODE_DROP = 0.0; // Fine adjust measured value and/or consider diode voltage drop (about 0.34V for SS34 diode)
uint32_t RESISTOR_TO_BATTTERY_PLUS = 9600; // Value in Ohms (Ω), for example 10000
uint32_t RESISTOR_TO_GND = 1000; // Value in Ohms (Ω), for example 2000. Measuring exact resistor values before soldering, if possible is recommended!
float DIODE_DROP = 0.31; // Fine adjust measured value and/or consider diode voltage drop (about 0.34V for SS34 diode)
/* It is recommended to add a sticker to your ESP32, which includes the 3 calibration values above */
volatile int outOfFuelVolumePercentage = 80; // Adjust the message volume in %
// Select the out of fuel message you want:
Expand Down
4 changes: 2 additions & 2 deletions src/6_adjustmentsLights.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@

// Choose the animation you want
//#define NEOPIXEL_DEMO // Demo
//#define NEOPIXEL_KNIGHT_RIDER // Knight Rider scanner animation for 8 LED (use it in combination with "kittScanner.h" "siren" sound in your vehicle file)
#define NEOPIXEL_KNIGHT_RIDER // Knight Rider scanner animation for 8 LED (use it in combination with "kittScanner.h" "siren" sound in your vehicle file)
//#define NEOPIXEL_BLUELIGHT // Bluelight animation for 8 LED
#define NEOPIXEL_UNION_JACK // United Kingdom animation for 8 LED (use it in combination with "BritishNationalAnthemSiren.h" sound in your vehicle file)
//#define NEOPIXEL_UNION_JACK // United Kingdom animation for 8 LED (use it in combination with "BritishNationalAnthemSiren.h" sound in your vehicle file)
#define NEOPIXEL_HIGHBEAM // Neopixel bar is used as high beam as well, if defined. Also usable in combination with NEOPIXEL_KNIGHT_RIDER & NEOPIXEL_BLUELIGHT
//#define NEOPIXEL_B33LZ3BUB // B33lz3bub Austria animation for 3 LED: https://www.rc-modellbau-portal.de/index.php?threads/baubericht-mercedes-actros-1851-gigaspace-tamiya.14349/page-3

Expand Down
30 changes: 27 additions & 3 deletions src/7_adjustmentsServos.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,9 @@

// Select the vehicle configuration you have:
//#define SERVOS_DEFAULT // <------- Select (remove //) one of the remote configurations below
//#define SERVOS_LANDY
#define SERVOS_C34
//#define SERVOS_LANDY_MN_MODEL
#define SERVOS_LANDY_DOUBLE_EAGLE
//#define SERVOS_C34
//#define SERVOS_URAL
//#define SERVOS_RGT_EX86100
//#define SERVOS_ACTROS
Expand All @@ -49,7 +50,7 @@ const uint16_t STEERING_RAMP_TIME = 0; // 0 = fastest speed, enlarge it to aroun

#endif

// Land Rover Defender servo configuration profile -------------------------------------------------------------------------------------------
// MN Model 1:12 Land Rover Defender servo configuration profile -------------------------------------------------------------------
#ifdef SERVOS_LANDY

// Servo frequency
Expand All @@ -68,6 +69,28 @@ const uint16_t STEERING_RAMP_TIME = 0; // 0 = fastest speed, enlarge it to aroun

#endif

// Double Eagle 1:8 Land Rover Defender servo configuration profile -------------------------------------------------------------------
#ifdef SERVOS_LANDY_DOUBLE_EAGLE

#define MODE2_WINCH // Mode 2 is used for winch mode, if defined. The winch is controlled by the CH4 pot and connected to Servo CH3. BUS mode only!
//#define NO_WINCH_DELAY // Use this, if you don't want a winch on / off ramp

// Servo frequency
const uint8_t SERVO_FREQUENCY = 50; // usually 50Hz, some servos may run smoother @ 100Hz

// WARNING: never connect receiver PWM signals to the "CH" pins in BUS communication mode!

// Servo limits
const uint16_t CH1L = 900, CH1C = 1600, CH1R = 2200; // CH1 steering left 900, center 1600, right 2200
const uint16_t CH2L = 1900, CH2C = 1000, CH2R = 1000; // CH2 transmission gear 1 1900, 2 1000, 3 1000
const uint16_t CH3L = 2000, CH3C = 1500, CH3R = 1000; // CH3 winch pull, off, release
const uint16_t CH4L = 1300, CH4R = 1700; // CH4 trailer coupler (5th. wheel) locked, unlocked

// Servo ramp time
const uint16_t STEERING_RAMP_TIME = 0; // 0 = fastest speed, enlarge it to around 3000 for "scale" servo movements

#endif

// WPL C34 Toyota Land Cruiser configuration profile -------------------------------------------------------------------------------------------
#ifdef SERVOS_C34

Expand Down Expand Up @@ -110,6 +133,7 @@ const uint16_t STEERING_RAMP_TIME = 0; // 0 = fastest speed, enlarge it to aroun
#ifdef SERVOS_RGT_EX86100

#define MODE2_WINCH // Mode 2 is used for winch mode, if defined. The winch is controlled by the CH4 pot and connected to Servo CH3. BUS mode only!
#define NO_WINCH_DELAY // Use this, if you don't want a winch on / off ramp

// Servo frequency
const uint8_t SERVO_FREQUENCY = 50; // usually 50Hz, some servos may run smoother @ 100Hz
Expand Down
Binary file added src/lib/.DS_Store
Binary file not shown.
46 changes: 46 additions & 0 deletions src/lib/README
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@

This directory is intended for project specific (private) libraries.
PlatformIO will compile them to static libraries and link into executable file.

The source code of each library should be placed in a an own separate directory
("lib/your_library_name/[here are source files]").

For example, see a structure of the following two libraries `Foo` and `Bar`:

|--lib
| |
| |--Bar
| | |--docs
| | |--examples
| | |--src
| | |- Bar.c
| | |- Bar.h
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
| |
| |--Foo
| | |- Foo.c
| | |- Foo.h
| |
| |- README --> THIS FILE
|
|- platformio.ini
|--src
|- main.c

and a contents of `src/main.c`:
```
#include <Foo.h>
#include <Bar.h>

int main (void)
{
...
}

```

PlatformIO Library Dependency Finder will find automatically dependent
libraries scanning project source files.

More information about PlatformIO Library Dependency Finder
- https://docs.platformio.org/page/librarymanager/ldf.html
24 changes: 19 additions & 5 deletions src/src.ino
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
Arduino IDE is supported as before, but stuff was renamed and moved to different folders!
*/

char codeVersion[] = "9.10.0"; // Software revision.
char codeVersion[] = "9.11.0"; // Software revision.

// This stuff is required for Visual Studio Code IDE, if .ino is renamed into .cpp!
#include <Arduino.h>
Expand Down Expand Up @@ -121,7 +121,7 @@ float batteryVolts();

// The following tasks only required for Arduino IDE! ----
// Install ESP32 board according to: https://randomnerdtutorials.com/installing-the-esp32-board-in-arduino-ide-windows-instructions/
// Warning: Use Espressif ESP32 board definition v1.06! v2.x is not working
// Warning: Use Espressif ESP32 board definition v1.05 or 10.6! v2.x is not working
// Adjust board settings according to: https://github.com/TheDIYGuy999/Rc_Engine_Sound_ESP32/blob/master/pictures/settings.png

// Visual Studio Code IDE instructions: ----
Expand Down Expand Up @@ -840,6 +840,14 @@ void IRAM_ATTR fixedPlaybackTimer() {
fixedTimerTicks = 4000000 / sirenSampleRate; // our fixed sampling rate
timerAlarmWrite(fixedTimer, fixedTimerTicks, true); // // change timer ticks, autoreload true

#if defined SIREN_STOP
if (!sirenTrigger) {
sirenLatch = false;
curSirenSample = 0;
a2 = 0;
}
#endif

if (curSirenSample < sirenSampleCount - 1) {
a2 = (sirenSamples[curSirenSample] * sirenVolumePercentage / 100);
curSirenSample ++;
Expand Down Expand Up @@ -1391,15 +1399,15 @@ void setupEspNow() {
peerInfo.encrypt = false;

// Add peer 1 (1st trailer)
memcpy(peerInfo.peer_addr, broadcastAddress1, ESP_NOW_ETH_ALEN);
memcpy(peerInfo.peer_addr, broadcastAddress1, 6); // TODO!
if (esp_now_add_peer(&peerInfo) != ESP_OK) {
Serial.printf("Failed to add peer #1 (1st trailer)\n");
return;
}

// Add peer 2 (2nd trailer)
#ifdef TRAILER_2
memcpy(peerInfo.peer_addr, broadcastAddress2, ESP_NOW_ETH_ALEN);
memcpy(peerInfo.peer_addr, broadcastAddress2, 6);
if (esp_now_add_peer(&peerInfo) != ESP_OK) {
Serial.printf("Failed to add peer #2 (2nd trailer)\n");
return;
Expand Down Expand Up @@ -2265,11 +2273,17 @@ void mcpwmOutput() {
mcpwm_set_duty_in_us(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B, shiftingServoMicros);

// Winch CH3 **********************
#if defined NO_WINCH_DELAY
uint16_t winchDelayTarget = 0; // Servo signal for winch is changed immediately
#else
uint16_t winchDelayTarget = 12000; // Servo signal for winch is changed slowly
#endif

#if defined MODE2_WINCH
static uint16_t winchServoMicrosTarget = CH3C;
static uint16_t winchServoMicros = CH3C;
static unsigned long winchDelayMicros;
if (micros() - winchDelayMicros > 12000) {
if (micros() - winchDelayMicros > winchDelayTarget) {
winchDelayMicros = micros();
if (winchPull) winchServoMicrosTarget = CH3L;
else if (winchRelease) winchServoMicrosTarget = CH3R;
Expand Down
Loading

0 comments on commit 3d2b6ed

Please sign in to comment.