refactor v1

This commit is contained in:
2025-01-10 13:53:27 +01:00
parent 09c7107a07
commit 285ec4b38d
52 changed files with 79 additions and 21 deletions

View File

@@ -0,0 +1,54 @@
# Source and include
BUILD_DIR=build
SRCS=$(wildcard src/*.c)
OBJS=$(SRCS:%.c=build/%.o)
INC=-I ./inc
# MCU configuration
# Set MCU type, clock frequency and programmer
MCU=atmega8
CLOCK_FREQ=16000000
PROG_STR=usbasp
# Compiler flags
CFLAGS=-std=c11 -Wall -Wextra -Werror -mmcu=$(MCU) -DF_CPU=$(CLOCK_FREQ)
OPT_FLAGS=-O3 -g -DDEBUG
# Compiler and utility tools
OBJCOPY=avr-objcopy
CC=avr-gcc
# Project configuration
PROJ_NAME=sflap_controller_fw
PROJ_BLD=$(BUILD_DIR)/$(PROJ_NAME)
# Rules
all: $(PROJ_BLD).elf
$(PROJ_BLD).elf: $(OBJS)
$(CC) -o $@ $^ $(INC) $(CFLAGS) $(OPT_FLAGS) $(MCU_FLAGS)
$(OBJCOPY) -j .text -j .data -O ihex $@ $(PROJ_BLD).hex
$(OBJCOPY) -j .text -j .data -O binary $@ $(PROJ_BLD).bin
build/%.o: %.c
mkdir -p build/src
$(CC) -c -o $@ $(INC) $(CFLAGS) $(OPT_FLAGS) $(MCU_FLAGS) $<
release: OPT_FLAGS=-O2 -DNDEBUG
release: $(PROJ_BLD).elf
fuse:
avrdude -c $(PROG_STR) -p $(MCU) -U lfuse:w:0xDF:m -U hfuse:w:0xCA:m -B 125kHz
flash:
avrdude -c $(PROG_STR) -p $(MCU) -U flash:w:$(PROJ_BLD).hex:i
flash-debug:
avrdude -c $(PROG_STR) -p $(MCU) -U flash:w:$(PROJ_BLD).elf:e
clean:
rm -rf build
.PHONY = clean, release, flash, flash-debug

View File

@@ -0,0 +1,162 @@
#include "mctrl.h"
#include "rcount.h"
#include "rs485.h"
#include <avr/io.h>
#include <avr/wdt.h>
#include <stdlib.h>
#include <util/delay.h>
/*
* PD0 -> BUS_RX
* PD1 -> BUS_TX
* PD2 -> BUS_DIR (0=RECV/1=SEND)
*
* PD3 -> SENSOR_IN
*
* PC0-3 -> MOTOR CTRL
*/
uint16_t address = 0x0000;
int16_t calib_offset = 0x0000;
void eeprom_write_c(uint16_t address, uint8_t data) {
// disable interrupt
cli();
while (EECR & (1 << EEWE))
; // wait until previous write is done
EEAR = address;
EEDR = data;
EECR |= (1 << EEMWE); // enable Master Write Enable
EECR |= (1 << EEWE); // write one
sei();
}
uint8_t eeprom_read_c(uint16_t address) {
while (EECR & (1 << EEWE))
; // wait until previous write is done
EEAR = address;
EECR |= (1 << EERE); // read one
return EEDR;
}
#define CONF_CONST_OKAY (uint8_t)0xAA
#define CONF_ADDR_OKAY 0x0004
#define CONF_ADDR_ADDR 0x0000
#define CONF_ADDR_OFFSET 0x0002
void initialSetup() {
wdt_disable();
if (eeprom_read_c(CONF_ADDR_OKAY) == CONF_CONST_OKAY) {
uint8_t addrL = eeprom_read_c(CONF_ADDR_ADDR);
uint8_t addrH = eeprom_read_c(CONF_ADDR_ADDR + 1);
address = addrL | (addrH << 8);
uint8_t offsetL = eeprom_read_c(CONF_ADDR_OFFSET);
uint8_t offsetH = eeprom_read_c(CONF_ADDR_OFFSET + 1);
calib_offset = offsetL | (offsetH << 8);
} else {
eeprom_write_c(CONF_ADDR_ADDR, (uint8_t)0x00);
eeprom_write_c(CONF_ADDR_ADDR + 1, (uint8_t)0x00);
eeprom_write_c(CONF_ADDR_OFFSET, (uint8_t)0x00);
eeprom_write_c(CONF_ADDR_OFFSET + 1, (uint8_t)0x00);
eeprom_write_c(CONF_ADDR_OKAY, CONF_CONST_OKAY);
}
}
void readCommand() {
char *payload = malloc(64);
uint8_t payload_len = sfbus_recv_frame(address, payload);
if (payload_len > 0) {
// read command byte
uint8_t opcode = *payload;
// parse commands
if (opcode == (uint8_t)0x10) {
// 0x1O = Set Digit
uint8_t targetDigit = *(payload + 1);
mctrl_set(targetDigit, 0);
} else if (opcode == (uint8_t)0x11) {
// 0x11 = Set Digit (full rotation)
uint8_t targetDigit = *(payload + 1);
mctrl_set(targetDigit, 1);
} else if (opcode == (uint8_t)0xF0) {
// 0xFO = READ EEPROM
uint8_t bytes = 5;
char *msg = malloc(bytes + 1);
*msg = 0xAA;
for (uint16_t i = 1; i < (uint16_t)bytes + 1; i++) {
*(msg + i) = eeprom_read_c(i - 1);
}
_delay_ms(2);
sfbus_send_frame(0xFFFF, msg, bytes + 1);
free(msg);
} else if (opcode == (uint8_t)0xF1) {
// 0xF1 = WRITE EEPROM
eeprom_write_c(CONF_ADDR_OKAY, (char)0xFF);
for (uint16_t i = 0; i < 4; i++) {
eeprom_write_c(i, *(payload + 1 + i));
}
eeprom_write_c(CONF_ADDR_OKAY, CONF_CONST_OKAY);
// respond with readout
uint8_t bytes = 5;
char *msg = malloc(bytes + 1);
*msg = 0xAA;
for (uint16_t i = 1; i < (uint16_t)bytes + 1; i++) {
*(msg + i) = eeprom_read_c(i - 1);
}
_delay_ms(2);
sfbus_send_frame(0xFFFF, msg, bytes + 1);
free(msg);
// now use new addr
uint8_t addrL = eeprom_read_c(CONF_ADDR_ADDR);
uint8_t addrH = eeprom_read_c(CONF_ADDR_ADDR + 1);
address = addrL | (addrH << 8);
} else if (opcode == (uint8_t)0xF8) {
// 0xF8 = Get Status
char *msg = malloc(7);
*msg = getSts();
uint16_t voltage = getVoltage();
*(msg + 2) = (voltage >> 0) & 0xFF;
*(msg + 1) = (voltage >> 8) & 0xFF;
uint32_t counter = rc_getCounter();
*(msg + 6) = (counter >> 0) & 0xFF;
*(msg + 5) = (counter >> 8) & 0xFF;
*(msg + 4) = (counter >> 16) & 0xFF;
*(msg + 3) = (counter >> 24) & 0xFF;
_delay_ms(2);
sfbus_send_frame(0xFFFF, msg, 7);
free(msg);
} else if (opcode == (uint8_t)0xFE) {
// 0xFE = PING
char msg = 0xFF;
_delay_ms(2);
sfbus_send_frame(0xFFFF, &msg, 1);
} else if ((opcode & (uint8_t)0xFE) == (uint8_t)0x20) {
// 0x20 = poweroff; 0x21 is poweron
uint8_t state = opcode & (uint8_t)0x01;
mctrl_power(state);
} else if (opcode == (uint8_t)0x30) {
// 0x30 = reset
do {
wdt_enable(WDTO_15MS);
for (;;) {
}
} while (0);
} else {
// invalid opcode
char msg = 0xEE;
_delay_ms(2);
sfbus_send_frame(0xFFFF, &msg, 1);
}
}
free(payload);
}
int main() {
initialSetup();
rs485_init();
mctrl_init();
while (1 == 1) {
readCommand();
}
}

View File

@@ -0,0 +1,242 @@
#include "mctrl.h"
// Motor driver steps definition. Reverse for direction change.
uint8_t motor_steps[4] = {
0b00000001,
0b00000010,
0b00000100,
0b00001000,
};
uint8_t step_index = 0; // cuurent index in motor_steps
uint8_t target_flap = 0; // target flap
uint16_t absolute_pos = 0; // absolute position in steps
uint16_t rel_offset = 1400; // offset of '0' flap relative to home
uint16_t steps_since_home = 0; // steps since last home signal
// homing util variables
uint8_t homing = 0; // current homing step
uint8_t lastSens = 0; // home sonsor signal from last tick
// counter for auto powersaving
uint8_t ticksSinceMove = 0;
// value to goto after the current target_flap is reached. 255 = NONE.
uint8_t afterRotation = 255;
int16_t *delta_err;
// error and status flags
uint8_t sts_flag_errorTooBig = 0; // last home signal too early or too late
uint8_t sts_flag_noHome = 0; // no home signal detected. Wheel stuck
uint8_t sts_flag_fuse = 0; // blown fuse detcted
uint8_t sts_flag_pwrdwn = 0; // device is powered down by controller
uint8_t sts_flag_failsafe = 0; // device is powered down for safety reasons
uint8_t sts_flag_busy = 0; // device is busy
// voltage monitoring variables
uint16_t currentVoltage = 0; // current ADC reading
uint8_t currentFaultReadings = 0; // ticks with faulty readings (too many will
// trip pwrdwn and sts_flag_fuse)
// initialize motor controller
void mctrl_init() {
DDRC = 0x0F; // set all pins as outputs
PORTC = 0x00; // set all to LOW
DDRD &= ~(1 << PD3); // PD3 is input
PORTD |= (1 << PD3); // PD3 pullup
// setup adc
ADMUX = 0x07; // Aref, ADC7
ADCSRA =
(1 << ADEN) | (1 << ADSC) | (1 << ADPS1); // Enable ADC, Start first
// reading No frerunning, 8MHz
while ((ADCSRA & (1 << ADSC)) > 0)
; // wait until first reading is complete,
// to avoid error flag on first tick!
// setup timer for ISR
TCCR1A = 0;
TCCR1B = (1 << WGM12) | (1 << CS11) | (1 << CS10); // CTC und Prescaler 64
OCR1A = 480; // 8.000.000 / 64 / 1000 für 1ms
OCR1A = 580; // 8.000.000 / 64 / 1000 für 1ms
// OCR1A = 450; // 8.000.000 / 64 /
// 1000 für 1ms
TIMSK = 1 << OCIE1A; // Timerinterrupts aktivieren
homing = 1;
delta_err = malloc(ERROR_DATASETS * sizeof(uint16_t));
_delay_ms(1000);
sei();
}
// call when critical fail. Powers down motor and sets flags
void failSafe() {
sts_flag_failsafe = 1;
PORTC = 0x00;
}
// read voltage non blocking (called every tick)
void readVoltage() {
currentVoltage = ADC; // read last measurement
ADMUX = 0x07; // select ADC7
ADCSRA |= (1 << ADSC); // trigger next reading
if (currentVoltage < 128) { // if voltage is too low, fuse is probably broken
currentFaultReadings++;
if (currentFaultReadings > 20) { // too many fault readings trigger failSafe
sts_flag_fuse = 1;
failSafe();
}
}
}
// MAIN service routine. Called by timer 1
ISR(TIMER1_COMPA_vect) {
readVoltage(); // read and check voltage
if (sts_flag_pwrdwn == 1 || sts_flag_failsafe == 1) {
return;
} // if sts_flag_pwrdwn, STOP!
if (steps_since_home >
STEPS_PRE_REV * 1.5) { // check if home is missing for too long
// home missing error. Wheel probably stuck or power fail
sts_flag_noHome = 1;
failSafe();
} else if (homing == 1) { // Homing procedure 1. step: move out of home
if ((PIND & (1 << PD3)) > 0) {
homing = 2;
} else {
mctrl_step();
}
} else if (homing == 2) { // Homing procedure 2. step: find magnet
mctrl_step();
if ((PIND & (1 << PD3)) == 0) {
homing = 3;
steps_since_home = 0;
absolute_pos = rel_offset;
incrementCounter();
}
} else if (homing == 3) { // Homing procedure 3. step: find magnet
if (absolute_pos <= 0) {
homing = 0;
absolute_pos = rel_offset;
}
mctrl_step();
absolute_pos--;
} else { // when no failsafe is triggered and homing is done
// calculate target position
uint16_t target_pos = (target_flap * STEPS_PRE_FLAP) + rel_offset;
if (target_pos >= STEPS_PRE_REV) {
target_pos -= STEPS_PRE_REV;
}
if (absolute_pos != target_pos) {
// if target position is not reached, move motor
ticksSinceMove = 0;
mctrl_step();
absolute_pos++;
if (absolute_pos >= STEPS_PRE_REV) {
absolute_pos -= STEPS_PRE_REV;
}
// detect home position
if ((PIND & (1 << PD3)) == 0) {
if (lastSens == 0) {
// new home transition
int16_t errorDelta =
(absolute_pos > (STEPS_PRE_REV / 2) ? absolute_pos - STEPS_PRE_REV
: absolute_pos);
sts_flag_errorTooBig =
(errorDelta > 30) || (errorDelta < -30) ? 1 : 0;
// storeErr(errorDelta);
absolute_pos = 0;
steps_since_home = 0;
// increment rotations counter
incrementCounter();
}
lastSens = 1;
} else {
lastSens = 0;
}
} else { // if target position is reached
if (afterRotation < 55) { // if after rotation is set, apply it as new target
target_flap = afterRotation;
afterRotation = 255;
} else if (ticksSinceMove < 2) { // if motor has not been moved
sts_flag_busy = 0;
} else if (ticksSinceMove < 50) { // if motor has not been moved
ticksSinceMove++;
} else { // power off after 50 ticks
// PORTC = 0x00; // turn off stepper
}
}
}
rc_tick(); // process counter tick, non-blocking
}
// TODO
void storeErr(int16_t error) {
int16_t *delta_err_tmp = malloc(ERROR_DATASETS * sizeof(uint16_t));
memcpy(delta_err, delta_err_tmp + sizeof(uint16_t),
((ERROR_DATASETS - 2) * sizeof(uint16_t)));
memcpy(&error, delta_err_tmp, sizeof(uint16_t));
free(delta_err);
delta_err = delta_err_tmp;
}
// TODO
void getErr(int16_t *error) {
memcpy(delta_err, error, (ERROR_DATASETS * sizeof(uint16_t)));
}
// return status flag
uint8_t getSts() {
uint8_t status = sts_flag_errorTooBig; // bit 0: delta too big
status |= sts_flag_noHome << 1; // bit 1: no home found
status |= sts_flag_fuse << 2; // bit 2: fuse blown
status |= sts_flag_pwrdwn << 4; // bit 4: device powered down
status |= sts_flag_failsafe << 5; // bit 5: failsafe active
status |= sts_flag_busy << 6; // bit 6: failsafe active
if ((PIND & (1 << PD3)) == 0) {
status |= (1 << 3);
}
return status;
}
// return voltage
uint16_t getVoltage() { return currentVoltage; }
// set target flap
void mctrl_set(uint8_t flap, uint8_t fullRotation) {
sts_flag_busy = 1;
if (fullRotation == 0) {
target_flap = flap;
// if (absolute_pos < STEPS_ADJ) {
// absolute_pos += STEPS_PRE_REV;
// }
// absolute_pos -= STEPS_ADJ;
} else {
target_flap = (target_flap + (STEPS_PRE_FLAP - 1)) % STEPS_PRE_FLAP;
afterRotation = flap;
}
}
// trigger home procedure
void mctrl_home() { homing = 1; }
// trigger home procedure
void mctrl_power(uint8_t state) {
if (state == 0) {
sts_flag_pwrdwn = 1;
PORTC = 0x00;
}else{
sts_flag_pwrdwn = 0;
PORTC = motor_steps[step_index];
}
}
// do stepper step (I/O)
void mctrl_step() {
step_index++;
steps_since_home++;
if (step_index > 3) {
step_index = 0;
}
PORTC = motor_steps[step_index];
}

View File

@@ -0,0 +1,36 @@
#pragma once
#define MP_A PC0
#define MP_B PC1
#define MP_C PC2
#define MP_D PC3
#define STEPS_PRE_REV 2025
#define STEPS_PRE_FLAP 45
#define STEPS_ADJ 0 // added per flap to compensate for motor power down
#define AMOUNTFLAPS 45
#define ERROR_DATASETS 8
#include <stdlib.h>
#include <string.h>
#include <avr/io.h>
#include <avr/interrupt.h>
#include <util/delay.h>
#include "rcount.h"
#ifdef __cplusplus
extern "C" {
#endif // __cplusplus
void mctrl_init();
void mctrl_step();
void mctrl_set(uint8_t flap, uint8_t fullRotation);
void getErr(int16_t* error);
uint8_t getSts();
uint16_t getVoltage();
void mctrl_power(uint8_t state);
#ifdef __cplusplus
}
#endif // __cplusplus

View File

@@ -0,0 +1,45 @@
#include "rcount.h"
uint8_t rc_eeprom_write_c(uint16_t address, uint8_t data) {
// disable interrupt
if (EECR & (1 << EEWE)) { return 1; }
EEAR = address;
EEDR = data;
EECR |= (1 << EEMWE); // enable Master Write Enable
EECR |= (1 << EEWE); // write one
return 0;
}
uint8_t rc_eeprom_read_c(uint16_t address) {
while (EECR & (1 << EEWE))
; // wait until previous write is done
EEAR = address;
EECR |= (1 << EERE); // read one
return EEDR;
}
uint32_t counter = (uint32_t)0xFFFFFFFF;
uint8_t counter_phase = 5;
void rc_tick() {
if (counter == (uint32_t)0xFFFFFFFF) { counter = rc_getCounter(); }
if (counter_phase < 5) {
cli();
if (rc_eeprom_write_c(0x100 + counter_phase, ((counter >> (counter_phase * 8)) & 0xFF)) == 0) {
counter_phase++;
}
sei();
}
}
void incrementCounter() {
counter++;
counter_phase = 0;
}
uint32_t rc_getCounter() {
uint32_t counter = rc_eeprom_read_c(0x100);
counter |= ((uint32_t)rc_eeprom_read_c(0x101) << 8);
counter |= ((uint32_t)rc_eeprom_read_c(0x102) << 16);
counter |= ((uint32_t)rc_eeprom_read_c(0x103) << 24);
return counter;
}

View File

@@ -0,0 +1,13 @@
#include <avr/io.h>
#include <avr/interrupt.h>
#ifdef __cplusplus
extern "C" {
#endif // __cplusplus
void incrementCounter();
uint32_t rc_getCounter();
void rc_tick();
#ifdef __cplusplus
}
#endif // __cplusplus

View File

@@ -0,0 +1,86 @@
#include "rs485.h"
void rs485_init() {
// init I/O
DDRD &= ~(1 << PD0); // BUS_DIR & TX is OUTPUT
DDRD |= (1 << PD2) | (1 << PD1); // BUS_DIR & TX is OUTPUT
PORTD &= 0x07; // clear PD0-PD4
// init UART
UBRRH = (BAUDRATE >> 8);
UBRRL = BAUDRATE; // set baud rate
UCSRB |= (1 << TXEN) | (1 << RXEN); // enable receiver and transmitter
UCSRC |= (1 << URSEL) | (1 << UCSZ0) | (1 << UCSZ1); // 8bit data format
}
void dbg(char data) {
while (!(UCSRA & (1 << UDRE)))
;
UDR = data;
}
void rs485_send_c(char data) {
PORTD |= (1 << PD2); // set transciever to transmitt
while (!(UCSRA & (1 << UDRE)))
; // wait until buffer is empty
UCSRA = (1 << TXC); // clear transmit Complete bit
UDR = data;
while (!(UCSRA & (1 << TXC)))
; // wait until transmitt complete
PORTD &= ~(1 << PD2); // set transciever to transmitt
}
void rs485_send_str(char* data) {
for (unsigned int i = 0; i < sizeof(data); i++) {
rs485_send_c(data[i]);
}
}
char rs485_recv_c() {
while (!(UCSRA & (1 << RXC)))
;
; // wait while data is being received
return UDR;
}
// SFBUS Functions
uint8_t sfbus_recv_frame(uint16_t address, char* payload) {
while (rs485_recv_c() != '+') {} // Wwait for start byte
uint8_t frm_version = rs485_recv_c();
if (frm_version != 0) return 0;
uint8_t frm_length = rs485_recv_c();
uint8_t frm_addrL = rs485_recv_c();
uint8_t frm_addrH = rs485_recv_c();
uint16_t frm_addr = frm_addrL | (frm_addrH << 8);
if (frm_addr != address) return 0;
char* _payload = payload;
for (uint8_t i = 0; i < (frm_length - 3); i++) {
*_payload = rs485_recv_c();
_payload++;
}
if (rs485_recv_c() != '$') return -1;
return frm_length;
}
void sfbus_send_frame(uint16_t address, char* payload, uint8_t length) {
char framelen = length;
rs485_send_c(SFBUS_SOF_BYTE); // send startbyte 3 times
rs485_send_c(0); // send protocol version
rs485_send_c(framelen + 3); // send lentgh of remaining frame
rs485_send_c(address & 0xFF); // target address
rs485_send_c((address >> 8) & 0xFF);
while (framelen > 0) { // send payload
rs485_send_c(*payload);
payload++;
framelen--;
}
rs485_send_c(SFBUS_EOF_BYTE); // send end of frame byte
}

View File

@@ -0,0 +1,27 @@
#pragma once
//#define F_CPU 16000000UL
#define UART_BAUD 19200
#define BAUDRATE ((F_CPU) / (UART_BAUD * 16UL) - 1) // set baud rate value for UBRR
#define SFBUS_SOF_BYTE '+'
#define SFBUS_EOF_BYTE '$'
#include <avr/io.h>
#include <avr/interrupt.h>
#ifdef __cplusplus
extern "C" {
#endif // __cplusplus
void dbg(char data);
void rs485_init(void);
void rs485_send_c(char data);
void rs485_send_str(char* data);
char rs485_recv_c(void);
uint8_t sfbus_recv_frame(uint16_t address, char* payload);
void sfbus_send_frame(uint16_t address, char* payload, uint8_t length);
#ifdef __cplusplus
}
#endif // __cplusplus

View File

@@ -0,0 +1,153 @@
#include <Stepper.h>
#define BAUDRATE 115200
#define STEPPERPIN1 11
#define STEPPERPIN2 10
#define STEPPERPIN3 9
#define STEPPERPIN4 8
#define STEPS 2038 //28BYJ-48 stepper, number of steps
#define HALLPIN 7 //Pin of hall sensor
#define AMOUNTFLAPS 45
#define ROTATIONDIRECTION 1 //-1 for reverse direction
#define OVERHEATINGTIMEOUT 2 //timeout in seconds to avoid overheating of stepper. After starting rotation, the counter will start. Stepper won't move again until timeout is passed
unsigned long lastRotation = 0;
//globals
int displayedLetter = 0; //currently shown letter
int desiredLetter = 0; //letter to be shown
const String letters[] = {" ", "A", "B", "C", "D", "E", "F", "G", "H", "I", "J", "K", "L", "M", "N", "O", "P", "Q", "R", "S", "T", "U", "V", "W", "X", "Y", "Z", "Ä", "Ö", "Ü", "0", "1", "2", "3", "4", "5", "6", "7", "8", "9", ":", ".", "-", "?", "!"};
Stepper stepper(STEPS, STEPPERPIN1, STEPPERPIN3, STEPPERPIN2, STEPPERPIN4); //stepper setup
bool lastInd1 = false; //store last status of phase
bool lastInd2 = false; //store last status of phase
bool lastInd3 = false; //store last status of phase
bool lastInd4 = false; //store last status of phase
float missedSteps = 0; //cummulate steps <1, to compensate via additional step when reaching >1
int currentlyrotating = 0; // 1 = drum is currently rotating, 0 = drum is standing still
int stepperSpeed = 10; //current speed of stepper, value only for first homing
int eeAddress = 0; //EEPROM address for calibration offset
int calOffset; //Offset for calibration in steps, stored in EEPROM, gets read in setup
int receivedNumber = 0;
void setup() {
// put your setup code here, to run once:
Serial.begin(BAUDRATE);
Serial.println("starting unit");
stepperSpeed = 17; //until homing is implemented
}
void loop() {
// put your main code here, to run repeatedly:
int calLetters[10] = {0, 26, 1, 21, 14, 43, 30, 31, 32, 39};
for (int i = 0; i < 10; i++) {
int currentCalLetter = calLetters[i];
rotateToLetter(currentCalLetter);
delay(5000);
}
}
//rotate to letter
void rotateToLetter(int toLetter) {
if (lastRotation == 0 || (millis() - lastRotation > OVERHEATINGTIMEOUT * 1000)) {
lastRotation = millis();
//get letter position
int posLetter = -1;
posLetter = toLetter;
int posCurrentLetter = -1;
posCurrentLetter = displayedLetter;
//int amountLetters = sizeof(letters) / sizeof(String);
#ifdef serial
Serial.print("go to letter: ");
Serial.println(letters[toLetter]);
#endif
//go to letter, but only if available (>-1)
if (posLetter > -1) { //check if letter exists
//check if letter is on higher index, then no full rotaion is needed
if (posLetter >= posCurrentLetter) {
#ifdef serial
Serial.println("direct");
#endif
//go directly to next letter, get steps from current letter to target letter
int diffPosition = posLetter - posCurrentLetter;
startMotor();
stepper.setSpeed(stepperSpeed);
//doing the rotation letterwise
for (int i = 0; i < diffPosition; i++) {
float preciseStep = (float)STEPS / (float)AMOUNTFLAPS;
int roundedStep = (int)preciseStep;
missedSteps = missedSteps + ((float)preciseStep - (float)roundedStep);
if (missedSteps > 1) {
roundedStep = roundedStep + 1;
missedSteps--;
}
stepper.step(ROTATIONDIRECTION * roundedStep);
}
}
else {
//full rotation is needed, good time for a calibration
#ifdef serial
Serial.println("full rotation incl. calibration");
#endif
//calibrate(false); //calibrate revolver and do not stop motor
//startMotor();
stepper.setSpeed(stepperSpeed);
for (int i = 0; i < posLetter; i++) {
float preciseStep = (float)STEPS / (float)AMOUNTFLAPS;
int roundedStep = (int)preciseStep;
missedSteps = missedSteps + (float)preciseStep - (float)roundedStep;
if (missedSteps > 1) {
roundedStep = roundedStep + 1;
missedSteps--;
}
stepper.step(ROTATIONDIRECTION * roundedStep);
}
}
//store new position
displayedLetter = toLetter;
//rotation is done, stop the motor
delay(100); //important to stop rotation before shutting of the motor to avoid rotation after switching off current
stopMotor();
}
else {
#ifdef serial
Serial.println("letter unknown, go to space");
#endif
desiredLetter = 0;
}
}
}
//switching off the motor driver
void stopMotor() {
lastInd1 = digitalRead(STEPPERPIN1);
lastInd2 = digitalRead(STEPPERPIN2);
lastInd3 = digitalRead(STEPPERPIN3);
lastInd4 = digitalRead(STEPPERPIN4);
digitalWrite(STEPPERPIN1, LOW);
digitalWrite(STEPPERPIN2, LOW);
digitalWrite(STEPPERPIN3, LOW);
digitalWrite(STEPPERPIN4, LOW);
#ifdef serial
Serial.println("Motor Stop");
#endif
currentlyrotating = 0; //set active state to not active
delay(100);
}
void startMotor() {
#ifdef serial
Serial.println("Motor Start");
#endif
currentlyrotating = 1; //set active state to active
digitalWrite(STEPPERPIN1, lastInd1);
digitalWrite(STEPPERPIN2, lastInd2);
digitalWrite(STEPPERPIN3, lastInd3);
digitalWrite(STEPPERPIN4, lastInd4);
}

View File

@@ -0,0 +1,35 @@
TARGET_EXEC ?= a.out
BUILD_DIR ?= ./build
SRC_DIRS ?= ./src
SRCS := $(shell find $(SRC_DIRS) -name *.cpp -or -name *.c -or -name *.s)
OBJS := $(SRCS:%=$(BUILD_DIR)/%.o)
DEPS := $(OBJS:.o=.d)
INC_DIRS := $(shell find $(SRC_DIRS) -type d)
INC_FLAGS := $(addprefix -I,$(INC_DIRS))
JSON_C_DIR=/path/to/json_c/install
CFLAGS += -I$(JSON_C_DIR)/include/json-c
# Or to use lines like: #include <json-c/json_object.h>
#CFLAGS += -I$(JSON_C_DIR)/include
LDFLAGS+= -L$(JSON_C_DIR)/lib -ljson-c
CPPFLAGS ?= $(INC_FLAGS) -MMD -MP
$(BUILD_DIR)/$(TARGET_EXEC): $(OBJS)
$(CC) $(OBJS) -o $@ $(LDFLAGS)
# c source
$(BUILD_DIR)/%.c.o: %.c
$(MKDIR_P) $(dir $@)
$(CC) $(CPPFLAGS) $(CFLAGS) -c $< -o $@
.PHONY: clean
clean:
$(RM) -r $(BUILD_DIR)
-include $(DEPS)
MKDIR_P ?= mkdir -p

View File

@@ -0,0 +1,181 @@
#include "devicemgr.h"
#include <json-c/json_object.h>
#include <string.h>
/*
* This file provides an abstraction layer to access many devices
* simultaneously. by Dennis Gunia - 2025 - wwwm.dennisgunia.de
*/
enum SFDEVICE_STATE { NEW, OFFLINE, ONLINE, FAILED };
enum SFDEVICE_POWER { DISABLED, ENABLED, UNKNOWN };
struct SFDEVICE {
int pos_x;
int pos_y;
u_int16_t address;
int rs485_descriptor;
double reg_voltage;
u_int32_t reg_counter;
u_int8_t reg_status;
u_int8_t current_flap;
enum SFDEVICE_STATE deviceState;
enum SFDEVICE_POWER powerState;
};
#define SFDEVICE_MAXDEV 128
#define SFDEVICE_MAX_X 20
#define SFDEVICE_MAX_Y 4
// next free slot to register device
int nextFreeSlot = -1;
int deviceMap[SFDEVICE_MAX_X][SFDEVICE_MAX_Y];
struct SFDEVICE devices[SFDEVICE_MAXDEV];
const char* symbols[] = {" ", "A", "B", "C", "D", "E", "F", "G", "H", "I", "J", "K", "L", "M", "N", "O", "P", "Q", "R", "S", "T", "U", "V", "W", "X", "Y", "Z", "Ä", "Ö", "Ü", "0", "1", "2", "3", "4", "5", "6", "7", "8", "9", ":", ".", "-", "?", "!"};
void devicemgr_init() {
// reserve memory buffer
for (int y = 0; y<SFDEVICE_MAX_Y; y++){
for (int x = 0; x<SFDEVICE_MAX_X; x++){
deviceMap[x][y] = -1; //all empty slots are -1
}
}
}
int devicemgr_readStatus(int device_id) {
double _voltage = 0;
u_int32_t _counter = 0;
u_int8_t _status =
sfbus_read_status(devices[device_id].rs485_descriptor,
devices[device_id].address, &_voltage, &_counter);
if (_status == 0xFF) {
devices[device_id].powerState = UNKNOWN;
devices[device_id].deviceState = OFFLINE;
return -1;
} else {
devices[device_id].reg_voltage = _voltage;
devices[device_id].reg_counter = _counter;
devices[device_id].reg_status = _status;
devices[device_id].powerState = ~((devices[device_id].reg_status >> 4)) & 0x01;
devices[device_id].deviceState = ONLINE;
if ((((devices[device_id].reg_status) >> 5) & 0x01) > 0){
devices[device_id].deviceState = FAILED;
}
return 0;
}
}
json_object * devicemgr_printMap(){
json_object *rows_array = json_object_new_array();
for (int y = 0; y<SFDEVICE_MAX_Y; y++){
json_object *columns_array = json_object_new_array();
for (int x = 0; x<SFDEVICE_MAX_X; x++){
json_object_array_add(columns_array, json_object_new_int(deviceMap[x][y]));
}
json_object_array_add(rows_array,columns_array);
}
return rows_array;
}
json_object * devicemgr_printDetails(int device_id){
// generate json object with status
json_object *root = json_object_new_object();
json_object_object_add(root, "id", json_object_new_int(device_id));
json_object_object_add(root, "address", json_object_new_int(devices[device_id].address));
json_object_object_add(root, "flapID", json_object_new_int(devices[device_id].current_flap));
json_object_object_add(root, "flapChar", json_object_new_string(symbols[devices[device_id].current_flap]));
json_object *position = json_object_new_object();
json_object_object_add(position, "x", json_object_new_int(devices[device_id].pos_x));
json_object_object_add(position, "y", json_object_new_int(devices[device_id].pos_y));
json_object_object_add(root, "position", position);
json_object *status = json_object_new_object();
json_object_object_add(status, "voltage", json_object_new_double(devices[device_id].reg_voltage));
json_object_object_add(status, "rotations", json_object_new_int(devices[device_id].reg_counter));
json_object_object_add(status, "power", json_object_new_boolean(devices[device_id].powerState));
json_object_object_add(status, "raw", json_object_new_uint64(devices[device_id].reg_status));
switch(devices[device_id].deviceState){
case ONLINE:
json_object_object_add(status, "device", json_object_new_string("ONLINE"));
break;
case OFFLINE:
json_object_object_add(status, "device", json_object_new_string("OFFLINE"));
break;
case FAILED:
json_object_object_add(status, "device", json_object_new_string("FAILED"));
break;
case NEW:
json_object_object_add(status, "device", json_object_new_string("NEW"));
break;
}
json_object *status_flags = json_object_new_object();
json_object_object_add(status_flags, "errorTooBig", json_object_new_boolean(((devices[device_id].reg_status) >> 0) & 0x01));
json_object_object_add(status_flags, "noHome", json_object_new_boolean(((devices[device_id].reg_status) >> 1) & 0x01));
json_object_object_add(status_flags, "fuseBlown", json_object_new_boolean(((devices[device_id].reg_status) >> 2) & 0x01));
json_object_object_add(status_flags, "homeSense", json_object_new_boolean(((devices[device_id].reg_status) >> 3) & 0x01));
json_object_object_add(status_flags, "powerDown", json_object_new_boolean(((devices[device_id].reg_status) >> 4) & 0x01));
json_object_object_add(status_flags, "failSafe", json_object_new_boolean(((devices[device_id].reg_status) >> 5) & 0x01));
json_object_object_add(status_flags, "busy", json_object_new_boolean(((devices[device_id].reg_status) >> 6) & 0x01));
json_object_object_add(status, "flags", status_flags);
json_object_object_add(root, "status", status);
return root;
}
json_object * devicemgr_printDetailsAll(){
json_object *root = json_object_new_object();
json_object_object_add(root, "devices_all", json_object_new_int(nextFreeSlot + 1));
json_object *devices_arr = json_object_new_array();
int devices_online = 0;
for (int i = 0; i< (nextFreeSlot + 1); i++){
devicemgr_readStatus(i);
if ( devices[i].deviceState == ONLINE ){devices_online++;}
json_object_array_add(devices_arr, devicemgr_printDetails(i));
}
json_object_object_add(root, "map", devicemgr_printMap());
json_object_object_add(root, "devices", devices_arr);
json_object_object_add(root, "devices_online", json_object_new_int(devices_online));
printf("The json representation:\n\n%s\n\n", json_object_to_json_string_ext(root, JSON_C_TO_STRING_PRETTY));
return root;
}
void setSingle(int id, u_int8_t flap){
sfbus_display_full(devices[id].rs485_descriptor , devices[id].address,flap);
devices[nextFreeSlot].current_flap = flap;
}
void printText(char* text,int x,int y){
for (int i = 0; i<strlen(text);i++){
int this_id = deviceMap[x+i][y];
if (this_id >= 0){
setSingle(devices[this_id].address,*(text+i));
}
}
}
int devicemgr_register(int rs485_descriptor, u_int16_t address, int x,int y) {
nextFreeSlot++;
devices[nextFreeSlot].pos_x = x;
devices[nextFreeSlot].pos_y = y;
devices[nextFreeSlot].address = address;
devices[nextFreeSlot].rs485_descriptor = rs485_descriptor;
devices[nextFreeSlot].reg_voltage = 0;
devices[nextFreeSlot].reg_counter = 0;
devices[nextFreeSlot].reg_status = 0;
devices[nextFreeSlot].current_flap = 0;
devices[nextFreeSlot].deviceState = NEW;
devices[nextFreeSlot].powerState = DISABLED;
// try to reach device
devicemgr_readStatus(nextFreeSlot);
if (deviceMap[x][y] >= 0){ // rest old ones
int old_id = deviceMap[x][y];
devices[old_id].pos_x = -1;
devices[old_id].pos_y = -1;
}
deviceMap[x][y] = nextFreeSlot;
return nextFreeSlot;
}

View File

@@ -0,0 +1,19 @@
#include <stdio.h>
#include <stdlib.h>
#include <sys/ioctl.h>
#include <fcntl.h> // Contains file controls like O_RDWR
#include <errno.h> // Error integer and strerror() function
#include <string.h>
#include <termios.h> // Contains POSIX terminal control definitions
#include <unistd.h> // write(), read(), close()
#include <sys/types.h>
#include "sfbus.h"
#include <json-c/json_object.h>
#include <sys/types.h>
#include <json-c/json.h>
int devicemgr_readStatus(int device_id) ;
json_object * devicemgr_printDetails(int device_id);
json_object * devicemgr_printDetailsAll();
int devicemgr_register(int rs485_descriptor, u_int16_t address, int x,int y);
void devicemgr_init();

View File

@@ -0,0 +1,163 @@
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/ioctl.h>
// Linux headers
#include <fcntl.h> // Contains file controls like O_RDWR
#include <sys/types.h>
#include <termios.h> // Contains POSIX terminal control definitions
#include <unistd.h> // write(), read(), close()
#include "rs485.h"
#include "sfbus.h"
#include <unistd.h>
#include "devicemgr.h"
void printUsage(char *argv[]) {
fprintf(stderr, "Usage: %s -p <tty> -c <command> [value]\n", argv[0]);
exit(EXIT_FAILURE);
}
int main(int argc, char *argv[]) {
int opt;
u_int16_t addr_int = 0;
char *port = malloc(256);
char *command = malloc(16);
char *addr = malloc(16);
char *data = malloc(256);
command = "";
addr = "";
data = "";
while ((opt = getopt(argc, argv, "p:c:a:d:")) != -1) {
switch (opt) {
case 'p':
port = optarg;
break;
case 'c':
command = optarg;
break;
case 'a':
addr = optarg;
break;
case 'd':
data = optarg;
break;
default:
printUsage(argv);
}
}
if (access(port, F_OK) != 0) {
fprintf(stderr, "Filedescriptor: %s does not exist or cannot be opened\n",
port);
printUsage(argv);
}
// parse address
if (strlen(addr) == 0) {
fprintf(stderr, "Please specify address\n");
printUsage(argv);
} else {
addr_int = strtol(addr, NULL, 10);
}
// start program
setvbuf(stdout, NULL, _IONBF, 0); // do not buffer stdout!!!!
printf("Open device at %s\n", port);
int fd = rs485_init(port, B19200); // setup rs485
// test
devicemgr_init();
devicemgr_register(fd,0,0,0);
devicemgr_register(fd,1,1,0);
devicemgr_printDetailsAll();
//exit(1);
if (strcmp(command, "ping") == 0) {
sfbus_ping(fd, addr_int);
exit(0);
} else if (strcmp(command, "r_eeprom") == 0) {
char *buffer = malloc(64);
sfbus_read_eeprom(fd, addr_int, buffer);
printf("Read data: 0x");
print_charHex(buffer, 5);
printf("\n");
free(buffer);
exit(0);
} else if (strcmp(command, "w_addr") == 0) {
int n_addr = strtol(data, NULL, 10);
if (n_addr < 1) {
printf("Please specify new address > 0 with -d\n");
exit(-1);
}
// read current eeprom status
char *buffer_w = malloc(64);
char *buffer_r = malloc(64);
if (sfbus_read_eeprom(fd, addr_int, buffer_w) < 0) {
fprintf(stderr, "Error reading eeprom\n");
exit(1);
}
// modify current addr
u_int16_t n_addr_16 = n_addr;
memcpy(buffer_w, &n_addr_16, 2);
if (sfbus_write_eeprom(fd, addr_int, buffer_w, buffer_r) < 0) {
fprintf(stderr, "Error writing eeprom\n");
exit(1);
}
exit(0);
} else if (strcmp(command, "status") == 0) {
double voltage = 0;
u_int32_t counter = 0;
u_int8_t status = sfbus_read_status(fd, addr_int, &voltage, &counter);
printf("=======================\n");
printf("Status register flags :\n");
printf(" 00 -> errorTooBig : %i\n", (status >> 0) & 0x01);
printf(" 01 -> noHome : %i\n", (status >> 1) & 0x01);
printf(" 02 -> fuseBlown : %i\n", (status >> 2) & 0x01);
printf(" 03 -> homeSense : %i\n", (status >> 3) & 0x01);
printf(" 04 -> powerDown : %i\n", (status >> 4) & 0x01);
printf(" 05 -> failSafe : %i\n", (status >> 5) & 0x01);
printf(" 06 -> busy : %i\n", (status >> 6) & 0x01);
printf("Driver-Voltage : %.2fV\n", voltage);
printf("Rotations : %i\n", counter);
exit(0);
} else if (strcmp(command, "display") == 0) {
int flap = strtol(data, NULL, 10);
// read current eeprom status
char *buffer_w = malloc(4);
sfbus_display(fd, addr_int, flap);
exit(0);
} else if (strcmp(command, "display_fr") == 0) {
int flap = strtol(data, NULL, 10);
// read current eeprom status
char *buffer_w = malloc(4);
sfbus_display_full(fd, addr_int, flap);
exit(0);
}else if (strcmp(command, "reset") == 0) {
sfbus_reset_device(fd, addr_int);
exit(0);
} else if (strcmp(command, "power_on") == 0) {
sfbus_motor_power(fd, addr_int,1);
exit(0);
} else if (strcmp(command, "power_off") == 0) {
sfbus_motor_power(fd, addr_int,0);
exit(0);
} else {
fprintf(stderr, "Invalid command specified!\n");
printUsage(argv);
}
char *buffer = malloc(256);
char *cmd = "\xF0";
sfbus_send_frame(fd, 0, strlen(cmd), cmd);
int len = sfbus_recv_frame_wait(fd, 0xFFFF, buffer);
// printf("TEST:%i %s\n", len, buffer);
free(buffer);
return 0;
}

View File

@@ -0,0 +1,69 @@
#include "rs485.h"
/*
* Open RS485 Interface (FT232RL)
*/
int rs485_init(char *device, int baud) {
int rs485_fd = open(device, O_RDWR);
if (rs485_fd < 0) {
printf("Error %i from open: %s\n", errno, strerror(errno));
return -1;
}
// Flush all data
int result = tcflush(rs485_fd, TCIOFLUSH);
if (result) {
perror("tcflush failed"); // just a warning, not a fatal error
return -1;
}
// Set port config and baud
struct termios options;
result = tcgetattr(rs485_fd, &options);
if (result) {
perror("tcgetattr failed");
close(rs485_fd);
return -1;
}
// Turn off any options that might interfere with our ability to send and
// receive raw binary bytes.
options.c_iflag &= ~(INLCR | IGNCR | ICRNL | IXON | IXOFF);
options.c_oflag &= ~(ONLCR | OCRNL);
options.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
// Set up timeouts: Calls to read() will return as soon as there is
// at least one byte available or when 100 ms has passed.
options.c_cc[VTIME] = 1;
options.c_cc[VMIN] = 0;
cfsetospeed(&options, baud);
cfsetispeed(&options, baud);
result = tcsetattr(rs485_fd, TCSANOW, &options);
if (result) {
perror("tcsetattr failed");
close(rs485_fd);
return -1;
}
rs485_trdir(rs485_fd, 1);
return rs485_fd;
}
/*
* Set RS485 Direction (FT232RL - RTS PIN)
*/
int rs485_trdir(int rs485_fd, int level) {
int status;
if (ioctl(rs485_fd, TIOCMGET, &status) == -1) {
perror("setRTS(): TIOCMGET");
return 0;
}
if (level)
status |= TIOCM_DTR;
else
status &= ~TIOCM_DTR;
if (ioctl(rs485_fd, TIOCMSET, &status) == -1) {
perror("setRTS(): TIOCMSET");
return 0;
}
return 1;
}

View File

@@ -0,0 +1,15 @@
#include <stdio.h>
#include <stdlib.h>
#include <sys/ioctl.h>
#include <fcntl.h> // Contains file controls like O_RDWR
#include <errno.h> // Error integer and strerror() function
#include <string.h>
#include <termios.h> // Contains POSIX terminal control definitions
#include <unistd.h> // write(), read(), close()
#include <sys/types.h>
#define RS485TX 0
#define RS485RX 1
int rs485_init(char *device, int baud);
int rs485_trdir(int rs485_fd, int level);

View File

@@ -0,0 +1,229 @@
#include "sfbus.h"
#include <stdio.h>
#include <string.h>
#include <sys/types.h>
void print_charHex(char *buffer, int length) {
int _tlength = length;
while (_tlength > 0) {
printf("%02X", (*buffer & 0xFF));
buffer++;
_tlength--;
}
}
void print_bufferHexRx(char *buffer, int length, u_int16_t address) {
printf("Rx (0x%04X): 0x", address);
print_charHex(buffer, length);
printf(" | %i bytes received\n", length);
}
void print_bufferHexTx(char *buffer, int length, u_int16_t address) {
printf("Tx (0x%04X): 0x", address);
print_charHex(buffer, length);
printf(" | %i bytes sent\n", length);
}
ssize_t sfbus_recv_frame_wait(int fd, u_int16_t address, char *buffer) {
ssize_t len = 0;
int retryCount = 2;
do {
len = sfbus_recv_frame(fd, address, buffer);
retryCount--;
if (retryCount == 0) {
fprintf(stderr, "Rx timeout\n");
return -1;
}
} while (len <= 0);
print_bufferHexRx(buffer, len - 3, address);
return len;
}
ssize_t sfbus_recv_frame(int fd, u_int16_t address, char *buffer) {
// wait for start byte
char byte = 0x00;
int retryCount = 3;
while (byte != '+') {
byte = 0x00;
read(fd, &byte, 1);
retryCount--;
if (retryCount == 0) {
return -1;
}
}
u_int8_t frm_version;
u_int8_t frm_addr_l;
u_int8_t frm_addr_h;
u_int8_t frm_length;
u_int8_t frm_eof;
read(fd, &frm_version, 1);
read(fd, &frm_length, 1);
read(fd, &frm_addr_l, 1);
read(fd, &frm_addr_h, 1);
u_int16_t dst_addr = frm_addr_l | (frm_addr_h << 8);
if (dst_addr != address) {
return 0;
}
u_int8_t frm_length_counter = frm_length - 3;
// read all bytes:
while (frm_length_counter > 0) {
read(fd, buffer, 1);
buffer++;
frm_length_counter--;
}
read(fd, &frm_eof, 1);
if (frm_eof == '$') {
return frm_length;
} else {
return -1;
}
}
void sfbus_send_frame(int fd, u_int16_t address, u_int8_t length,
char *buffer) {
int frame_size_complete = length + 6;
char *frame = malloc(frame_size_complete);
char *frame_ptr = frame;
*frame = '+'; // startbyte
frame++;
*frame = 0; // protocol version
frame++;
*frame = length + 3; // length
frame++;
*frame = (address);
frame++;
*frame = ((address >> 8));
frame++;
while (length > 0) {
*frame = *buffer;
length--;
buffer++;
frame++;
}
*frame = '$'; // startbyte
rs485_trdir(fd, 0);
int result = write(fd, frame_ptr, frame_size_complete);
print_bufferHexTx(frame_ptr + 5, frame_size_complete - 6, address);
free(frame_ptr);
// tcdrain(fd);
usleep(470 * (frame_size_complete + 1));
rs485_trdir(fd, 1);
}
int sfbus_ping(int fd, u_int16_t address) {
char *cmd = "\xFE";
char *buffer = malloc(64);
sfbus_send_frame(fd, address, strlen(cmd), cmd);
int len = sfbus_recv_frame_wait(fd, 0xFFFF, buffer);
if (len == 4 && *buffer == (char)0xFF) {
printf("Ping okay!\n");
free(buffer);
return 0;
} else {
printf("Ping invalid response!\n");
free(buffer);
return 1;
}
}
int sfbus_read_eeprom(int fd, u_int16_t address, char *buffer) {
char *cmd = "\xF0";
char *_buffer = malloc(256);
sfbus_send_frame(fd, address, strlen(cmd), cmd);
int len = sfbus_recv_frame_wait(fd, 0xFFFF, _buffer);
if (len != 9) {
printf("Invalid data!\n");
return -1;
}
if (*(_buffer + 5) != (char)0xAA || *(_buffer) != (char)0xAA) {
printf("Invalid data!\n");
return -1;
}
memcpy(buffer, _buffer + 1, len - 4);
free(_buffer);
// printf("Read valid data!\n");
return len;
}
int sfbus_write_eeprom(int fd, u_int16_t address, char *wbuffer,
char *rbuffer) {
char *cmd = malloc(5);
*cmd = (char)0xF1; // write eeprom command
memcpy(cmd + 1, wbuffer, 4);
sfbus_send_frame(fd, address, 5, cmd);
free(cmd);
// wait for readback
char *_buffer = malloc(256);
int len = sfbus_recv_frame_wait(fd, 0xFFFF, _buffer);
if (len != 9) {
printf("Invalid data!\n");
return -1;
}
if (*(_buffer + 5) != (char)0xAA || *(_buffer) != (char)0xAA) {
printf("Invalid data!\n");
return -1;
}
memcpy(rbuffer, _buffer + 1, len - 4);
free(_buffer);
// printf("Read valid data!\n");
return len;
}
int sfbus_display(int fd, u_int16_t address, u_int8_t flap) {
char *cmd = malloc(5);
*cmd = (char)0x10; // write eeprom command
*(cmd + 1) = flap;
sfbus_send_frame(fd, address, 2, cmd);
free(cmd);
return 0;
}
int sfbus_display_full(int fd, u_int16_t address, u_int8_t flap) {
char *cmd = malloc(5);
*cmd = (char)0x11; // write eeprom command
*(cmd + 1) = flap;
sfbus_send_frame(fd, address, 2, cmd);
free(cmd);
return 0;
}
u_int8_t sfbus_read_status(int fd, u_int16_t address, double *voltage,
u_int32_t *counter) {
char *cmd = "\xF8";
char *_buffer = malloc(256);
sfbus_send_frame(fd, address, strlen(cmd), cmd);
int res = sfbus_recv_frame_wait(fd, 0xFFFF, _buffer);
if (res < 0){
return 0xFF;
}
u_int16_t _voltage = *(_buffer + 2) & 0xFF | ((*(_buffer + 1) << 8) & 0xFF00);
u_int32_t _counter =
*(_buffer + 6) & 0xFF | (((*(_buffer + 3) & 0xFF) << 24)) |
(((*(_buffer + 4) & 0xFF) << 16)) | (((*(_buffer + 5) & 0xFF) << 8));
double __voltage = ((double)_voltage / 1024) * 55;
*voltage = __voltage;
*counter = (u_int32_t)_counter;
return *_buffer;
}
void sfbus_reset_device(int fd, u_int16_t address) {
char *cmd = "\x30";
sfbus_send_frame(fd, address, strlen(cmd), cmd);
}
void sfbus_motor_power(int fd, u_int16_t address, u_int8_t state) {
char *cmd = "\x20";
if (state > 0) {
cmd = "\x21";
}
sfbus_send_frame(fd, address, 1, cmd);
}

View File

@@ -0,0 +1,14 @@
#include "rs485.h"
ssize_t sfbus_recv_frame(int fd, u_int16_t address, char *buffer);
ssize_t sfbus_recv_frame_wait(int fd, u_int16_t address, char *buffer);
void sfbus_send_frame(int fd, u_int16_t address, u_int8_t length, char *buffer);
void print_charHex(char *buffer, int length);
int sfbus_ping(int fd, u_int16_t address);
int sfbus_read_eeprom(int fd, u_int16_t address, char* buffer);
int sfbus_write_eeprom(int fd, u_int16_t address, char* wbuffer, char *rbuffer);
int sfbus_display(int fd, u_int16_t address, u_int8_t flap);
int sfbus_display_full(int fd, u_int16_t address, u_int8_t flap);
u_int8_t sfbus_read_status(int fd, u_int16_t address, double *voltage, u_int32_t *counter);
void sfbus_reset_device(int fd, u_int16_t address);
void sfbus_motor_power(int fd, u_int16_t address, u_int8_t state);