CAN ist working
This commit is contained in:
parent
1ace7a8d6a
commit
d92818d4e5
43
Software/ChainLube/src/can.cpp
Normal file
43
Software/ChainLube/src/can.cpp
Normal file
@ -0,0 +1,43 @@
|
|||||||
|
#include "can.h"
|
||||||
|
|
||||||
|
MCP_CAN CAN0(GPIO_CS_CAN);
|
||||||
|
|
||||||
|
void Init_CAN()
|
||||||
|
{
|
||||||
|
|
||||||
|
if (CAN0.begin(MCP_STDEXT, CAN_500KBPS, MCP_16MHZ) == CAN_OK)
|
||||||
|
Serial.println("MCP2515 Initialized Successfully!");
|
||||||
|
else
|
||||||
|
Serial.println("Error Initializing MCP2515...");
|
||||||
|
|
||||||
|
CAN0.init_Mask(0, 0, 0x07FF0000); // Init first mask...
|
||||||
|
CAN0.init_Mask(1, 0, 0x07FF0000); // Init second mask...
|
||||||
|
CAN0.init_Filt(0, 0, 0x012D0000); // Init first filter...
|
||||||
|
|
||||||
|
CAN0.setMode(MCP_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t Process_CAN_WheelSpeed()
|
||||||
|
{
|
||||||
|
#define FACTOR_RWP_KMH_890ADV 18 // Divider to convert Raw Data to km/h
|
||||||
|
|
||||||
|
can_frame canMsg;
|
||||||
|
static uint32_t lastRecTimestamp;
|
||||||
|
uint16_t RearWheelSpeed_raw;
|
||||||
|
|
||||||
|
if (CAN0.readMsgBuf(&canMsg.can_id, &canMsg.can_dlc, canMsg.data) == CAN_OK)
|
||||||
|
{
|
||||||
|
RearWheelSpeed_raw = (uint16_t)canMsg.data[5] << 8 | canMsg.data[6];
|
||||||
|
// raw / FACTOR_RWP_KMH_890ADV -> km/h * 100000 -> cm/h / 3600 -> cm/s
|
||||||
|
// raw * 500 -> cm/s
|
||||||
|
uint32_t RWP_millimeter_per_second = (((uint32_t)RearWheelSpeed_raw * 1000000) / FACTOR_RWP_KMH_890ADV ) / 3600;
|
||||||
|
|
||||||
|
uint32_t timesincelast = millis() - lastRecTimestamp;
|
||||||
|
lastRecTimestamp = millis();
|
||||||
|
|
||||||
|
uint32_t milimeters_to_add = (RWP_millimeter_per_second * timesincelast) / 1000;
|
||||||
|
|
||||||
|
return milimeters_to_add;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
18
Software/ChainLube/src/can.h
Normal file
18
Software/ChainLube/src/can.h
Normal file
@ -0,0 +1,18 @@
|
|||||||
|
#ifndef _CAN_H_
|
||||||
|
#define _CAN_H_
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <mcp_can.h>
|
||||||
|
#include <SPI.h>
|
||||||
|
#include "common.h"
|
||||||
|
|
||||||
|
struct can_frame {
|
||||||
|
uint32_t can_id;
|
||||||
|
uint8_t can_dlc;
|
||||||
|
uint8_t data[8] __attribute__((aligned(8)));
|
||||||
|
};
|
||||||
|
|
||||||
|
void Init_CAN();
|
||||||
|
uint32_t Process_CAN_WheelSpeed();
|
||||||
|
|
||||||
|
#endif
|
@ -22,6 +22,15 @@ typedef enum SpeedSource_e
|
|||||||
#endif
|
#endif
|
||||||
} SpeedSource_t;
|
} SpeedSource_t;
|
||||||
|
|
||||||
|
const char SpeedSourceString[][8] = {
|
||||||
|
"Timer",
|
||||||
|
"Impuls",
|
||||||
|
"GPS",
|
||||||
|
#if PCB_REVISION >= 13
|
||||||
|
"CAN-Bus"
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
typedef enum GPSBaudRate_e
|
typedef enum GPSBaudRate_e
|
||||||
{
|
{
|
||||||
BAUD_9600,
|
BAUD_9600,
|
||||||
@ -34,7 +43,7 @@ const char GPSBaudRateString[][7] = {
|
|||||||
|
|
||||||
const size_t GPSBaudRateString_Elements = sizeof(GPSBaudRateString) / sizeof(GPSBaudRateString[0]);
|
const size_t GPSBaudRateString_Elements = sizeof(GPSBaudRateString) / sizeof(GPSBaudRateString[0]);
|
||||||
|
|
||||||
#if PCB_REVISION == 13
|
#if PCB_REVISION >= 13
|
||||||
|
|
||||||
typedef enum CANSource_e
|
typedef enum CANSource_e
|
||||||
{
|
{
|
||||||
@ -47,15 +56,6 @@ const char CANSourceString[][28] = {
|
|||||||
const char CANSourceString_Elements = sizeof(CANSourceString) / sizeof(CANSourceString[0]);
|
const char CANSourceString_Elements = sizeof(CANSourceString) / sizeof(CANSourceString[0]);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const char SpeedSourceString[][8] = {
|
|
||||||
"Timer",
|
|
||||||
"Impuls",
|
|
||||||
"GPS",
|
|
||||||
#if PCB_REVISION == 13
|
|
||||||
"CAN-Bus"
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
|
|
||||||
const size_t SpeedSourceString_Elements = sizeof(SpeedSourceString) / sizeof(SpeedSourceString[0]);
|
const size_t SpeedSourceString_Elements = sizeof(SpeedSourceString) / sizeof(SpeedSourceString[0]);
|
||||||
|
|
||||||
typedef struct
|
typedef struct
|
||||||
@ -68,10 +68,10 @@ typedef struct
|
|||||||
|
|
||||||
typedef struct
|
typedef struct
|
||||||
{
|
{
|
||||||
uint32_t DistancePerLube_Default = 0;
|
uint32_t DistancePerLube_Default = 8000;
|
||||||
uint32_t DistancePerLube_Rain = 0;
|
uint32_t DistancePerLube_Rain = 4000;
|
||||||
uint32_t tankCapacity_ml = 320;
|
uint32_t tankCapacity_ml = 320;
|
||||||
uint32_t amountPerDose_µl = 0;
|
uint32_t amountPerDose_µl = 72;
|
||||||
uint8_t TankRemindAtPercentage = 30;
|
uint8_t TankRemindAtPercentage = 30;
|
||||||
uint8_t PulsePerRevolution = 1;
|
uint8_t PulsePerRevolution = 1;
|
||||||
uint32_t TireWidth_mm = 150;
|
uint32_t TireWidth_mm = 150;
|
||||||
|
@ -7,10 +7,6 @@
|
|||||||
#include <RemoteDebug.h>
|
#include <RemoteDebug.h>
|
||||||
#include <FastLED.h>
|
#include <FastLED.h>
|
||||||
#include <Ticker.h>
|
#include <Ticker.h>
|
||||||
#if PCB_REVISION >= 13
|
|
||||||
#include <mcp_can.h>
|
|
||||||
#include <SPI.h>
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "common.h"
|
#include "common.h"
|
||||||
#include "rmtdbghelp.h"
|
#include "rmtdbghelp.h"
|
||||||
@ -18,6 +14,7 @@
|
|||||||
#include "webui.h"
|
#include "webui.h"
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
#include "globals.h"
|
#include "globals.h"
|
||||||
|
#include "can.h"
|
||||||
|
|
||||||
#ifdef WIFI_CLIENT
|
#ifdef WIFI_CLIENT
|
||||||
#include <ESP8266WiFiMulti.h>
|
#include <ESP8266WiFiMulti.h>
|
||||||
@ -29,10 +26,6 @@ const uint32_t connectTimeoutMs = 5000;
|
|||||||
ESP8266WiFiMulti wifiMulti;
|
ESP8266WiFiMulti wifiMulti;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PCB_REVISION >= 13
|
|
||||||
MCP_CAN CAN0(GPIO_CS_CAN);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef DEBUG
|
#ifdef DEBUG
|
||||||
const bool debug_flag = true;
|
const bool debug_flag = true;
|
||||||
#else
|
#else
|
||||||
@ -102,30 +95,26 @@ void setup()
|
|||||||
GetConfig_EEPROM();
|
GetConfig_EEPROM();
|
||||||
GetPersistence_EEPROM();
|
GetPersistence_EEPROM();
|
||||||
|
|
||||||
#if PCB_REVISION >= 13
|
|
||||||
Init_CAN();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
u8x8.begin();
|
u8x8.begin();
|
||||||
u8x8.setFont(u8x8_font_chroma48medium8_r);
|
u8x8.setFont(u8x8_font_chroma48medium8_r);
|
||||||
|
|
||||||
FastLED.addLeds<WS2811, GPIO_LED, GRB>(leds, 1); // GRB ordering is assumed
|
FastLED.addLeds<WS2811, GPIO_LED, GRB>(leds, 1); // GRB ordering is assumed
|
||||||
|
|
||||||
#if PCB_REVISION <= 13
|
if (LubeConfig.SpeedSource == SOURCE_IMPULSE)
|
||||||
|
{
|
||||||
pinMode(GPIO_TRIGGER, INPUT_PULLUP);
|
pinMode(GPIO_TRIGGER, INPUT_PULLUP);
|
||||||
#endif
|
attachInterrupt(digitalPinToInterrupt(GPIO_TRIGGER), trigger_ISR, FALLING);
|
||||||
|
}
|
||||||
pinMode(GPIO_BUTTON, INPUT_PULLUP);
|
pinMode(GPIO_BUTTON, INPUT_PULLUP);
|
||||||
pinMode(GPIO_PUMP, OUTPUT);
|
pinMode(GPIO_PUMP, OUTPUT);
|
||||||
|
|
||||||
attachInterrupt(digitalPinToInterrupt(GPIO_TRIGGER), trigger_ISR, FALLING);
|
|
||||||
|
|
||||||
if (MDNS.begin(DeviceName))
|
if (MDNS.begin(DeviceName))
|
||||||
MDNS.addService("telnet", "tcp", 23);
|
MDNS.addService("telnet", "tcp", 23);
|
||||||
|
|
||||||
Debug.begin(DeviceName); // Initialize the WiFi server
|
Debug.begin(DeviceName);
|
||||||
Debug.setResetCmdEnabled(true); // Enable the reset command
|
Debug.setResetCmdEnabled(true);
|
||||||
Debug.showProfiler(true); // Profiler (Good to measure times, to optimize codes)
|
Debug.showProfiler(false);
|
||||||
Debug.showColors(true); // Colors
|
Debug.showColors(true);
|
||||||
Debug.setPassword(QUOTE(ADMIN_PASSWORD));
|
Debug.setPassword(QUOTE(ADMIN_PASSWORD));
|
||||||
Debug.setSerialEnabled(true);
|
Debug.setSerialEnabled(true);
|
||||||
Debug.showDebugLevel(true);
|
Debug.showDebugLevel(true);
|
||||||
@ -170,6 +159,10 @@ void setup()
|
|||||||
u8x8.drawString(1, 1, "ChainLube Mk1");
|
u8x8.drawString(1, 1, "ChainLube Mk1");
|
||||||
u8x8.refreshDisplay();
|
u8x8.refreshDisplay();
|
||||||
|
|
||||||
|
#if PCB_REVISION >= 13
|
||||||
|
Init_CAN();
|
||||||
|
#endif
|
||||||
|
|
||||||
initWebUI();
|
initWebUI();
|
||||||
UpdateWebUITicker.start();
|
UpdateWebUITicker.start();
|
||||||
Serial.println("Setup Done");
|
Serial.println("Setup Done");
|
||||||
@ -184,13 +177,15 @@ void loop()
|
|||||||
case SOURCE_IMPULSE:
|
case SOURCE_IMPULSE:
|
||||||
wheelDistance = Process_Impulse_WheelSpeed();
|
wheelDistance = Process_Impulse_WheelSpeed();
|
||||||
break;
|
break;
|
||||||
|
case SOURCE_CAN:
|
||||||
|
wheelDistance = Process_CAN_WheelSpeed();
|
||||||
|
break;
|
||||||
case SOURCE_TIME:
|
case SOURCE_TIME:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
RunLubeApp(wheelDistance);
|
RunLubeApp(wheelDistance);
|
||||||
UpdateWebUITicker.update();
|
UpdateWebUITicker.update();
|
||||||
|
|
||||||
Display_Process();
|
Display_Process();
|
||||||
Button_Process();
|
Button_Process();
|
||||||
LED_Process();
|
LED_Process();
|
||||||
@ -524,7 +519,7 @@ void LED_Process(uint8_t override, CRGB SetColor)
|
|||||||
|
|
||||||
void Display_Process()
|
void Display_Process()
|
||||||
{
|
{
|
||||||
u8x8.setCursor(0, 3);
|
u8x8.setCursor(0, 2);
|
||||||
uint32_t DistRemain = globals.systemStatus == sysStat_Normal ? LubeConfig.DistancePerLube_Default : LubeConfig.DistancePerLube_Rain;
|
uint32_t DistRemain = globals.systemStatus == sysStat_Normal ? LubeConfig.DistancePerLube_Default : LubeConfig.DistancePerLube_Rain;
|
||||||
DistRemain -= TravelDistance_highRes / 1000;
|
DistRemain -= TravelDistance_highRes / 1000;
|
||||||
u8x8.printf("Mode: %10s\n", globals.systemStatustxt);
|
u8x8.printf("Mode: %10s\n", globals.systemStatustxt);
|
||||||
@ -533,6 +528,7 @@ void Display_Process()
|
|||||||
u8x8.printf("WiFi: %10s\n", (WiFi.getMode() == WIFI_AP ? "AP" : WiFi.getMode() == WIFI_OFF ? "OFF"
|
u8x8.printf("WiFi: %10s\n", (WiFi.getMode() == WIFI_AP ? "AP" : WiFi.getMode() == WIFI_OFF ? "OFF"
|
||||||
: WiFi.getMode() == WIFI_STA ? "CLIENT"
|
: WiFi.getMode() == WIFI_STA ? "CLIENT"
|
||||||
: "UNKNOWN"));
|
: "UNKNOWN"));
|
||||||
|
u8x8.printf("Source: %8s\n", SpeedSourceString[LubeConfig.SpeedSource]);
|
||||||
u8x8.refreshDisplay();
|
u8x8.refreshDisplay();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
x
Reference in New Issue
Block a user