Commit 56afc6c3 authored by service-config's avatar service-config

DONE

 - Modified some datatypes declarations to be more efficient and less
 memory intenssive.
 - Removed redundant buffers
 - Resized packet buffers to their minimum so save memory
 - remove threaded approach to make overall performance more
 predictable.
 - Fixed the mess I did on the CRC code..
 - Added some debug options
parent 7c39ff0e
This diff is collapsed.
......@@ -20,12 +20,14 @@
#include <datatypes.h>
//#define DEBUG_BLDC
// interface functions
void bldc_interface_init(void(*func)(unsigned char *data, unsigned int len));
void bldc_interface_init(void(*func)(unsigned char *data, int len));
void bldc_interface_set_forward_can(int32_t vesc_id);
void bldc_interface_set_forward_func(void(*func)(unsigned char *data, unsigned int len));
void bldc_interface_send_packet(unsigned char *data, unsigned int len);
void bldc_interface_process_packet(unsigned char *data, unsigned int len);
void bldc_interface_set_forward_func(void(*func)(unsigned char *data, int len));
void bldc_interface_send_packet(unsigned char *data, int len);
void bldc_interface_process_packet(unsigned char *data, int len);
// Function pointer setters
void bldc_interface_set_rx_value_func(void(*func)(mc_values *values));
......
......@@ -29,8 +29,8 @@
#define PACKET_HANDLER 0
// Private functions
static void process_packet(unsigned char *data, unsigned int len);
static void send_packet_bldc_interface(unsigned char *data, unsigned int len);
static void process_packet(unsigned char *data, int len);
static void send_packet_bldc_interface(unsigned char *data, int len);
/**
* Initialize the UART BLDC interface and provide a function to be used for
......@@ -39,7 +39,7 @@ static void send_packet_bldc_interface(unsigned char *data, unsigned int len);
* @param func
* Function provided for sending packets.
*/
void bldc_interface_uart_init(void(*func)(unsigned char *data, unsigned int len)) {
void bldc_interface_uart_init(void(*func)(unsigned char *data, int len)) {
// Initialize packet handler
packet_init(func, process_packet, PACKET_HANDLER);
......@@ -75,7 +75,7 @@ void bldc_interface_uart_run_timer(void) {
* @param len
* Data array length
*/
static void process_packet(unsigned char *data, unsigned int len) {
static void process_packet(unsigned char *data, int len) {
// Let bldc_interface process the packet.
bldc_interface_process_packet(data, len);
}
......@@ -88,7 +88,7 @@ static void process_packet(unsigned char *data, unsigned int len) {
* @param len
* Data array length
*/
static void send_packet_bldc_interface(unsigned char *data, unsigned int len) {
static void send_packet_bldc_interface(unsigned char *data, int len) {
// Pass the packet to the packet handler to add checksum, length, start and stop bytes.
packet_send_packet(data, len, PACKET_HANDLER);
}
......
......@@ -29,7 +29,7 @@
#include <packet.h> // For the MAX_PACKET_LEN define
// Functions
void bldc_interface_uart_init(void(*func)(unsigned char *data, unsigned int len));
void bldc_interface_uart_init(void(*func)(unsigned char *data, int len));
void bldc_interface_uart_process_byte(unsigned char b);
void bldc_interface_uart_run_timer();
......
......@@ -24,53 +24,53 @@
#include <buffer.h>
void buffer_append_int16(uint8_t* buffer, int16_t number, int32_t *index) {
void buffer_append_int16(uint8_t* buffer, int16_t number, int *index) {
buffer[(*index)++] = number >> 8;
buffer[(*index)++] = number;
}
void buffer_append_uint16(uint8_t* buffer, uint16_t number, int32_t *index) {
void buffer_append_uint16(uint8_t* buffer, uint16_t number, int *index) {
buffer[(*index)++] = number >> 8;
buffer[(*index)++] = number;
}
void buffer_append_int32(uint8_t* buffer, int32_t number, int32_t *index) {
void buffer_append_int32(uint8_t* buffer, int32_t number, int *index) {
buffer[(*index)++] = number >> 24;
buffer[(*index)++] = number >> 16;
buffer[(*index)++] = number >> 8;
buffer[(*index)++] = number;
}
void buffer_append_uint32(uint8_t* buffer, uint32_t number, int32_t *index) {
void buffer_append_uint32(uint8_t* buffer, uint32_t number, int *index) {
buffer[(*index)++] = number >> 24;
buffer[(*index)++] = number >> 16;
buffer[(*index)++] = number >> 8;
buffer[(*index)++] = number;
}
void buffer_append_float16(uint8_t* buffer, float number, float scale, int32_t *index) {
void buffer_append_float16(uint8_t* buffer, float number, float scale, int *index) {
buffer_append_int16(buffer, (int16_t)(number * scale), index);
}
void buffer_append_float32(uint8_t* buffer, float number, float scale, int32_t *index) {
void buffer_append_float32(uint8_t* buffer, float number, float scale, int *index) {
buffer_append_int32(buffer, (int32_t)(number * scale), index);
}
int16_t buffer_get_int16(const uint8_t *buffer, int32_t *index) {
int16_t buffer_get_int16(const uint8_t *buffer, int *index) {
int16_t res = ((uint16_t) buffer[*index]) << 8 |
((uint16_t) buffer[*index + 1]);
*index += 2;
return res;
}
uint16_t buffer_get_uint16(const uint8_t *buffer, int32_t *index) {
uint16_t buffer_get_uint16(const uint8_t *buffer, int *index) {
uint16_t res = ((uint16_t) buffer[*index]) << 8 |
((uint16_t) buffer[*index + 1]);
*index += 2;
return res;
}
int32_t buffer_get_int32(const uint8_t *buffer, int32_t *index) {
int32_t buffer_get_int32(const uint8_t *buffer, int *index) {
int32_t res = ((uint32_t) buffer[*index]) << 24 |
((uint32_t) buffer[*index + 1]) << 16 |
((uint32_t) buffer[*index + 2]) << 8 |
......@@ -79,7 +79,7 @@ int32_t buffer_get_int32(const uint8_t *buffer, int32_t *index) {
return res;
}
uint32_t buffer_get_uint32(const uint8_t *buffer, int32_t *index) {
uint32_t buffer_get_uint32(const uint8_t *buffer, int *index) {
uint32_t res = ((uint32_t) buffer[*index]) << 24 |
((uint32_t) buffer[*index + 1]) << 16 |
((uint32_t) buffer[*index + 2]) << 8 |
......@@ -88,10 +88,10 @@ uint32_t buffer_get_uint32(const uint8_t *buffer, int32_t *index) {
return res;
}
float buffer_get_float16(const uint8_t *buffer, float scale, int32_t *index) {
float buffer_get_float16(const uint8_t *buffer, float scale, int *index) {
return (float)buffer_get_int16(buffer, index) / scale;
}
float buffer_get_float32(const uint8_t *buffer, float scale, int32_t *index) {
float buffer_get_float32(const uint8_t *buffer, float scale, int *index) {
return (float)buffer_get_int32(buffer, index) / scale;
}
......@@ -28,17 +28,17 @@
#include <Arduino.h>
//#include <stdint.h>
void buffer_append_int16(uint8_t* buffer, int16_t number, int32_t *index);
void buffer_append_uint16(uint8_t* buffer, uint16_t number, int32_t *index);
void buffer_append_int32(uint8_t* buffer, int32_t number, int32_t *index);
void buffer_append_uint32(uint8_t* buffer, uint32_t number, int32_t *index);
void buffer_append_float16(uint8_t* buffer, float number, float scale, int32_t *index);
void buffer_append_float32(uint8_t* buffer, float number, float scale, int32_t *index);
int16_t buffer_get_int16(const uint8_t *buffer, int32_t *index);
uint16_t buffer_get_uint16(const uint8_t *buffer, int32_t *index);
int32_t buffer_get_int32(const uint8_t *buffer, int32_t *index);
uint32_t buffer_get_uint32(const uint8_t *buffer, int32_t *index);
float buffer_get_float16(const uint8_t *buffer, float scale, int32_t *index);
float buffer_get_float32(const uint8_t *buffer, float scale, int32_t *index);
void buffer_append_int16(uint8_t* buffer, int16_t number, int *index);
void buffer_append_uint16(uint8_t* buffer, uint16_t number, int *index);
void buffer_append_int32(uint8_t* buffer, int32_t number, int *index);
void buffer_append_uint32(uint8_t* buffer, uint32_t number, int *index);
void buffer_append_float16(uint8_t* buffer, float number, float scale, int *index);
void buffer_append_float32(uint8_t* buffer, float number, float scale, int *index);
int16_t buffer_get_int16(const uint8_t *buffer, int *index);
uint16_t buffer_get_uint16(const uint8_t *buffer, int *index);
int32_t buffer_get_int32(const uint8_t *buffer, int *index);
uint32_t buffer_get_uint32(const uint8_t *buffer, int *index);
float buffer_get_float16(const uint8_t *buffer, float scale, int *index);
float buffer_get_float32(const uint8_t *buffer, float scale, int *index);
#endif /* BUFFER_H_ */
......@@ -25,34 +25,19 @@
#include <comm_uart_arduino.h>
#include <bldc_interface_uart.h>
// Settings
#define __CUA_UART_BAUDRATE 115200
//#define SERIAL_RX_BUFFER_SIZE 1024/4
#define __CUA_UART_BAUDRATE 9600
// Private functions
static void send_packet(unsigned char *data, unsigned int len);
static void send_packet(unsigned char *data, int len);
// Interrupts (Makeshift "Threads")
static bool is_data_ready = false;
// Variables
static uint8_t serial_rx_buffer[SERIAL_RX_BUFFER_SIZE];
static int serial_rx_read_pos = 0;
static int serial_rx_write_pos = 0;
//static bool is_data_ready = false;
ISR(TIMER1_COMPA_vect){//timer1 interrupt 1Hz
// Wait for data to become available and process it as long as there is data.
if(is_data_ready) {
while (serial_rx_read_pos != serial_rx_write_pos) {
bldc_interface_uart_process_byte(serial_rx_buffer[serial_rx_read_pos++]);
if (serial_rx_read_pos == SERIAL_RX_BUFFER_SIZE) {
serial_rx_read_pos = 0;
}
}
}
}
#ifdef __CUA_USE_SECOND_SERIAL
SoftwareSerial mySerial(8, 7); // RX, TX
#endif
/**
* This thread is only for calling the timer function once
......@@ -69,17 +54,44 @@ ISR(TIMER1_COMPA_vect){//timer1 interrupt 1Hz
time loop() runs, so using delay inside loop can delay
response. Multiple bytes of data may be available.
*/
void serialEvent() {
while (Serial.available()) {
void softwareSerialEvent() {
bool isWork = false;
#ifdef DEBUG_BLDC
int len = 0;
uint8_t rbyte;
#endif
if(mySerial.available()) {
isWork = true;
#ifdef DEBUG_BLDC
Serial.print(F("[ bldc ] softwareSerialEvent = read["));
#endif
}
serial_rx_buffer[serial_rx_write_pos++] = Serial.read();
while (mySerial.available()) {
if (serial_rx_write_pos == SERIAL_RX_BUFFER_SIZE) {
serial_rx_write_pos = 0;
}
#ifndef DEBUG_BLDC
bldc_interface_uart_process_byte(mySerial.read());
#else
rbyte = mySerial.read();
bldc_interface_uart_process_byte(rbyte);
Serial.write(rbyte);
len += sizeof(uint8_t);
#endif
}
is_data_ready = true;
if(isWork) {
#ifdef DEBUG_BLDC
Serial.print(F("] len["));
Serial.print(len);
Serial.println(F("]"));
#endif
is_data_ready = true;
}
}
/**
......@@ -90,29 +102,26 @@ void serialEvent() {
* @param len
* Data array length
*/
static void send_packet(unsigned char *data, unsigned int len) {
if (len > (PACKET_MAX_PL_LEN + 5)) {
static void send_packet(unsigned char *data, int len) {
/*if (len > (PACKET_MAX_PL_LEN + 5)) {
return;
}
/* Wait for the previous transmission to finish.
while (UART_DEV.txstate == UART_TX_ACTIVE) {
chThdSleep(1);
}*/
// Copy this data to a new buffer in case the provided one is re-used
// after this function returns.
static uint8_t buffer[PACKET_MAX_PL_LEN + 5];
memcpy(buffer, data, len);
// Send the data over UART
Serial.write(buffer, len);
//uartStartSend(&UART_DEV, len, buffer);
#ifdef DEBUG_BLDC
Serial.print(F("[ bldc ] send_packet = write["));
Serial.write(data, len);
Serial.print(F("] len["));
Serial.print(len);
Serial.println(F("]"));
#endif
mySerial.write(data, len);
}
void comm_uart_arduino_init() {
// Initialize UART
Serial.begin(__CUA_UART_BAUDRATE);
mySerial.begin(__CUA_UART_BAUDRATE);
/*while (!Serial) {
; // wait for serial port to connect. Needed for native USB port only
}*/
......@@ -136,7 +145,7 @@ static void send_packet(unsigned char *data, unsigned int len) {
// enable timer compare interrupt
TIMSK0 |= (1 << OCIE0A);*/
//set timer1 interrupt at 1Hz
/*set timer1 interrupt at 1Hz
TCCR1A = 0;// set entire TCCR1A register to 0
TCCR1B = 0;// same for TCCR1B
TCNT1 = 0;//initialize counter value to 0
......@@ -147,7 +156,7 @@ static void send_packet(unsigned char *data, unsigned int len) {
// Set CS101 and CS12 bits for 1024 prescaler
TCCR1B |= (1 << CS12) | (1 << CS10);
// enable timer compare interrupt
TIMSK1 |= (1 << OCIE1A);
TIMSK1 |= (1 << OCIE1A);*/
//set timer2 interrupt at 1kHz
TCCR2A = 0;// set entire TCCR2A register to 0
......@@ -162,9 +171,6 @@ static void send_packet(unsigned char *data, unsigned int len) {
// enable timer compare interrupt
TIMSK2 |= (1 << OCIE2A);
// Inotialize the processing interrupt
is_data_ready = false;
// Allow interrupts so that the Processing and Timer interrupts ("Threads") start
interrupts();
}
......
......@@ -8,9 +8,20 @@
#ifndef COMM_UART_ARDUINO_H_
#define COMM_UART_ARDUINO_H_
#define __CUA_USE_SECOND_SERIAL
#include "Arduino.h"
#ifdef __CUA_USE_SECOND_SERIAL
#include <SoftwareSerial.h>
#else
#define mySerial Serial
#endif
//#define DEBUG_BLDC
// Functions
void comm_uart_arduino_init();
void softwareSerialEvent();
#endif /* COMM_UART_ARDUINO_H_ */
\ No newline at end of file
......@@ -58,7 +58,7 @@ unsigned short crc16(unsigned char *buf, unsigned int len) {
unsigned int i;
unsigned short cksum = 0;
for (i = 0; i < len; i++) {
cksum = pgm_read_word_near(crc16_tab + (((cksum >> 8) ^ *buf++) & 0xFF));
cksum = pgm_read_word_near(crc16_tab + (((cksum >> 8) ^ *buf++) & 0xFF)) ^ (cksum << 8);
//cksum = crc16_tab[(((cksum >> 8) ^ *buf++) & 0xFF)] ^ (cksum << 8);
}
return cksum;
......
......@@ -29,8 +29,8 @@
typedef struct {
volatile unsigned char rx_state;
volatile unsigned char rx_timeout;
void(*send_func)(unsigned char *data, unsigned int len);
void(*process_func)(unsigned char *data, unsigned int len);
void(*send_func)(unsigned char *data, int len);
void(*process_func)(unsigned char *data, int len);
unsigned int payload_length;
unsigned char rx_buffer[PACKET_MAX_PL_LEN];
unsigned char tx_buffer[PACKET_MAX_PL_LEN + 6];
......@@ -41,13 +41,13 @@ typedef struct {
static PACKET_STATE_t handler_states[PACKET_HANDLERS];
void packet_init(void (*s_func)(unsigned char *data, unsigned int len),
void (*p_func)(unsigned char *data, unsigned int len), int handler_num) {
void packet_init(void (*s_func)(unsigned char *data, int len),
void (*p_func)(unsigned char *data, int len), int handler_num) {
handler_states[handler_num].send_func = s_func;
handler_states[handler_num].process_func = p_func;
}
void packet_send_packet(unsigned char *data, unsigned int len, int handler_num) {
void packet_send_packet(unsigned char *data, int len, int handler_num) {
if (len > PACKET_MAX_PL_LEN) {
return;
}
......@@ -149,9 +149,19 @@ void packet_process_byte(uint8_t rx_data, int handler_num) {
case 6:
if (rx_data == 3) {
#ifdef DEBUG_BLDC_P
Serial.print(F("[ bldc ] packet_process_byte = rx_data["));
Serial.print(rx_data);
Serial.print("] rx_state[");
Serial.print(handler_states[handler_num].rx_state);
Serial.print("] payload_length[");
Serial.print(handler_states[handler_num].payload_length);
Serial.println("]");
#endif
if (crc16(handler_states[handler_num].rx_buffer, handler_states[handler_num].payload_length)
== ((unsigned short)handler_states[handler_num].crc_high << 8
| (unsigned short)handler_states[handler_num].crc_low)) {
| (unsigned short)handler_states[handler_num].crc_low)) {
//Serial.println("Packet received!");
// Packet received!
if (handler_states[handler_num].process_func) {
handler_states[handler_num].process_func(handler_states[handler_num].rx_buffer,
......
......@@ -28,16 +28,18 @@
#include <Arduino.h>
//#include <stdint.h>
//#define DEBUG_BLDC_P
// Settings
#define PACKET_RX_TIMEOUT 2
#define PACKET_HANDLERS 1
#define PACKET_MAX_PL_LEN 512/4
#define PACKET_MAX_PL_LEN 128 //256
// Functions
void packet_init(void (*s_func)(unsigned char *data, unsigned int len),
void (*p_func)(unsigned char *data, unsigned int len), int handler_num);
void packet_init(void (*s_func)(unsigned char *data, int len),
void (*p_func)(unsigned char *data, int len), int handler_num);
void packet_process_byte(uint8_t rx_data, int handler_num);
void packet_timerfunc(void);
void packet_send_packet(unsigned char *data, unsigned int len, int handler_num);
void packet_send_packet(unsigned char *data, int len, int handler_num);
#endif /* PACKET_H_ */
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment