WS2812 and great rpm improvements

This commit is contained in:
Lukas Bachschwell 2018-05-26 22:17:12 +02:00
parent d6027e093b
commit d630525841
5 changed files with 134 additions and 29 deletions

View File

@ -33,4 +33,4 @@ monitor_baud = 115200
lib_deps =
ServoESP32
DallasTemperature
FastLED
Adafruit NeoPixel

View File

@ -22,7 +22,6 @@ it features:
### Software:
implement ws2812
add graphics to quick selection
implement display on reciever
rpm direction and calibration

View File

@ -1,23 +1,53 @@
#include "FastLED.h"
#include <Adafruit_NeoPixel.h>
#define NUM_STRIPS 2
#define NUM_LEDS_PER_STRIP 10
CRGB leds[NUM_STRIPS][NUM_LEDS_PER_STRIP];
#define PIN_STRIP1 34
#define NUM_LEDS 40
#define PIN_STRIP 17
bool shouldUpdateLights = false;
Adafruit_NeoPixel pixels = Adafruit_NeoPixel(NUM_LEDS, PIN_STRIP, NEO_GRB + NEO_KHZ800);
void lightOff() {
for(int i = 0; i < NUM_LEDS; i++) {
pixels.setPixelColor(i, pixels.Color(0,0,0));
}
portDISABLE_INTERRUPTS();
pixels.show();
portENABLE_INTERRUPTS();
}
void lightWhite() {
for(int i = 0; i < NUM_LEDS; i++) {
pixels.setPixelColor(i, pixels.Color(180,180,180));
}
portDISABLE_INTERRUPTS();
pixels.show();
portENABLE_INTERRUPTS();
}
void lightBackFront() {
// Implement me :-)
for(int i = 0; i < NUM_LEDS; i++) {
pixels.setPixelColor(i, pixels.Color(180,180,180));
}
portDISABLE_INTERRUPTS();
pixels.show();
portENABLE_INTERRUPTS();
}
void updateLights() {
if(lightActive) {
lightWhite();
}else {
lightOff();
}
shouldUpdateLights = false;
}
void setupLights() {
FastLED.addLeds<NEOPIXEL, PIN_STRIP1>(leds[0], NUM_LEDS_PER_STRIP);
}
void loopLights() {
// This outer loop will go over each strip, one at a time
for(int x = 0; x < NUM_STRIPS; x++) {
// This inner loop will go over each led in the current strip, one at a time
for(int i = 0; i < NUM_LEDS_PER_STRIP; i++) {
leds[x][i] = CRGB::Red;
FastLED.show();
leds[x][i] = CRGB::Black;
delay(100);
}
}
portDISABLE_INTERRUPTS();
pixels.begin();
portENABLE_INTERRUPTS();
delay(1);
lightOff();
}

View File

@ -66,7 +66,11 @@ int fanMode = FANS_AUTO;
void setBoardOptions(uint8_t options) {
Serial.print("opt: ");
Serial.println(options, BIN);
lightActive = options & 1;
if(lightActive != options & 1) {
lightActive = options & 1;
shouldUpdateLights = true;
}
fanMode = (options >> 2) & 3;
}
@ -276,6 +280,9 @@ void setup() {
sensors.begin();
setupLights();
lightOff();
xTaskCreatePinnedToCore(
measureRpm,
"rpm task",
@ -336,4 +343,5 @@ void loop() {
checkTemperature();
checkVoltage();
if(shouldUpdateLights) updateLights();
}

View File

@ -6,15 +6,21 @@
#define halYellowRight 18
#define halGreenRight 5
#define FORWARD 0
#define BACKWARD 1
#define wheelCircumference 26.062
#define pulsesPerRotation 22
#include "driver/pcnt.h"
TaskHandle_t rpmTaskHandle;
int rpmRight = 0;
int rpmLeft = 0;
int lastState[2] = {1, 1};
long lastTime[2] = {0, 0};
int counter[2] = {0, 0};
int16_t counter[2] = {0, 0};
int direction[2] = {0, 0};
long rpmTimer = 0;
@ -39,6 +45,10 @@ int relativeLookup[6][6] {
{ 1, 2,-3,-2,-1, 0} // 6
};
#define PCNT_UNIT_LEFT PCNT_UNIT_0
#define PCNT_UNIT_RIGHT PCNT_UNIT_1
int getState(bool isLeft) {
if(isLeft) {
return motorPosition[digitalRead(halBlueLeft)][digitalRead(halYellowLeft)][digitalRead(halGreenLeft)];
@ -55,18 +65,67 @@ void initRPMPins() {
pinMode(halBlueRight, INPUT_PULLUP);
pinMode(halYellowRight, INPUT_PULLUP);
pinMode(halGreenRight, INPUT_PULLUP);
// init counter
pcnt_config_t pcnt_config_left = {
.pulse_gpio_num = halBlueLeft,
.ctrl_gpio_num = PCNT_PIN_NOT_USED,
.lctrl_mode = PCNT_MODE_KEEP,
.hctrl_mode = PCNT_MODE_KEEP,
.pos_mode = PCNT_COUNT_INC, // count both rising and falling edges
.neg_mode = PCNT_COUNT_INC,
.counter_h_lim = 32767,
.counter_l_lim = -1,
.unit = PCNT_UNIT_LEFT,
.channel = PCNT_CHANNEL_0
};
pcnt_config_t pcnt_config_right = {
.pulse_gpio_num = halBlueRight,
.ctrl_gpio_num = PCNT_PIN_NOT_USED,
.lctrl_mode = PCNT_MODE_KEEP,
.hctrl_mode = PCNT_MODE_KEEP,
.pos_mode = PCNT_COUNT_INC, // count both rising and falling edges
.neg_mode = PCNT_COUNT_INC,
.counter_h_lim = 32767,
.counter_l_lim = -1,
.unit = PCNT_UNIT_RIGHT,
.channel = PCNT_CHANNEL_0
};
pcnt_unit_config(&pcnt_config_left);
pcnt_unit_config(&pcnt_config_right);
pcnt_counter_pause(PCNT_UNIT_LEFT);
pcnt_counter_pause(PCNT_UNIT_RIGHT);
pcnt_counter_clear(PCNT_UNIT_LEFT);
pcnt_counter_clear(PCNT_UNIT_RIGHT);
pcnt_counter_resume(PCNT_UNIT_LEFT);
pcnt_counter_resume(PCNT_UNIT_RIGHT);
}
void measureRpm(void * parameter) {
while(true) {
if(millis()-rpmTimer>250) {
rpmRight = constrain(counter[0], 0, 350)*4;
rpmLeft = constrain(counter[1], 0, 350)*4;
kmh = (wheelCircumference/100) * (rpmRight+rpmLeft)/2 * 60/1000;
// read counters
pcnt_get_counter_value(PCNT_UNIT_LEFT, &counter[1]);
pcnt_get_counter_value(PCNT_UNIT_RIGHT, &counter[0]);
pcnt_counter_clear(PCNT_UNIT_LEFT);
pcnt_counter_clear(PCNT_UNIT_RIGHT);
rpmRight = (counter[0]/pulsesPerRotation)*4;
rpmLeft = (counter[1]/pulsesPerRotation)*4;
kmh = (wheelCircumference/100) * (rpmRight+rpmLeft)/2 * 3600/1000;
Serial.print(kmh); Serial.print(" "); Serial.println(direction[0]);
sendSpeed = abs(floor(kmh));
sendSpeedDecimals = (kmh - sendSpeed) * 100;
Serial.print("remote "); Serial.println(kmh);
counter[true] = 0;
counter[false] = 0;
rpmTimer = millis();
@ -74,16 +133,25 @@ void measureRpm(void * parameter) {
int state = getState(0);
if(lastState[0] != state) {
counter[0] = counter[0] + relativeLookup[lastState[0]-1][state-1];
if(relativeLookup[lastState[0]-1][state-1] > 0) {
direction[0] = FORWARD;
} else {
direction[0] = BACKWARD;
}
lastState[0] = state;
}
state = getState(1);
if(lastState[1] != state) {
counter[1] = counter[1] + relativeLookup[lastState[1]-1][state-1];
if(relativeLookup[lastState[1]-1][state-1] > 0) {
direction[1] = FORWARD;
} else {
direction[1] = BACKWARD;
}
lastState[1] = state;
}
vTaskDelay(pdMS_TO_TICKS(1));
vTaskDelay(1 / portTICK_PERIOD_MS);
}
}