Long packet support, configurable min and max duty, longer CAN buffer, default parameter changes, appconf ack fix, refactoring

This commit is contained in:
Benjamin Vedder 2015-05-20 16:13:48 +02:00
parent bc7a779632
commit 87932662b7
19 changed files with 254 additions and 162 deletions

View File

@ -49,9 +49,9 @@ static int serial_rx_write_pos = 0;
static int is_running = 0;
// Private functions
static void process_packet(unsigned char *data, unsigned char len);
static void send_packet_wrapper(unsigned char *data, unsigned char len);
static void send_packet(unsigned char *data, unsigned char len);
static void process_packet(unsigned char *data, unsigned int len);
static void send_packet_wrapper(unsigned char *data, unsigned int len);
static void send_packet(unsigned char *data, unsigned int len);
/*
* This callback is invoked when a transmission buffer has been completely
@ -114,16 +114,16 @@ static UARTConfig uart_cfg = {
0
};
static void process_packet(unsigned char *data, unsigned char len) {
static void process_packet(unsigned char *data, unsigned int len) {
commands_set_send_func(send_packet_wrapper);
commands_process_packet(data, len);
}
static void send_packet_wrapper(unsigned char *data, unsigned char len) {
static void send_packet_wrapper(unsigned char *data, unsigned int len) {
packet_send_packet(data, len, PACKET_HANDLER);
}
static void send_packet(unsigned char *data, unsigned char len) {
static void send_packet(unsigned char *data, unsigned int len) {
// Wait for the previous transmission to finish.
while (HW_UART_DEV.txstate == UART_TX_ACTIVE) {
chThdSleep(1);
@ -131,7 +131,7 @@ static void send_packet(unsigned char *data, unsigned char len) {
// Copy this data to a new buffer in case the provided one is re-used
// after this function returns.
static uint8_t buffer[300];
static uint8_t buffer[PACKET_MAX_PL_LEN + 5];
memcpy(buffer, data, len);
uartStartSend(&HW_UART_DEV, len, buffer);

View File

@ -33,10 +33,12 @@
#include "commands.h"
#include "app.h"
#include "crc.h"
#include "packet.h"
// Settings
#define CANDx CAND1
#define RX_FRAMES_SIZE 10
#define RX_FRAMES_SIZE 100
#define RX_BUFFER_SIZE PACKET_MAX_PL_LEN
// Threads
static WORKING_AREA(cancom_read_thread_wa, 512);
@ -49,8 +51,8 @@ static msg_t cancom_process_thread(void *arg);
// Variables
static can_status_msg stat_msgs[CAN_STATUS_MSGS_TO_STORE];
static Mutex can_mtx;
static uint8_t rx_buffer[256];
static uint8_t rx_buffer_last_id;
static uint8_t rx_buffer[RX_BUFFER_SIZE];
static unsigned int rx_buffer_last_id;
static CANRxFrame rx_frames[RX_FRAMES_SIZE];
static int rx_frame_read;
static int rx_frame_write;
@ -68,7 +70,7 @@ static const CANConfig cancfg = {
};
// Private functions
static void send_packet_wrapper(unsigned char *data, unsigned char len);
static void send_packet_wrapper(unsigned char *data, unsigned int len);
void comm_can_init(void) {
for (int i = 0;i < CAN_STATUS_MSGS_TO_STORE;i++) {
@ -138,7 +140,8 @@ static msg_t cancom_process_thread(void *arg) {
process_tp = chThdSelf();
int32_t ind = 0;
int32_t rxbuf_len;
unsigned int rxbuf_len;
unsigned int rxbuf_ind;
uint8_t crc_low;
uint8_t crc_high;
bool commands_send;
@ -190,11 +193,25 @@ static msg_t cancom_process_thread(void *arg) {
memcpy(rx_buffer + rxmsg.data8[0], rxmsg.data8 + 1, rxmsg.DLC - 1);
break;
case CAN_PACKET_FILL_RX_BUFFER_LONG:
rxbuf_ind = (unsigned int)rxmsg.data8[0] << 8;
rxbuf_ind |= rxmsg.data8[1];
if (rxbuf_ind < RX_BUFFER_SIZE) {
memcpy(rx_buffer + rxbuf_ind, rxmsg.data8 + 2, rxmsg.DLC - 2);
}
break;
case CAN_PACKET_PROCESS_RX_BUFFER:
ind = 0;
rx_buffer_last_id = rxmsg.data8[ind++];
commands_send = rxmsg.data8[ind++];
rxbuf_len = rxmsg.data8[ind++];
rxbuf_len = (unsigned int)rxmsg.data8[ind++] << 8;
rxbuf_len |= (unsigned int)rxmsg.data8[ind++];
if (rxbuf_len > RX_BUFFER_SIZE) {
break;
}
crc_high = rxmsg.data8[ind++];
crc_low = rxmsg.data8[ind++];
@ -306,7 +323,7 @@ void comm_can_transmit(uint32_t id, uint8_t *data, uint8_t len) {
}
/**
* Send a buffer up to 256 bytes as fragments. If the buffer is 6 bytes or less
* Send a buffer up to RX_BUFFER_SIZE bytes as fragments. If the buffer is 6 bytes or less
* it will be sent in a single CAN frame, otherwise it will be split into
* several frames.
*
@ -323,7 +340,7 @@ void comm_can_transmit(uint32_t id, uint8_t *data, uint8_t len) {
* If true, this packet will be passed to the send function of commands.
* Otherwise, it will be passed to the process function.
*/
void comm_can_send_buffer(uint8_t controller_id, uint8_t *data, uint8_t len, bool send) {
void comm_can_send_buffer(uint8_t controller_id, uint8_t *data, unsigned int len, bool send) {
uint8_t send_buffer[8];
if (len <= 6) {
@ -334,9 +351,15 @@ void comm_can_send_buffer(uint8_t controller_id, uint8_t *data, uint8_t len, boo
ind += len;
comm_can_transmit(controller_id | ((uint32_t)CAN_PACKET_PROCESS_SHORT_BUFFER << 8), send_buffer, ind);
} else {
for (int i = 0;i < len;i += 7) {
uint8_t send_len = 7;
unsigned int end_a = 0;
for (unsigned int i = 0;i < len;i += 7) {
end_a = i;
if (i > 256) {
break;
}
uint8_t send_len = 7;
send_buffer[0] = i;
if ((i + 7) <= len) {
@ -349,10 +372,26 @@ void comm_can_send_buffer(uint8_t controller_id, uint8_t *data, uint8_t len, boo
comm_can_transmit(controller_id | ((uint32_t)CAN_PACKET_FILL_RX_BUFFER << 8), send_buffer, send_len + 1);
}
for (unsigned int i = end_a;i < len;i += 6) {
uint8_t send_len = 6;
send_buffer[0] = i >> 8;
send_buffer[1] = i & 0xFF;
if ((i + 6) <= len) {
memcpy(send_buffer + 2, data + i, send_len);
} else {
send_len = len - i;
memcpy(send_buffer + 2, data + i, send_len);
}
comm_can_transmit(controller_id | ((uint32_t)CAN_PACKET_FILL_RX_BUFFER_LONG << 8), send_buffer, send_len + 2);
}
uint32_t ind = 0;
send_buffer[ind++] = app_get_configuration()->controller_id;
send_buffer[ind++] = send;
send_buffer[ind++] = len;
send_buffer[ind++] = len >> 8;
send_buffer[ind++] = len & 0xFF;
unsigned short crc = crc16(data, len);
send_buffer[ind++] = (uint8_t)(crc >> 8);
send_buffer[ind++] = (uint8_t)(crc & 0xFF);
@ -432,6 +471,6 @@ can_status_msg *comm_can_get_status_msg_id(int id) {
return 0;
}
static void send_packet_wrapper(unsigned char *data, unsigned char len) {
static void send_packet_wrapper(unsigned char *data, unsigned int len) {
comm_can_send_buffer(rx_buffer_last_id, data, len, true);
}

View File

@ -34,7 +34,7 @@
// Functions
void comm_can_init(void);
void comm_can_transmit(uint32_t id, uint8_t *data, uint8_t len);
void comm_can_send_buffer(uint8_t controller_id, uint8_t *data, uint8_t len, bool send);
void comm_can_send_buffer(uint8_t controller_id, uint8_t *data, unsigned int len, bool send);
void comm_can_set_duty(uint8_t controller_id, float duty);
void comm_can_set_current(uint8_t controller_id, float current);
void comm_can_set_current_brake(uint8_t controller_id, float current);

View File

@ -43,9 +43,9 @@ static Mutex send_mutex;
static Thread *process_tp;
// Private functions
static void process_packet(unsigned char *data, unsigned char len);
static void send_packet(unsigned char *buffer, unsigned char len);
static void send_packet_wrapper(unsigned char *data, unsigned char len);
static void process_packet(unsigned char *data, unsigned int len);
static void send_packet(unsigned char *buffer, unsigned int len);
static void send_packet_wrapper(unsigned char *data, unsigned int len);
static msg_t serial_read_thread(void *arg) {
(void)arg;
@ -101,16 +101,16 @@ static msg_t serial_process_thread(void *arg) {
return 0;
}
static void process_packet(unsigned char *data, unsigned char len) {
static void process_packet(unsigned char *data, unsigned int len) {
commands_set_send_func(send_packet_wrapper);
commands_process_packet(data, len);
}
static void send_packet_wrapper(unsigned char *data, unsigned char len) {
static void send_packet_wrapper(unsigned char *data, unsigned int len) {
packet_send_packet(data, len, PACKET_HANDLER);
}
static void send_packet(unsigned char *buffer, unsigned char len) {
static void send_packet(unsigned char *buffer, unsigned int len) {
chMtxLock(&send_mutex);
chSequentialStreamWrite(&SDU1, buffer, len);
chMtxUnlock();

View File

@ -39,6 +39,7 @@
#include "comm_can.h"
#include "flash_helper.h"
#include "utils.h"
#include "packet.h"
#include <math.h>
#include <string.h>
@ -51,13 +52,13 @@ static WORKING_AREA(detect_thread_wa, 2048);
static Thread *detect_tp;
// Private variables
static uint8_t send_buffer[256];
static uint8_t send_buffer[PACKET_MAX_PL_LEN];
static float detect_cycle_int_limit;
static float detect_coupling_k;
static float detect_current;
static float detect_min_rpm;
static float detect_low_duty;
static void(*send_func)(unsigned char *data, unsigned char len) = 0;
static void(*send_func)(unsigned char *data, unsigned int len) = 0;
void commands_init(void) {
chThdCreateStatic(detect_thread_wa, sizeof(detect_thread_wa), NORMALPRIO, detect_thread, NULL);
@ -69,7 +70,7 @@ void commands_init(void) {
* @param func
* A pointer to the packet sending function.
*/
void commands_set_send_func(void(*func)(unsigned char *data, unsigned char len)) {
void commands_set_send_func(void(*func)(unsigned char *data, unsigned int len)) {
send_func = func;
}
@ -82,7 +83,7 @@ void commands_set_send_func(void(*func)(unsigned char *data, unsigned char len))
* @param len
* The data length.
*/
void commands_send_packet(unsigned char *data, unsigned char len) {
void commands_send_packet(unsigned char *data, unsigned int len) {
if (send_func) {
send_func(data, len);
}
@ -97,7 +98,7 @@ void commands_send_packet(unsigned char *data, unsigned char len) {
* @param len
* The length of the buffer.
*/
void commands_process_packet(unsigned char *data, unsigned char len) {
void commands_process_packet(unsigned char *data, unsigned int len) {
if (!len) {
return;
}
@ -128,7 +129,7 @@ void commands_process_packet(unsigned char *data, unsigned char len) {
break;
case COMM_JUMP_TO_BOOTLOADER:
utils_jump_to_bootloader();
flash_helper_jump_to_bootloader();
break;
case COMM_ERASE_NEW_APP:
@ -241,6 +242,8 @@ void commands_process_packet(unsigned char *data, unsigned char len) {
mcconf.l_temp_fet_end = (float)buffer_get_int32(data, &ind) / 1000.0;
mcconf.l_temp_motor_start = (float)buffer_get_int32(data, &ind) / 1000.0;
mcconf.l_temp_motor_end = (float)buffer_get_int32(data, &ind) / 1000.0;
mcconf.l_min_duty = (float)buffer_get_int32(data, &ind) / 1000000.0;
mcconf.l_max_duty = (float)buffer_get_int32(data, &ind) / 1000000.0;
mcconf.lo_current_max = mcconf.l_current_max;
mcconf.lo_current_min = mcconf.l_current_min;
@ -311,6 +314,8 @@ void commands_process_packet(unsigned char *data, unsigned char len) {
buffer_append_int32(send_buffer, (int32_t)(mcconf.l_temp_fet_end * 1000.0), &ind);
buffer_append_int32(send_buffer, (int32_t)(mcconf.l_temp_motor_start * 1000.0), &ind);
buffer_append_int32(send_buffer, (int32_t)(mcconf.l_temp_motor_end * 1000.0), &ind);
buffer_append_int32(send_buffer, (int32_t)(mcconf.l_min_duty * 1000000.0), &ind);
buffer_append_int32(send_buffer, (int32_t)(mcconf.l_max_duty * 1000000.0), &ind);
send_buffer[ind++] = mcconf.sl_is_sensorless;
buffer_append_int32(send_buffer, (int32_t)(mcconf.sl_min_erpm * 1000.0), &ind);
@ -401,7 +406,7 @@ void commands_process_packet(unsigned char *data, unsigned char len) {
timeout_configure(appconf.timeout_msec, appconf.timeout_brake_current);
ind = 0;
send_buffer[ind++] = COMM_SET_MCCONF;
send_buffer[ind++] = COMM_SET_APPCONF;
commands_send_packet(send_buffer, ind);
break;

View File

@ -29,9 +29,9 @@
// Functions
void commands_init(void);
void commands_set_send_func(void(*func)(unsigned char *data, unsigned char len));
void commands_send_packet(unsigned char *data, unsigned char len);
void commands_process_packet(unsigned char *data, unsigned char len);
void commands_set_send_func(void(*func)(unsigned char *data, unsigned int len));
void commands_send_packet(unsigned char *data, unsigned int len);
void commands_process_packet(unsigned char *data, unsigned int len);
void commands_printf(char* format, ...);
void commands_send_samples(uint8_t *data, int len);
void commands_send_rotor_pos(float rotor_pos);

View File

@ -93,6 +93,12 @@
#ifndef MCPWM_MAX_FB_CURR_DIR_CHANGE
#define MCPWM_MAX_FB_CURR_DIR_CHANGE 10.0 // Maximum current during full brake during which a direction change is allowed
#endif
#ifndef MCPWM_MIN_DUTY
#define MCPWM_MIN_DUTY 0.01 // Minimum duty cycle
#endif
#ifndef MCPWM_MAX_DUTY
#define MCPWM_MAX_DUTY 0.95 // Maximum duty cycle
#endif
// EEPROM settings
#define EEPROM_BASE_MCCONF 1000
@ -150,7 +156,9 @@ void conf_general_read_app_configuration(app_configuration *conf) {
conf->send_can_status = false;
conf->send_can_status_rate_hz = 500;
conf->app_to_use = APP_NONE;
// The default app is UART in case the UART port is used for
// firmware updates.
conf->app_to_use = APP_UART;
conf->app_ppm_conf.ctrl_type = PPM_CTRL_TYPE_NONE;
conf->app_ppm_conf.pid_max_erpm = 15000;
@ -272,6 +280,8 @@ void conf_general_read_mc_configuration(mc_configuration *conf) {
conf->l_temp_fet_end = MCPWM_LIM_TEMP_FET_END;
conf->l_temp_motor_start = MCPWM_LIM_TEMP_MOTOR_START;
conf->l_temp_motor_end = MCPWM_LIM_TEMP_MOTOR_END;
conf->l_min_duty = MCPWM_MIN_DUTY;
conf->l_max_duty = MCPWM_MAX_DUTY;
conf->lo_current_max = conf->l_current_max;
conf->lo_current_min = conf->l_current_min;

View File

@ -27,7 +27,7 @@
// Firmware version
#define FW_VERSION_MAJOR 1
#define FW_VERSION_MINOR 1
#define FW_VERSION_MINOR 2
#include "datatypes.h"
@ -39,7 +39,7 @@
// Component parameters to override
//#define V_REG 3.3
#define VIN_R1 39000.0
//#define VIN_R1 39000.0
//#define VIN_R2 2200.0
//#define CURRENT_AMP_GAIN 10.0
//#define CURRENT_SHUNT_RES 0.001
@ -94,7 +94,7 @@
* Output WS2811 signal on the HALL1 pin. Notice that hall sensors can't be used
* at the same time.
*/
#define WS2811_ENABLE 0
#define WS2811_ENABLE 1
#define WS2811_CLK_HZ 800000
#define WS2811_LED_NUM 14
#define WS2811_USE_CH2 1 // 0: CH1 (PB6) 1: CH2 (PB7)

View File

@ -105,6 +105,8 @@ typedef struct {
float l_temp_fet_end;
float l_temp_motor_start;
float l_temp_motor_end;
float l_min_duty;
float l_max_duty;
// Overridden limits (Computed during runtime)
float lo_current_max;
float lo_current_min;
@ -294,6 +296,7 @@ typedef enum {
CAN_PACKET_SET_RPM,
CAN_PACKET_SET_POS,
CAN_PACKET_FILL_RX_BUFFER,
CAN_PACKET_FILL_RX_BUFFER_LONG,
CAN_PACKET_PROCESS_RX_BUFFER,
CAN_PACKET_PROCESS_SHORT_BUFFER,
CAN_PACKET_STATUS

View File

@ -27,6 +27,8 @@
#include "hal.h"
#include "stm32f4xx_conf.h"
#include "utils.h"
#include "mcpwm.h"
#include "hw.h"
#include <string.h>
/*
@ -89,6 +91,7 @@ uint16_t flash_helper_erase_new_app(uint32_t new_app_size) {
new_app_size += flash_addr[NEW_APP_BASE];
mcpwm_release_motor();
utils_sys_lock_cnt();
RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, DISABLE);
@ -113,6 +116,7 @@ uint16_t flash_helper_write_new_app_data(uint32_t offset, uint8_t *data, uint32_
FLASH_ClearFlag(FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR |
FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
mcpwm_release_motor();
utils_sys_lock_cnt();
RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, DISABLE);
@ -128,3 +132,49 @@ uint16_t flash_helper_write_new_app_data(uint32_t offset, uint8_t *data, uint32_
return FLASH_COMPLETE;
}
/**
* Stop the system and jump to the bootloader.
*/
void flash_helper_jump_to_bootloader(void) {
typedef void (*pFunction)(void);
mcpwm_release_motor();
usbDisconnectBus(&USBD1);
usbStop(&USBD1);
uartStop(&HW_UART_DEV);
palSetPadMode(HW_UART_TX_PORT, HW_UART_TX_PIN, PAL_MODE_INPUT);
palSetPadMode(HW_UART_RX_PORT, HW_UART_RX_PIN, PAL_MODE_INPUT);
// Disable watchdog
RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, DISABLE);
chSysDisable();
pFunction jump_to_bootloader;
// Variable that will be loaded with the start address of the application
vu32* jump_address;
const vu32* bootloader_address = (vu32*)0x080E0000;
// Get jump address from application vector table
jump_address = (vu32*) bootloader_address[1];
// Load this address into function pointer
jump_to_bootloader = (pFunction) jump_address;
// Clear pending interrupts
SCB_ICSR = ICSR_PENDSVCLR;
// Disable all interrupts
for(int i = 0;i < 8;i++) {
NVIC->ICER[i] = NVIC->IABR[i];
}
// Set stack pointer
__set_MSP((u32) (bootloader_address[0]));
// Jump to the bootloader
jump_to_bootloader();
}

View File

@ -30,5 +30,6 @@
// Functions
uint16_t flash_helper_erase_new_app(uint32_t new_app_size);
uint16_t flash_helper_write_new_app_data(uint32_t offset, uint8_t *data, uint32_t len);
void flash_helper_jump_to_bootloader(void);
#endif /* FLASH_HELPER_H_ */

View File

@ -34,7 +34,8 @@
#define MCPWM_CURRENT_MIN -60.0 // Current limit in Amperes (Lower)
#define MCPWM_IN_CURRENT_MAX 60.0 // Input current limit in Amperes (Upper)
#define MCPWM_IN_CURRENT_MIN -20.0 // Input current limit in Amperes (Lower)
#define MCPWM_MAX_ABS_CURRENT 110.0 // The maximum absolute current above which a fault is generated
#define MCPWM_MAX_ABS_CURRENT 130.0 // The maximum absolute current above which a fault is generated
#define MCPWM_SLOW_ABS_OVERCURRENT 1 // Use the filtered (and hence slower) current for the overcurrent fault detection
// Sensorless settings
#define MCPWM_IS_SENSORLESS 1 // Use sensorless commutation

74
mcpwm.c
View File

@ -608,7 +608,7 @@ void mcpwm_set_pid_pos(float pos) {
pos_pid_set_pos = pos;
if (state != MC_STATE_RUNNING) {
set_duty_cycle_hl(MCPWM_MIN_DUTY_CYCLE);
set_duty_cycle_hl(conf.l_min_duty);
}
}
@ -637,7 +637,7 @@ void mcpwm_set_current(float current) {
current_set = current;
if (state != MC_STATE_RUNNING) {
set_duty_cycle_hl(SIGN(current) * MCPWM_MIN_DUTY_CYCLE);
set_duty_cycle_hl(SIGN(current) * conf.l_min_duty);
}
}
@ -1078,7 +1078,7 @@ static int try_input(void) {
* the motor phases will be shorted to brake the motor.
*/
static void set_duty_cycle_hl(float dutyCycle) {
utils_truncate_number(&dutyCycle, -MCPWM_MAX_DUTY_CYCLE, MCPWM_MAX_DUTY_CYCLE);
utils_truncate_number(&dutyCycle, -conf.l_max_duty, conf.l_max_duty);
if (state == MC_STATE_DETECTING) {
stop_pwm_ll();
@ -1088,11 +1088,11 @@ static void set_duty_cycle_hl(float dutyCycle) {
dutycycle_set = dutyCycle;
if (state != MC_STATE_RUNNING) {
if (fabsf(dutyCycle) >= MCPWM_MIN_DUTY_CYCLE) {
if (fabsf(dutyCycle) >= conf.l_min_duty) {
// dutycycle_now is updated by the back-emf detection. If the motor already
// is spinning, it will be non-zero.
if (fabsf(dutycycle_now) < MCPWM_MIN_DUTY_CYCLE) {
dutycycle_now = SIGN(dutyCycle) * MCPWM_MIN_DUTY_CYCLE;
if (fabsf(dutycycle_now) < conf.l_min_duty) {
dutycycle_now = SIGN(dutyCycle) * conf.l_min_duty;
}
set_duty_cycle_ll(dutycycle_now);
@ -1129,14 +1129,14 @@ static void set_duty_cycle_hl(float dutyCycle) {
* the motor will be switched off.
*/
static void set_duty_cycle_ll(float dutyCycle) {
if (dutyCycle >= MCPWM_MIN_DUTY_CYCLE) {
if (dutyCycle >= conf.l_min_duty) {
direction = 1;
} else if (dutyCycle <= -MCPWM_MIN_DUTY_CYCLE) {
} else if (dutyCycle <= -conf.l_min_duty) {
dutyCycle = -dutyCycle;
direction = 0;
}
if (dutyCycle < MCPWM_MIN_DUTY_CYCLE) {
if (dutyCycle < conf.l_min_duty) {
switch (state) {
case MC_STATE_RUNNING:
full_brake_ll();
@ -1150,8 +1150,8 @@ static void set_duty_cycle_ll(float dutyCycle) {
break;
}
return;
} else if (dutyCycle > MCPWM_MAX_DUTY_CYCLE) {
dutyCycle = MCPWM_MAX_DUTY_CYCLE;
} else if (dutyCycle > conf.l_max_duty) {
dutyCycle = conf.l_max_duty;
}
set_duty_cycle_hw(dutyCycle);
@ -1202,7 +1202,7 @@ static void set_duty_cycle_hw(float dutyCycle) {
timer_tmp = timer_struct;
utils_sys_unlock_cnt();
utils_truncate_number(&dutyCycle, MCPWM_MIN_DUTY_CYCLE, MCPWM_MAX_DUTY_CYCLE);
utils_truncate_number(&dutyCycle, conf.l_min_duty, conf.l_max_duty);
if (conf.motor_type == MOTOR_TYPE_BLDC && conf.pwm_mode == PWM_MODE_BIPOLAR && !IS_DETECTING()) {
timer_tmp.duty = (uint16_t) (((float) timer_tmp.top / 2.0) * dutyCycle
@ -1269,16 +1269,16 @@ static void run_pid_control_speed(void) {
float output = p_term + i_term + d_term;
// Make sure that at least minimum output is used
if (fabsf(output) < MCPWM_MIN_DUTY_CYCLE) {
output = SIGN(output) * MCPWM_MIN_DUTY_CYCLE;
if (fabsf(output) < conf.l_min_duty) {
output = SIGN(output) * conf.l_min_duty;
}
// Do not output in reverse direction to oppose too high rpm
if (speed_pid_set_rpm > 0.0 && output < 0.0) {
output = MCPWM_MIN_DUTY_CYCLE;
output = conf.l_min_duty;
i_term = 0.0;
} else if (speed_pid_set_rpm < 0.0 && output > 0.0) {
output = -MCPWM_MIN_DUTY_CYCLE;
output = -conf.l_min_duty;
i_term = 0.0;
}
@ -1463,7 +1463,7 @@ static msg_t timer_thread(void *arg) {
} else {
dutycycle_now = -amp / (float)ADC_Value[ADC_IND_VIN_SENS];
}
utils_truncate_number((float*)&dutycycle_now, -MCPWM_MAX_DUTY_CYCLE, MCPWM_MAX_DUTY_CYCLE);
utils_truncate_number((float*)&dutycycle_now, -conf.l_max_duty, conf.l_max_duty);
break;
case MC_STATE_DETECTING:
@ -1488,7 +1488,7 @@ static msg_t timer_thread(void *arg) {
filter_add_sample((float*)kv_fir_samples, mcpwm_get_kv(),
KV_FIR_TAPS_BITS, (uint32_t*)&kv_fir_index);
} else if (state == MC_STATE_OFF) {
if (dutycycle_now >= MCPWM_MIN_DUTY_CYCLE) {
if (dutycycle_now >= conf.l_min_duty) {
filter_add_sample((float*)kv_fir_samples, mcpwm_get_kv(),
KV_FIR_TAPS_BITS, (uint32_t*)&kv_fir_index);
}
@ -1965,20 +1965,20 @@ void mcpwm_adc_int_handler(void *p, uint32_t flags) {
}
// Upper truncation
utils_truncate_number((float*)&dutycycle_now_tmp, -MCPWM_MAX_DUTY_CYCLE, MCPWM_MAX_DUTY_CYCLE);
utils_truncate_number((float*)&dutycycle_now_tmp, -conf.l_max_duty, conf.l_max_duty);
// Lower truncation
if (fabsf(dutycycle_now_tmp) < MCPWM_MIN_DUTY_CYCLE) {
if (fabsf(dutycycle_now_tmp) < conf.l_min_duty) {
if (dutycycle_now_tmp < 0.0 && current_set > 0.0) {
dutycycle_now_tmp = MCPWM_MIN_DUTY_CYCLE;
dutycycle_now_tmp = conf.l_min_duty;
} else if (dutycycle_now_tmp > 0.0 && current_set < 0.0) {
dutycycle_now_tmp = -MCPWM_MIN_DUTY_CYCLE;
dutycycle_now_tmp = -conf.l_min_duty;
}
}
// The set dutycycle should be in the correct direction in case the output is lower
// than the minimum duty cycle and the mechanism below gets activated.
dutycycle_set = dutycycle_now_tmp >= 0.0 ? MCPWM_MIN_DUTY_CYCLE : -MCPWM_MIN_DUTY_CYCLE;
dutycycle_set = dutycycle_now_tmp >= 0.0 ? conf.l_min_duty : -conf.l_min_duty;
} else if (control_mode == CONTROL_MODE_CURRENT_BRAKE) {
// Compute error
const float error = -fabsf(current_set) - current_nofilter;
@ -1998,15 +1998,15 @@ void mcpwm_adc_int_handler(void *p, uint32_t flags) {
dutycycle_now_tmp += SIGN(dutycycle_now_tmp) * step;
// Upper truncation
utils_truncate_number((float*)&dutycycle_now_tmp, -MCPWM_MAX_DUTY_CYCLE, MCPWM_MAX_DUTY_CYCLE);
utils_truncate_number((float*)&dutycycle_now_tmp, -conf.l_max_duty, conf.l_max_duty);
// Lower truncation
if (fabsf(dutycycle_now_tmp) < MCPWM_MIN_DUTY_CYCLE) {
if (fabsf(dutycycle_now_tmp) < conf.l_min_duty) {
if (fabsf(rpm_now) < conf.l_max_erpm_fbrake_cc) {
dutycycle_now_tmp = 0.0;
dutycycle_set = dutycycle_now_tmp;
} else {
dutycycle_now_tmp = SIGN(dutycycle_now_tmp) * MCPWM_MIN_DUTY_CYCLE;
dutycycle_now_tmp = SIGN(dutycycle_now_tmp) * conf.l_min_duty;
dutycycle_set = dutycycle_now_tmp;
}
}
@ -2022,7 +2022,7 @@ void mcpwm_adc_int_handler(void *p, uint32_t flags) {
ramp_step_no_lim * fabsf(current_nofilter - conf.lo_current_max) * MCPWM_CURRENT_LIMIT_GAIN);
limit_delay = 1;
} else if (current_nofilter < conf.lo_current_min) {
utils_step_towards((float*) &dutycycle_now, direction ? MCPWM_MAX_DUTY_CYCLE : -MCPWM_MAX_DUTY_CYCLE,
utils_step_towards((float*) &dutycycle_now, direction ? conf.l_max_duty : -conf.l_max_duty,
ramp_step_no_lim * fabsf(current_nofilter - conf.lo_current_min) * MCPWM_CURRENT_LIMIT_GAIN);
limit_delay = 1;
} else if (current_in_nofilter > conf.lo_in_current_max) {
@ -2030,7 +2030,7 @@ void mcpwm_adc_int_handler(void *p, uint32_t flags) {
ramp_step_no_lim * fabsf(current_in_nofilter - conf.lo_in_current_max) * MCPWM_CURRENT_LIMIT_GAIN);
limit_delay = 1;
} else if (current_in_nofilter < conf.lo_in_current_min) {
utils_step_towards((float*) &dutycycle_now, direction ? MCPWM_MAX_DUTY_CYCLE : -MCPWM_MAX_DUTY_CYCLE,
utils_step_towards((float*) &dutycycle_now, direction ? conf.l_max_duty : -conf.l_max_duty,
ramp_step_no_lim * fabsf(current_in_nofilter - conf.lo_in_current_min) * MCPWM_CURRENT_LIMIT_GAIN);
limit_delay = 1;
} else if (rpm > conf.l_max_erpm) {
@ -2055,19 +2055,19 @@ void mcpwm_adc_int_handler(void *p, uint32_t flags) {
// When the set duty cycle is in the opposite direction, make sure that the motor
// starts again after stopping completely
if (fabsf(dutycycle_now) < MCPWM_MIN_DUTY_CYCLE) {
if (dutycycle_set >= MCPWM_MIN_DUTY_CYCLE) {
dutycycle_now = MCPWM_MIN_DUTY_CYCLE;
} else if (dutycycle_set <= -MCPWM_MIN_DUTY_CYCLE) {
dutycycle_now = -MCPWM_MIN_DUTY_CYCLE;
if (fabsf(dutycycle_now) < conf.l_min_duty) {
if (dutycycle_set >= conf.l_min_duty) {
dutycycle_now = conf.l_min_duty;
} else if (dutycycle_set <= -conf.l_min_duty) {
dutycycle_now = -conf.l_min_duty;
}
}
// Don't start in the opposite direction when the RPM is too high even if the current is low enough.
if (dutycycle_now >= MCPWM_MIN_DUTY_CYCLE && rpm < -conf.l_max_erpm_fbrake) {
dutycycle_now = -MCPWM_MIN_DUTY_CYCLE;
} else if (dutycycle_now <= -MCPWM_MIN_DUTY_CYCLE && rpm > conf.l_max_erpm_fbrake) {
dutycycle_now = MCPWM_MIN_DUTY_CYCLE;
if (dutycycle_now >= conf.l_min_duty && rpm < -conf.l_max_erpm_fbrake) {
dutycycle_now = -conf.l_min_duty;
} else if (dutycycle_now <= -conf.l_min_duty && rpm > conf.l_max_erpm_fbrake) {
dutycycle_now = conf.l_min_duty;
}
set_duty_cycle_ll(dutycycle_now);

View File

@ -96,8 +96,6 @@ extern volatile int mcpwm_vzero;
#define MCPWM_SWITCH_FREQUENCY_DC_MOTOR 25000 // The DC motor switching frequency
#define MCPWM_DEAD_TIME_CYCLES 80 // Dead time
#define MCPWM_RPM_TIMER_FREQ 1000000.0 // Frequency of the RPM measurement timer
#define MCPWM_MIN_DUTY_CYCLE 0.005 // Minimum duty cycle
#define MCPWM_MAX_DUTY_CYCLE 0.95 // Maximum duty cycle
#define MCPWM_RAMP_STEP 0.01 // Ramping step (1000 times/sec) at maximum duty cycle
#define MCPWM_RAMP_STEP_RPM_LIMIT 0.0005 // Ramping step when limiting the RPM
#define MCPWM_CURRENT_LIMIT_GAIN 2.0 // The error gain of the current limiting algorithm

View File

@ -103,7 +103,7 @@ static msg_t rx_thread(void *arg) {
mstate.bt_push = buttons & (1 << 2);
mstate.vbat = (float)buffer_get_int16(buf, &index) / 1000.0;
cdata.js_x = mstate.js_x;
cdata.js_x = 255 - mstate.js_x;
cdata.js_y = mstate.js_y;
cdata.bt_c = mstate.bt_c;
cdata.bt_z = mstate.bt_z;

View File

@ -26,48 +26,54 @@
#include "packet.h"
#include "crc.h"
// Settings
#define RX_TIMEOUT 2
#define PACKET_HANDLERS 2
typedef struct {
volatile unsigned char rx_state;
volatile unsigned char rx_timeout;
void(*send_func)(unsigned char *data, unsigned char len);
void(*process_func)(unsigned char *data, unsigned char len);
unsigned char payload_length;
unsigned char rx_buffer[256];
unsigned char rx_data_ptr;
void(*send_func)(unsigned char *data, unsigned int len);
void(*process_func)(unsigned char *data, unsigned int len);
unsigned int payload_length;
unsigned char rx_buffer[PACKET_MAX_PL_LEN];
unsigned char tx_buffer[PACKET_MAX_PL_LEN + 6];
unsigned int rx_data_ptr;
unsigned char crc_low;
unsigned char crc_high;
} PACKET_STATE_t;
static PACKET_STATE_t handler_states[PACKET_HANDLERS];
void packet_init(void (*s_func)(unsigned char *data, unsigned char len),
void (*p_func)(unsigned char *data, unsigned char len), int handler_num) {
void packet_init(void (*s_func)(unsigned char *data, unsigned int len),
void (*p_func)(unsigned char *data, unsigned 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 char len, int handler_num) {
uint8_t data_buffer[256];
void packet_send_packet(unsigned char *data, unsigned int len, int handler_num) {
if (len > PACKET_MAX_PL_LEN) {
return;
}
int b_ind = 0;
data_buffer[b_ind++] = 2;
data_buffer[b_ind++] = len;
if (len <= 256) {
handler_states[handler_num].tx_buffer[b_ind++] = 2;
handler_states[handler_num].tx_buffer[b_ind++] = len;
} else {
handler_states[handler_num].tx_buffer[b_ind++] = 3;
handler_states[handler_num].tx_buffer[b_ind++] = len >> 8;
handler_states[handler_num].tx_buffer[b_ind++] = len & 0xFF;
}
for(int i = 0;i < len;i++) {
data_buffer[b_ind++] = data[i];
for(unsigned int i = 0;i < len;i++) {
handler_states[handler_num].tx_buffer[b_ind++] = data[i];
}
unsigned short crc = crc16(data, len);
data_buffer[b_ind++] = (uint8_t)(crc >> 8);
data_buffer[b_ind++] = (uint8_t)(crc & 0xFF);
data_buffer[b_ind++] = 3;
handler_states[handler_num].tx_buffer[b_ind++] = (uint8_t)(crc >> 8);
handler_states[handler_num].tx_buffer[b_ind++] = (uint8_t)(crc & 0xFF);
handler_states[handler_num].tx_buffer[b_ind++] = 3;
if (handler_states[handler_num].send_func) {
handler_states[handler_num].send_func(data_buffer, len + 5);
handler_states[handler_num].send_func(handler_states[handler_num].tx_buffer, b_ind);
}
}
@ -88,41 +94,59 @@ void packet_process_byte(uint8_t rx_data, int handler_num) {
switch (handler_states[handler_num].rx_state) {
case 0:
if (rx_data == 2) {
handler_states[handler_num].rx_state++;
handler_states[handler_num].rx_timeout = RX_TIMEOUT;
// 1 byte PL len
handler_states[handler_num].rx_state += 2;
handler_states[handler_num].rx_timeout = PACKET_RX_TIMEOUT;
handler_states[handler_num].rx_data_ptr = 0;
handler_states[handler_num].payload_length = 0;
} else if (rx_data == 3) {
// 2 byte PL len
handler_states[handler_num].rx_state++;
handler_states[handler_num].rx_timeout = PACKET_RX_TIMEOUT;
handler_states[handler_num].rx_data_ptr = 0;
handler_states[handler_num].payload_length = 0;
} else {
handler_states[handler_num].rx_state = 0;
}
break;
case 1:
handler_states[handler_num].payload_length = rx_data;
handler_states[handler_num].payload_length = (unsigned int)rx_data << 8;
handler_states[handler_num].rx_state++;
handler_states[handler_num].rx_timeout = RX_TIMEOUT;
handler_states[handler_num].rx_timeout = PACKET_RX_TIMEOUT;
break;
case 2:
handler_states[handler_num].payload_length |= (unsigned int)rx_data;
if (handler_states[handler_num].payload_length <= PACKET_MAX_PL_LEN) {
handler_states[handler_num].rx_state++;
handler_states[handler_num].rx_timeout = PACKET_RX_TIMEOUT;
} else {
handler_states[handler_num].rx_state = 0;
}
break;
case 3:
handler_states[handler_num].rx_buffer[handler_states[handler_num].rx_data_ptr++] = rx_data;
if (handler_states[handler_num].rx_data_ptr == handler_states[handler_num].payload_length) {
handler_states[handler_num].rx_state++;
}
handler_states[handler_num].rx_timeout = RX_TIMEOUT;
break;
case 3:
handler_states[handler_num].crc_high = rx_data;
handler_states[handler_num].rx_state++;
handler_states[handler_num].rx_timeout = RX_TIMEOUT;
handler_states[handler_num].rx_timeout = PACKET_RX_TIMEOUT;
break;
case 4:
handler_states[handler_num].crc_low = rx_data;
handler_states[handler_num].crc_high = rx_data;
handler_states[handler_num].rx_state++;
handler_states[handler_num].rx_timeout = RX_TIMEOUT;
handler_states[handler_num].rx_timeout = PACKET_RX_TIMEOUT;
break;
case 5:
handler_states[handler_num].crc_low = rx_data;
handler_states[handler_num].rx_state++;
handler_states[handler_num].rx_timeout = PACKET_RX_TIMEOUT;
break;
case 6:
if (rx_data == 3) {
if (crc16(handler_states[handler_num].rx_buffer, handler_states[handler_num].payload_length)
== ((unsigned short)handler_states[handler_num].crc_high << 8

View File

@ -27,11 +27,16 @@
#include <stdint.h>
// Settings
#define PACKET_RX_TIMEOUT 2
#define PACKET_HANDLERS 2
#define PACKET_MAX_PL_LEN 1024
// Functions
void packet_init(void (*s_func)(unsigned char *data, unsigned char len),
void (*p_func)(unsigned char *data, unsigned char len), int handler_num);
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_process_byte(uint8_t rx_data, int handler_num);
void packet_timerfunc(void);
void packet_send_packet(unsigned char *data, unsigned char len, int handler_num);
void packet_send_packet(unsigned char *data, unsigned int len, int handler_num);
#endif /* PACKET_H_ */

43
utils.c
View File

@ -25,7 +25,6 @@
#include "utils.h"
#include "ch.h"
#include "hal.h"
#include "mcpwm.h"
#include <math.h>
// Private variables
@ -151,45 +150,3 @@ void utils_sys_unlock_cnt(void) {
}
}
}
/**
* Stop the system and jump to the bootloader.
*/
void utils_jump_to_bootloader(void) {
typedef void (*pFunction)(void);
mcpwm_release_motor();
usbDisconnectBus(&USBD1);
usbStop(&USBD1);
// Disable watchdog
RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, DISABLE);
chSysDisable();
pFunction jump_to_bootloader;
// Variable that will be loaded with the start address of the application
vu32* jump_address;
const vu32* bootloader_address = (vu32*)0x080E0000;
// Get jump address from application vector table
jump_address = (vu32*) bootloader_address[1];
// Load this address into function pointer
jump_to_bootloader = (pFunction) jump_address;
// Clear pending interrupts
SCB_ICSR = ICSR_PENDSVCLR;
// Disable all interrupts
for(int i = 0;i < 8;i++) {
NVIC->ICER[i] = NVIC->IABR[i];
}
// Set stack pointer
__set_MSP((u32) (bootloader_address[0]));
// Jump to the bootloader
jump_to_bootloader();
}

View File

@ -34,7 +34,6 @@ void utils_deadband(float *value, float tres, float max);
float utils_angle_difference(float angle1, float angle2);
void utils_sys_lock_cnt(void);
void utils_sys_unlock_cnt(void);
void utils_jump_to_bootloader(void);
// Return the sign of the argument. -1 if negative, 1 if zero or positive.
#define SIGN(x) ((x<0)?-1:1)