update for dmx
This commit is contained in:
parent
547c2f3569
commit
b92ed1a431
3
.gitmodules
vendored
3
.gitmodules
vendored
@ -4,3 +4,6 @@
|
|||||||
[submodule "lib/DMXSerial"]
|
[submodule "lib/DMXSerial"]
|
||||||
path = lib/DMXSerial
|
path = lib/DMXSerial
|
||||||
url = https://github.com/mathertel/DMXSerial
|
url = https://github.com/mathertel/DMXSerial
|
||||||
|
[submodule "lib/PWM"]
|
||||||
|
path = lib/PWM
|
||||||
|
url = https://github.com/terryjmyers/PWM
|
||||||
|
|||||||
@ -13,3 +13,4 @@ platform = atmelavr
|
|||||||
board = uno
|
board = uno
|
||||||
framework = arduino
|
framework = arduino
|
||||||
monitor_speed = 115200
|
monitor_speed = 115200
|
||||||
|
; lib_deps = mathertel/DMXSerial@^1.5.3
|
||||||
|
|||||||
14
src/main.cpp
14
src/main.cpp
@ -1,7 +1,7 @@
|
|||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <DMXSerial.h>
|
#include <DMXSerial.h>
|
||||||
#include <PID_v1.h>
|
#include <PID_v1.h>
|
||||||
#include <PWM.h>
|
#include <../lib/PWM/PWM.h>
|
||||||
|
|
||||||
// Motor Driver: IBT-2 (BTS7960)
|
// Motor Driver: IBT-2 (BTS7960)
|
||||||
#define LPWM_PIN 9 // LPWM for CCW motion (postive)
|
#define LPWM_PIN 9 // LPWM for CCW motion (postive)
|
||||||
@ -30,7 +30,7 @@
|
|||||||
#define SAMPLE_RATE 10000 // min time (us) between velocity calculations
|
#define SAMPLE_RATE 10000 // min time (us) between velocity calculations
|
||||||
#define LOOP_RATE 10 // min time (ms) between control adjustments. ** Must be >= SAMPLE_RATE (converted to us) **
|
#define LOOP_RATE 10 // min time (ms) between control adjustments. ** Must be >= SAMPLE_RATE (converted to us) **
|
||||||
|
|
||||||
#define DMX_CHANNEL 500 // DMX Channel to read
|
#define DMX_CHANNEL 2 // DMX Channel to read
|
||||||
|
|
||||||
// wall state variables:
|
// wall state variables:
|
||||||
long encoderPosition = 0; // raw count from encoder
|
long encoderPosition = 0; // raw count from encoder
|
||||||
@ -111,20 +111,12 @@ void setup() {
|
|||||||
// initialize loop timers
|
// initialize loop timers
|
||||||
prevSample = millis();
|
prevSample = millis();
|
||||||
prevControl = millis();
|
prevControl = millis();
|
||||||
// lastToggle = millis() - 2000;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
// if (millis() - lastToggle > 7000) {
|
|
||||||
// if (targetPosition == 0) {
|
|
||||||
// targetPosition = 0.5;
|
|
||||||
// } else {
|
|
||||||
// targetPosition = 0;
|
|
||||||
// }
|
|
||||||
// lastToggle = millis();
|
|
||||||
// }
|
|
||||||
|
|
||||||
if (DMXSerial.noDataSince() < 5000) {
|
if (DMXSerial.noDataSince() < 5000) {
|
||||||
|
targetPosition = (float)(DMXSerial.read(DMX_CHANNEL) - 101) / 100.0f; // 0 is disabled. position values are 1-201, 101 is center, <101 is CW, >101 is CCW. 1 & 201 are 360 degrees
|
||||||
digitalWrite(R_EN_PIN, HIGH);
|
digitalWrite(R_EN_PIN, HIGH);
|
||||||
digitalWrite(L_EN_PIN, HIGH);
|
digitalWrite(L_EN_PIN, HIGH);
|
||||||
|
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user