Skip to content

Commit

Permalink
v0.14.0: Oscilloscope, frequency counter and much more
Browse files Browse the repository at this point in the history
  • Loading branch information
TheDIYGuy999 committed Mar 11, 2023
1 parent 8e19c81 commit d8d05d1
Show file tree
Hide file tree
Showing 9 changed files with 164 additions and 90 deletions.
46 changes: 34 additions & 12 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,36 +23,58 @@ Support thread (in German and English): https://www.rc-modellbau-portal.de/index
## Menu
![](documentation/pictures/menu.png)

## Oscilloscope 0 - 3.3V
![](documentation/pictures/scope.jpg)

![](documentation/pictures/ppm_scope.jpg)

## Calculator
![](documentation/pictures/scope.jpg)

## Features
- 5 channel PWM Signal generator for the following modes: STD, NOR, SSR, SUR, SXR
- manual or automatic movement modes
- PWM read function with pulsewidth and frequency display
- PPM, SBUS and IBUS read function
- Oscilloscope for 3.3V RC signals, PWM and PPM signals can be visualized well
- Calculator
- P O N G game
- Flappy Birds game
- Settings menu, parameters are stored in EEPROM
- Operation via rotary encoder with push button
- Supply via USB (for small servos) or XT-60 plug
- 0.96 or 1.3 Inch OLED display
- Some functions can be controlled via the built in website


## TODO Software ****************************************
- make servo center and endpoints flexible
- remove PPM menu delay
- fix PWM read bargraph
- Menu: Add beep on / off & servo stroke, remove servo stuff except frequency
- Add servo output in signal read mode
- Add frequency measuring for PWM input
- Add servo output in signal read mode (decoder)

## TODO Hardware ****************************************
- Capacitor for 5V rail
- Capacitor for smooth upload
- Anti backfeed diode with jumper
- Room for buzzer
- separate connector for BUS inputs
- Connector for gyro sensor

## ******************************************************

## Changelog

## New in v0.14-beta.1:
- SSL servo mode removed
- SSR, SUR and SXR frequencies changed, now working with Sanwa PGS-CL II servo
## New in v0.14.0:
- Oscilloscope added
- BUS & oscilloscope input is on CH 5 now

## New in v0.14-beta.0:
- Precise frequency counter in PWM impulse read mode added
- fixed PWM impulse read bargraph issues
- SSL servo mode removed, because it was useless
- SSR, SUR and SXR frequencies changed, now working with Sanwa PGS-CL II servo
- Added support for active 3V buzzer on GPIO 4
- Calculator: added power of
- Servo operation mode names are displayed, if known
- ESP32Servo removed, repaced with native MCPWM ESP32 functionality. Allows way faster servo timings
- A lot of new servo modes added, more servo info on screen
- ESP32Servo library removed, repaced with native MCPWM ESP32 functionality. Allows way faster servo timings
- A lot of new servo modes added, names are displayed on screen

## New in v0.13.0:
- Servo Hz setting effective on all servo channels and in automatic mode
Expand Down
Binary file added documentation/pictures/calculator.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added documentation/pictures/ppm_scope.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added documentation/pictures/scope.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
2 changes: 1 addition & 1 deletion src/0_generalSettings.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
*/

// Display settings ----------------------------------------------------------------------------------------------
//#define OLED1306 //A SSD1306 0.96" Display is selected, if defined. Otherwise a SH1106 1.3" display
//#define OLED1306 //An SSD1306 0.96" Display is selected, if defined. Otherwise an SH1106 1.3" display
//#define ALTERNATIVE_LOGO // Alternative boot logo

// WiFi settings -------------------------------------------------------------------------------------------------
Expand Down
131 changes: 91 additions & 40 deletions src/src.ino
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
GPIO 22: SDL OLED
*/

char codeVersion[] = "0.14-beta.1"; // Software revision.
char codeVersion[] = "0.14.0"; // Software revision.

//
// =======================================================================================================
Expand All @@ -55,7 +55,7 @@ char codeVersion[] = "0.14-beta.1"; // Software revision.
// No manual library download is required in Visual Studio Code IDE (see platformio.ini)

/* Boardversion
ESP32 2.0.5 or 2.0.6 <<--- (make sure your Espressif32 piatform is up to date in Platformio > Platforms > Updates)
ESP32 2.0.5 or 2.0.6 <<--- (make sure your Espressif32 platform is up to date in Platformio > Platforms > Updates)
*/

/* Required Libraries / Benötigte Bibliotheken
Expand Down Expand Up @@ -148,18 +148,17 @@ bool disableButtonRead; // In gewissen Situationen soll der Encoder Button
#define SERVO_CONNECTOR_5 32

// Servo
volatile unsigned char servopin[5] = {SERVO_CONNECTOR_1, SERVO_CONNECTOR_2, SERVO_CONNECTOR_3, SERVO_CONNECTOR_4, SERVO_CONNECTOR_5}; // Pins Servoausgang 1 - 5
// Servo servo[5]; // Servo Objekte erzeugen
int servo_pos[5]; // Speicher für Servowerte
int selectedServo = 0; // Das momentan angesteuerte Servo
String servoMode = ""; // Servo operation mode text
uint8_t servopin[5] = {SERVO_CONNECTOR_1, SERVO_CONNECTOR_2, SERVO_CONNECTOR_3, SERVO_CONNECTOR_4, SERVO_CONNECTOR_5}; // Pins Servoausgang 1 - 5 // Servo Objekte erzeugen
int servo_pos[5]; // Speicher für Servowerte
int selectedServo = 0; // Das momentan angesteuerte Servo
String servoMode = ""; // Servo operation mode text

// Servo operation modes
// Servo operation modes (see servoModes.h)
enum
{
STD, // Std = 50Hz 1000 - 1500 - 2000µs = gemäss ursprünglichem Standard
NOR, // NOR = 100Hz 1000 - 1500 - 2000µs = normal = für die meisten analogen Servos
SHR, // SHR = 333Hz 1000 - 1500 - 2000µs = Sanwa High-Response = für alle Digitalservos
SHR, // SHR = 333Hz 1000 - 1500 - 2000µs = Sanwa High Response = für alle Digitalservos
SSR, // SSR = 400Hz 130 - 300 - 470µs = Sanwa Super Response = nur für Sanwa Servos der SRG-Linie
SUR, // SUR = 800Hz 130 - 300 - 470µs = Sanwa Ultra Response
SXR // SXR = 1600Hz 130 - 300 - 470µs = Sanwa Xtreme Response
Expand Down Expand Up @@ -234,6 +233,7 @@ bool Auto_Pause = 0; // Pause im Auto Modus
//-Menu 53 Impuls lesen
int Impuls_min = 1000;
int Impuls_max = 2000;
int pwmFreq = 0;

//-Menu 54 Multiwitch Futaba lesen
#define kanaele 9 // Anzahl der Multiswitch Kanäle
Expand Down Expand Up @@ -284,7 +284,7 @@ const long timeoutTime = 2000; // Define timeout time in milliseconds
// =======================================================================================================
//

// Map as Float
// Map as Float --------------------------------------------------------------------------------
float map_float(float x, float in_min, float in_max, float out_min, float out_max)
{
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
Expand All @@ -296,7 +296,7 @@ float us2degree(uint16_t value)
return map_float(float(value), float(SERVO_MIN), float(SERVO_MAX), -45.0, 45.0);
}

// buzzer control
// buzzer control ------------------------------------------------------------------------------
void beep()
{
static unsigned long buzzerTriggerMillis;
Expand All @@ -313,7 +313,7 @@ void beep()
}
}

// Loop time measurement
// Loop time measurement -----------------------------------------------------------------------
unsigned long loopDuration()
{
static unsigned long timerOld;
Expand All @@ -324,7 +324,35 @@ unsigned long loopDuration()
return loopTime;
}

// Additional headers
// Frequency counter ---------------------------------------------------------------------------
#define WAIT_FOR_PIN_STATE(state) \
while (digitalRead(pin) != (state)) \
{ \
if (cpu_hal_get_cycle_count() - start_cycle_count > timeout_cycles) \
{ \
return 0; \
} \
}

unsigned long readFreq(uint8_t pin, uint8_t state, unsigned long timeout)
{
const uint32_t max_timeout_us = clockCyclesToMicroseconds(UINT_MAX);
if (timeout > max_timeout_us)
{
timeout = max_timeout_us;
}
const uint32_t timeout_cycles = microsecondsToClockCycles(timeout);
const uint32_t start_cycle_count = cpu_hal_get_cycle_count();
WAIT_FOR_PIN_STATE(!state);
WAIT_FOR_PIN_STATE(state); // Signal going high
const uint32_t pulse_start_cycle_count = cpu_hal_get_cycle_count(); // Store start time
WAIT_FOR_PIN_STATE(!state); // Signal going low
WAIT_FOR_PIN_STATE(state); // Signal going high again

return 1000000 / (clockCyclesToMicroseconds(cpu_hal_get_cycle_count() - pulse_start_cycle_count));
}

// Additional headers --------------------------------------------------------------------------
#include "src/pong.h" // A little pong game :-)
#include "src/flappyBirds.h" // A little flappy birds game :-)
#include "src/calculator.h" // A handy calculator
Expand Down Expand Up @@ -648,7 +676,8 @@ void MenuUpdate()
{
// Servotester Auswahl *********************************************************
case Servotester_Auswahl:
servoModes(); // Refresh servo operation mode
servoModes(); // Refresh servo operation mode
batteryVolts(); // Read battery voltage
display.clear();
display.setTextAlignment(TEXT_ALIGN_CENTER);
display.setFont(ArialMT_Plain_24);
Expand Down Expand Up @@ -1192,6 +1221,8 @@ void MenuUpdate()
// PWM Impuls lesen *********************************************************
case Impuls_lesen_Menu:

bool parameterSet; // See servoModes.h

if (!SetupMenu)
{
pinMode(servopin[0], INPUT);
Expand All @@ -1202,38 +1233,64 @@ void MenuUpdate()
SetupMenu = true;
}

servo_pos[selectedServo] = pulseIn(servopin[selectedServo], HIGH, 50000);
servo_pos[selectedServo] = pulseIn(servopin[selectedServo], HIGH, 50000); // Read PWM signal
pwmFreq = readFreq(servopin[selectedServo], HIGH, 50000); // Read PWM frequency

// Switch progress bar range
if (servo_pos[selectedServo] < 750)
parameterSet = 1; // Normal pulsewidth range
else
parameterSet = 0; // Sanwa pulsewidth range

if (servo_pos[selectedServo] < Impuls_min && servo_pos[selectedServo] > 100)
if (servo_pos[selectedServo] > servoMin[parameterSet] && servo_pos[selectedServo] < servoMax[parameterSet])
{
Impuls_min = servo_pos[selectedServo];
Impuls_min = servoMin[parameterSet];
Impuls_max = servoMax[parameterSet];
}

// Enlarge range, if required
if (servo_pos[selectedServo] > Impuls_max)
{
Impuls_max = servo_pos[selectedServo];
}
if (servo_pos[selectedServo] < Impuls_min)
Impuls_min = servo_pos[selectedServo];

display.clear();
display.setTextAlignment(TEXT_ALIGN_CENTER);
display.setFont(ArialMT_Plain_24);
display.drawString(64, 0, impulseString[LANGUAGE] + String(selectedServo + 1));
display.drawString(64, 25, String(servo_pos[selectedServo]) + "µs");
if (servo_pos[selectedServo] < 1000)
servo_pos[selectedServo] = 1000; // Make sure, that progressbar always is within range
display.drawProgressBar(8, 50, 112, 10, (((servo_pos[selectedServo] - Impuls_min) * 100) / (Impuls_max - Impuls_min)));
display.display();
static unsigned long pwmMenuMillis;
if (millis() - pwmMenuMillis > 100)
{ // Every 100ms (slow screen refresh down, display is too nervous otherwise!)
pwmMenuMillis = millis();
display.clear();
display.setTextAlignment(TEXT_ALIGN_CENTER);
display.setFont(ArialMT_Plain_24);
display.drawString(64, 0, impulseString[LANGUAGE] + String(selectedServo + 1));
display.drawString(64, 25, String(servo_pos[selectedServo]) + "µs");

display.setTextAlignment(TEXT_ALIGN_LEFT);
display.setFont(ArialMT_Plain_10);

display.drawString(0, 25, "Hz");
display.drawString(0, 35, String(pwmFreq));

if (pwmFreq > 1)
{
display.drawProgressBar(8, 50, 112, 10, (((servo_pos[selectedServo] - Impuls_min) * 100) / (Impuls_max - Impuls_min)));
}
else
{
display.setTextAlignment(TEXT_ALIGN_CENTER);
display.setFont(ArialMT_Plain_10);
display.drawString(64, 50, impulseSignalString[LANGUAGE]);
}

display.display();
}

if (encoderState == 1)
{
selectedServo--;
Impuls_min = 1000;
Impuls_max = 2000;
}
if (encoderState == 2)
{
selectedServo++;
Impuls_min = 1000;
Impuls_max = 2000;
}

if (selectedServo > 4)
Expand All @@ -1251,20 +1308,14 @@ void MenuUpdate()
SetupMenu = false;
selectedServo = 0;
}

if (buttonState == 2)
{
Impuls_min = 1000;
Impuls_max = 2000;
}
break;

// Multiswitch lesen *********************************************************
https: // www.modelltruck.net/showthread.php?54795-Futaba-Robbe-Multiswitch-Decoder-mit-Arduino
case Multiswitch_lesen_Menu:
static unsigned long multiswitchMenuMillis;
if (millis() - multiswitchMenuMillis > 20)
{ // Every 20ms (slow screen refresh down, signal is unstable otherwise!) TODO, still unstable
{ // Every 20ms (slow screen refresh down)
multiswitchMenuMillis = millis();
display.clear();
display.setTextAlignment(TEXT_ALIGN_LEFT);
Expand Down Expand Up @@ -2023,7 +2074,7 @@ void loop()
ButtonRead();
beep();
MenuUpdate();
batteryVolts();
// batteryVolts(); // TODO
webInterface();
// Serial.print(loopDuration());
}
1 change: 1 addition & 0 deletions src/src/languages.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ String pongBallRateString[] {"Pong ball speed", "Pong Ball Gesch.", "Pong V. de

// Impuls lesen
String impulseString[] {"Impulse", "Impuls", "Impulsion"};
String impulseSignalString[] {"No signal", "Kein Signal", "Pas de signal"};

// Automatik
String delayString[] {"Delay", "Verz.", "Ret."};
Expand Down
23 changes: 8 additions & 15 deletions src/src/oscilloscope.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,6 @@

#include "Arduino.h"

/*
###################################################################
Title: Arduino Oscilloscope
Purpose: Made for the Servotester Deluxe
Created by: TheDIYGuy999
Note: Please reuse, repurpose, and redistribute this code.
Note: ESP32 & 1106 OLED
###################################################################
*/

//
// ========================================
// GLOBAL VARIABLES
Expand All @@ -22,11 +12,11 @@

int displayWidth = 128;

int timeBase = 0; // define a variable for the x delay (90 for 50 Hz, 10 for 333, 0 for 1520)
int samplingDelay = 0; // define a variable for the X scale / delay
int sampleNo = 0; // define a variable for the sample number used to collect x position into array
int sampleHi = 0; // Samples, which are above trigger level
int posX = 0; // define a variable for the sample number used to write x position on the LCD
int timeBase = 0; // define a variable for the x delay (90 for 50 Hz, 10 for 333, 0 for 1520)
int samplingDelay = 100; // define a variable for the X scale / delay (100 is ideal for a 50Hz signal)
int sampleNo = 0; // define a variable for the sample number used to collect x position into array
int sampleHi = 0; // Samples, which are above trigger level
int posX = 0; // define a variable for the sample number used to write x position on the LCD

// array parameters
#define arraySize displayWidth // how much samples are in the array
Expand Down Expand Up @@ -82,6 +72,9 @@ void adjustADC()
popupMillis = millis();
}

if (buttonState == 2)
popupMillis = millis(); // Show popup, if button licked

samplingDelay = constrain(samplingDelay, 0, 332); // 332 for 50Hz
}

Expand Down
Loading

0 comments on commit d8d05d1

Please sign in to comment.