Merge remote-tracking branch 'vedderb/master'

This commit is contained in:
Mitch Lustig 2019-09-21 00:04:53 -07:00
commit 6c25041a91
18 changed files with 1104 additions and 5 deletions

View File

@ -270,6 +270,68 @@
#define APPCONF_NRF_SEND_CRC_ACK true
#endif
// Balance app
#ifndef APPCONF_BALANCE_KP
#define APPCONF_BALANCE_KP 0.0
#endif
#ifndef APPCONF_BALANCE_KI
#define APPCONF_BALANCE_KI 0.0
#endif
#ifndef APPCONF_BALANCE_KD
#define APPCONF_BALANCE_KD 0.0
#endif
#ifndef APPCONF_BALANCE_HERTZ
#define APPCONF_BALANCE_HERTZ 1000
#endif
#ifndef APPCONF_BALANCE_M_AXIS
#define APPCONF_BALANCE_M_AXIS 0
#endif
#ifndef APPCONF_BALANCE_C_AXIS
#define APPCONF_BALANCE_C_AXIS 1
#endif
#ifndef APPCONF_BALANCE_M_FAULT
#define APPCONF_BALANCE_M_FAULT 20
#endif
#ifndef APPCONF_BALANCE_C_FAULT
#define APPCONF_BALANCE_C_FAULT 45
#endif
#ifndef APPCONF_BALANCE_USE_SWITCHES
#define APPCONF_BALANCE_USE_SWITCHES false
#endif
#ifndef APPCONF_BALANCE_OVERSPEED_DUTY
#define APPCONF_BALANCE_OVERSPEED_DUTY 0.9
#endif
#ifndef APPCONF_BALANCE_TILTBACK_DUTY
#define APPCONF_BALANCE_TILTBACK_DUTY 0.75
#endif
#ifndef APPCONF_BALANCE_TILTBACK_ANGLE
#define APPCONF_BALANCE_TILTBACK_ANGLE 15.0
#endif
#ifndef APPCONF_BALANCE_TILTBACK_SPEED
#define APPCONF_BALANCE_TILTBACK_SPEED 5.0
#endif
#ifndef APPCONF_BALANCE_TILTBACK_HIGH_V
#define APPCONF_BALANCE_TILTBACK_HIGH_V 100.0
#endif
#ifndef APPCONF_BALANCE_TILTBACK_LOW_V
#define APPCONF_BALANCE_TILTBACK_LOW_V 0.0
#endif
#ifndef APPCONF_BALANCE_STARTUP_M_TOLERANCE
#define APPCONF_BALANCE_STARTUP_M_TOLERANCE 20.0
#endif
#ifndef APPCONF_BALANCE_STARTUP_C_TOLERANCE
#define APPCONF_BALANCE_STARTUP_C_TOLERANCE 8.0
#endif
#ifndef APPCONF_BALANCE_STARTUP_SPEED
#define APPCONF_BALANCE_STARTUP_SPEED 30.0
#endif
#ifndef APPCONF_BALANCE_DEADZONE
#define APPCONF_BALANCE_DEADZONE 0.0
#endif
#ifndef APPCONF_BALANCE_CURRENT_BOOST
#define APPCONF_BALANCE_CURRENT_BOOST 0.0
#endif
// IMU
#ifndef APPCONF_IMU_TYPE
#define APPCONF_IMU_TYPE IMU_TYPE_INTERNAL

View File

@ -52,6 +52,7 @@ void app_set_configuration(app_configuration *conf) {
app_adc_stop();
app_uartcomm_stop();
app_nunchuk_stop();
app_balance_stop();
if (!conf_general_permanent_nrf_found) {
nrf_driver_stop();
@ -67,6 +68,9 @@ void app_set_configuration(app_configuration *conf) {
imu_init(&conf->imu_conf);
// Configure balance app before starting it.
app_balance_configure(&appconf.app_balance_conf, &appconf.imu_conf);
switch (appconf.app_to_use) {
case APP_PPM:
app_ppm_start();
@ -97,6 +101,10 @@ void app_set_configuration(app_configuration *conf) {
app_nunchuk_start();
break;
case APP_BALANCE:
app_balance_start();
break;
case APP_NRF:
if (!conf_general_permanent_nrf_found) {
nrf_driver_init();

View File

@ -54,6 +54,18 @@ void app_nunchuk_configure(chuk_config *conf);
float app_nunchuk_get_decoded_chuk(void);
void app_nunchuk_update_output(chuck_data *data);
void app_balance_start(void);
void app_balance_stop(void);
void app_balance_configure(balance_config *conf, imu_config *conf2);
float app_balance_get_pid_output(void);
float app_balance_get_m_angle(void);
float app_balance_get_c_angle(void);
uint32_t app_balance_get_diff_time(void);
float app_balance_get_motor_current(void);
float app_balance_get_motor_position(void);
uint16_t app_balance_get_state(void);
uint16_t app_balance_get_switch_value(void);
// Custom apps
void app_custom_start(void);
void app_custom_stop(void);

339
applications/app_balance.c Normal file
View File

@ -0,0 +1,339 @@
/*
Copyright 2019 Mitch Lustig
This file is part of the VESC firmware.
The VESC firmware is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
The VESC firmware is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "conf_general.h"
#include "ch.h" // ChibiOS
#include "hal.h" // ChibiOS HAL
#include "mc_interface.h" // Motor control functions
#include "hw.h" // Pin mapping on this hardware
#include "timeout.h" // To reset the timeout
#include "commands.h"
#include "imu/imu.h"
#include "imu/ahrs.h"
#include "utils.h"
#include "datatypes.h"
#include <math.h>
// Data type
typedef enum {
STARTUP = 0,
RUNNING,
FAULT,
DEAD
} BalanceState;
typedef enum {
CENTERING = 0,
TILTBACK
} SetpointAdjustmentType;
// Balance thread
static THD_FUNCTION(balance_thread, arg);
static THD_WORKING_AREA(balance_thread_wa, 2048); // 2kb stack for this thread
static volatile balance_config balance_conf;
static volatile imu_config imu_conf;
static thread_t *app_thread;
// Values used in loop
static BalanceState state;
static float m_angle, c_angle;
static float proportional, integral, derivative;
static float last_proportional;
static float pid_value;
static float setpoint, setpoint_target;
static SetpointAdjustmentType setpointAdjustmentType;
static float startup_step_size, tiltback_step_size;
static systime_t current_time, last_time, diff_time;
static systime_t startup_start_time, startup_diff_time;
static uint16_t switches_value;
// Values read to pass in app data to GUI
static float motor_current;
static float motor_position;
void app_balance_configure(balance_config *conf, imu_config *conf2) {
balance_conf = *conf;
imu_conf = *conf2;
}
void app_balance_start(void) {
// Reset all Values
state = STARTUP;
m_angle = 0;
c_angle = 0;
switches_value = 0;
proportional = 0;
integral = 0;
derivative = 0;
last_proportional = 0;
pid_value = 0;
setpoint = 0;
setpoint_target = 0;
setpointAdjustmentType = CENTERING;
startup_step_size = 0;
tiltback_step_size = 0;
current_time = 0;
last_time = 0;
diff_time = 0;
startup_start_time = 0;
startup_diff_time = 0;
#ifdef HW_SPI_PORT_SCK
// Configure pins
if(balance_conf.use_switches){
palSetPadMode(HW_SPI_PORT_SCK, HW_SPI_PIN_SCK, PAL_MODE_INPUT_PULLDOWN);
palSetPadMode(HW_SPI_PORT_MISO, HW_SPI_PIN_MISO, PAL_MODE_INPUT_PULLDOWN);
}
#endif
// Start the balance thread
app_thread = chThdCreateStatic(balance_thread_wa, sizeof(balance_thread_wa), NORMALPRIO, balance_thread, NULL);
}
void app_balance_stop(void) {
if(app_thread != NULL){
chThdTerminate(app_thread);
chThdWait(app_thread);
}
mc_interface_set_current(0);
}
float app_balance_get_pid_output(void) {
return pid_value;
}
float app_balance_get_m_angle(void) {
return m_angle;
}
float app_balance_get_c_angle(void) {
return c_angle;
}
uint32_t app_balance_get_diff_time(void) {
return ST2US(diff_time);
}
float app_balance_get_motor_current(void) {
return motor_current;
}
float app_balance_get_motor_position(void) {
return motor_position;
}
uint16_t app_balance_get_state(void) {
return state;
}
uint16_t app_balance_get_switch_value(void) {
return switches_value;
}
float get_setpoint_adjustment_step_size(void){
switch(setpointAdjustmentType){
case (CENTERING):
return startup_step_size;
case (TILTBACK):
return tiltback_step_size;
}
return 0;
}
float apply_deadzone(float error){
if(balance_conf.deadzone == 0){
return error;
}
if(error < balance_conf.deadzone && error > -balance_conf.deadzone){
return 0;
} else if(error > balance_conf.deadzone){
return error - balance_conf.deadzone;
} else {
return error + balance_conf.deadzone;
}
}
static THD_FUNCTION(balance_thread, arg) {
(void)arg;
chRegSetThreadName("APP_BALANCE");
// Do one off config
startup_step_size = balance_conf.startup_speed / balance_conf.hertz;
tiltback_step_size = balance_conf.tiltback_speed / balance_conf.hertz;
state = STARTUP;
setpointAdjustmentType = CENTERING;
while (!chThdShouldTerminateX()) {
// Update times
current_time = chVTGetSystemTimeX();
if(last_time == 0){
last_time = current_time;
}
diff_time = current_time - last_time;
last_time = current_time;
// Read values for GUI
motor_current = mc_interface_get_tot_current_directional_filtered();
motor_position = mc_interface_get_pid_pos_now();
// Get the values we want
switch(balance_conf.m_axis){
case (PITCH):
m_angle = imu_get_pitch() * 180.0f / M_PI;;
break;
case (ROLL):
m_angle = imu_get_roll() * 180.0f / M_PI;
break;
case (YAW):
m_angle = imu_get_yaw() * 180.0f / M_PI;
break;
}
switch(balance_conf.c_axis){
case (PITCH):
c_angle = imu_get_pitch() * 180.0f / M_PI;;
break;
case (ROLL):
c_angle = imu_get_roll() * 180.0f / M_PI;
break;
case (YAW):
c_angle = imu_get_yaw() * 180.0f / M_PI;
break;
}
if(!balance_conf.use_switches){
switches_value = 2;
}else{
switches_value = 0;
#ifdef HW_SPI_PORT_SCK
if(palReadPad(HW_SPI_PORT_SCK, HW_SPI_PIN_SCK)){
switches_value += 1;
}
if(palReadPad(HW_SPI_PORT_MISO, HW_SPI_PIN_MISO)){
switches_value += 1;
}
#endif
}
// State based logic
switch(state){
case (STARTUP):
while(!imu_startup_done()){
chThdSleepMilliseconds(50);
}
state = FAULT;
startup_start_time = 0;
startup_diff_time = 0;
break;
case (RUNNING):
// Check for overspeed
if(fabsf(mc_interface_get_duty_cycle_now()) > balance_conf.overspeed_duty){
state = DEAD;
}
// Check for fault
if(
fabsf(m_angle) > balance_conf.m_fault || // Balnce axis tip over
fabsf(c_angle) > balance_conf.c_fault || // Cross axis tip over
app_balance_get_switch_value() == 0 || // Switch fully open
(app_balance_get_switch_value() == 1 && fabsf(mc_interface_get_duty_cycle_now()) < 0.003) // Switch partially open and stopped
){
state = FAULT;
}
// Over speed tilt back safety
if(fabsf(mc_interface_get_duty_cycle_now()) > balance_conf.tiltback_duty ||
(fabsf(mc_interface_get_duty_cycle_now()) > 0.05 && GET_INPUT_VOLTAGE() > balance_conf.tiltback_high_voltage) ||
(fabsf(mc_interface_get_duty_cycle_now()) > 0.05 && GET_INPUT_VOLTAGE() < balance_conf.tiltback_low_voltage)){
if(mc_interface_get_duty_cycle_now() > 0){
setpoint_target = balance_conf.tiltback_angle;
} else {
setpoint_target = -balance_conf.tiltback_angle;
}
setpointAdjustmentType = TILTBACK;
}else{
setpoint_target = 0;
}
// Adjust setpoint
if(setpoint != setpoint_target){
// If we are less than one step size away, go all the way
if(fabsf(setpoint_target - setpoint) < get_setpoint_adjustment_step_size()){
setpoint = setpoint_target;
}else if (setpoint_target - setpoint > 0){
setpoint += get_setpoint_adjustment_step_size();
}else{
setpoint -= get_setpoint_adjustment_step_size();
}
}
// Do PID maths
proportional = setpoint - m_angle;
// Apply deadzone
proportional = apply_deadzone(proportional);
// Resume real PID maths
integral = integral + proportional;
derivative = proportional - last_proportional;
pid_value = (balance_conf.kp * proportional) + (balance_conf.ki * integral) + (balance_conf.kd * derivative);
last_proportional = proportional;
// Apply current boost
if(pid_value > 0){
pid_value += balance_conf.current_boost;
}else if(pid_value < 0){
pid_value -= balance_conf.current_boost;
}
// Reset the timeout
timeout_reset();
// Output to motor
if(pid_value == 0){
mc_interface_release_motor();
}else {
mc_interface_set_current(pid_value);
}
break;
case (FAULT):
// Check for valid startup position and switch state
if(fabsf(m_angle) < balance_conf.startup_m_tolerance && fabsf(c_angle) < balance_conf.startup_c_tolerance && app_balance_get_switch_value() == 2){
setpoint = m_angle;
setpoint_target = 0;
setpointAdjustmentType = CENTERING;
state = RUNNING;
break;
}
// Disable output
mc_interface_set_current(0);
break;
case (DEAD):
// Disable output
mc_interface_set_current(0);
break;
}
// Delay between loops
chThdSleepMicroseconds((int)((1000.0 / balance_conf.hertz) * 1000.0));
}
// Disable output
mc_interface_set_current(0);
}

View File

@ -4,6 +4,7 @@ APPSRC = applications/app.c \
applications/app_sten.c \
applications/app_uartcomm.c \
applications/app_nunchuk.c \
applications/app_balance.c \
applications/app_custom.c
APPINC = applications

Binary file not shown.

Binary file not shown.

View File

@ -327,3 +327,37 @@ cd $FWPATH
make clean
cd $DIR
#################### HW A200S 2.1 ########################
COPYDIR=A200S_V21
rm -f $COPYDIR/*
# default
cd $FWPATH
touch conf_general.h
make -j8 build_args='-DHW_SOURCE=\"hw_a200s_v2.c\" -DHW_HEADER=\"hw_a200s_v2.h\" -DHW_A200S_REV_21' USE_VERBOSE_COMPILE=no
cd $DIR
cp $FWPATH/build/BLDC_4_ChibiOS.bin $COPYDIR/VESC_default.bin
# Clean
cd $FWPATH
make clean
cd $DIR
#################### HW A200S 2.2 ########################
COPYDIR=A200S_V22
rm -f $COPYDIR/*
# default
cd $FWPATH
touch conf_general.h
make -j8 build_args='-DHW_SOURCE=\"hw_a200s_v2.c\" -DHW_HEADER=\"hw_a200s_v2.h\" ' USE_VERBOSE_COMPILE=no
cd $DIR
cp $FWPATH/build/BLDC_4_ChibiOS.bin $COPYDIR/VESC_default.bin
# Clean
cd $FWPATH
make clean
cd $DIR

View File

@ -510,6 +510,21 @@ void commands_process_packet(unsigned char *data, unsigned int len,
reply_func(send_buffer, ind);
} break;
case COMM_GET_DECODED_BALANCE: {
int32_t ind = 0;
uint8_t send_buffer[50];
send_buffer[ind++] = COMM_GET_DECODED_BALANCE;
buffer_append_int32(send_buffer, (int32_t)(app_balance_get_pid_output() * 1000000.0), &ind);
buffer_append_int32(send_buffer, (int32_t)(app_balance_get_m_angle() * 1000000.0), &ind);
buffer_append_int32(send_buffer, (int32_t)(app_balance_get_c_angle() * 1000000.0), &ind);
buffer_append_uint32(send_buffer, app_balance_get_diff_time(), &ind);
buffer_append_int32(send_buffer, (int32_t)(app_balance_get_motor_current() * 1000000.0), &ind);
buffer_append_int32(send_buffer, (int32_t)(app_balance_get_motor_position() * 1000000.0), &ind);
buffer_append_uint16(send_buffer, app_balance_get_state(), &ind);
buffer_append_uint16(send_buffer, app_balance_get_switch_value(), &ind);
reply_func(send_buffer, ind);
} break;
case COMM_FORWARD_CAN:
comm_can_send_buffer(data[0], data + 1, len - 1, 0);
break;

View File

@ -114,6 +114,9 @@
//#define HW_SOURCE "hw_hd.c"
//#define HW_HEADER "hw_hd.h"
//#define HW_SOURCE "hw_a200s_v2.c"
//#define HW_HEADER "hw_a200s_v2.h"
#endif
#ifndef HW_SOURCE

View File

@ -223,6 +223,26 @@ int32_t confgenerator_serialize_appconf(uint8_t *buffer, const app_configuration
buffer[ind++] = (uint8_t)conf->app_nrf_conf.address[1];
buffer[ind++] = (uint8_t)conf->app_nrf_conf.address[2];
buffer[ind++] = conf->app_nrf_conf.send_crc_ack;
buffer_append_float32_auto(buffer, conf->app_balance_conf.kp, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.ki, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.kd, &ind);
buffer_append_uint16(buffer, conf->app_balance_conf.hertz, &ind);
buffer[ind++] = conf->app_balance_conf.m_axis;
buffer[ind++] = conf->app_balance_conf.c_axis;
buffer_append_float32_auto(buffer, conf->app_balance_conf.m_fault, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.c_fault, &ind);
buffer[ind++] = conf->app_balance_conf.use_switches;
buffer_append_float32_auto(buffer, conf->app_balance_conf.overspeed_duty, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.tiltback_duty, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.tiltback_angle, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.tiltback_speed, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.tiltback_high_voltage, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.tiltback_low_voltage, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.startup_m_tolerance, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.startup_c_tolerance, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.startup_speed, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.deadzone, &ind);
buffer_append_float32_auto(buffer, conf->app_balance_conf.current_boost, &ind);
buffer[ind++] = conf->imu_conf.type;
buffer[ind++] = conf->imu_conf.mode;
buffer_append_uint16(buffer, conf->imu_conf.sample_rate_hz, &ind);
@ -472,6 +492,26 @@ bool confgenerator_deserialize_appconf(const uint8_t *buffer, app_configuration
conf->app_nrf_conf.address[1] = buffer[ind++];
conf->app_nrf_conf.address[2] = buffer[ind++];
conf->app_nrf_conf.send_crc_ack = buffer[ind++];
conf->app_balance_conf.kp = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.ki = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.kd = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.hertz = buffer_get_uint16(buffer, &ind);
conf->app_balance_conf.m_axis = buffer[ind++];
conf->app_balance_conf.c_axis = buffer[ind++];
conf->app_balance_conf.m_fault = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.c_fault = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.use_switches = buffer[ind++];
conf->app_balance_conf.overspeed_duty = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.tiltback_duty = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.tiltback_angle = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.tiltback_speed = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.tiltback_high_voltage = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.tiltback_low_voltage = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.startup_m_tolerance = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.startup_c_tolerance = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.startup_speed = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.deadzone = buffer_get_float32_auto(buffer, &ind);
conf->app_balance_conf.current_boost = buffer_get_float32_auto(buffer, &ind);
conf->imu_conf.type = buffer[ind++];
conf->imu_conf.mode = buffer[ind++];
conf->imu_conf.sample_rate_hz = buffer_get_uint16(buffer, &ind);
@ -705,6 +745,26 @@ void confgenerator_set_defaults_appconf(app_configuration *conf) {
conf->app_nrf_conf.address[1] = APPCONF_NRF_ADDR_B1;
conf->app_nrf_conf.address[2] = APPCONF_NRF_ADDR_B2;
conf->app_nrf_conf.send_crc_ack = APPCONF_NRF_SEND_CRC_ACK;
conf->app_balance_conf.kp = APPCONF_BALANCE_KP;
conf->app_balance_conf.ki = APPCONF_BALANCE_KI;
conf->app_balance_conf.kd = APPCONF_BALANCE_KD;
conf->app_balance_conf.hertz = APPCONF_BALANCE_HERTZ;
conf->app_balance_conf.m_axis = APPCONF_BALANCE_M_AXIS;
conf->app_balance_conf.c_axis = APPCONF_BALANCE_C_AXIS;
conf->app_balance_conf.m_fault = APPCONF_BALANCE_M_FAULT;
conf->app_balance_conf.c_fault = APPCONF_BALANCE_C_FAULT;
conf->app_balance_conf.use_switches = APPCONF_BALANCE_USE_SWITCHES;
conf->app_balance_conf.overspeed_duty = APPCONF_BALANCE_OVERSPEED_DUTY;
conf->app_balance_conf.tiltback_duty = APPCONF_BALANCE_TILTBACK_DUTY;
conf->app_balance_conf.tiltback_angle = APPCONF_BALANCE_TILTBACK_ANGLE;
conf->app_balance_conf.tiltback_speed = APPCONF_BALANCE_TILTBACK_SPEED;
conf->app_balance_conf.tiltback_high_voltage = APPCONF_BALANCE_TILTBACK_HIGH_V;
conf->app_balance_conf.tiltback_low_voltage = APPCONF_BALANCE_TILTBACK_LOW_V;
conf->app_balance_conf.startup_m_tolerance = APPCONF_BALANCE_STARTUP_M_TOLERANCE;
conf->app_balance_conf.startup_c_tolerance = APPCONF_BALANCE_STARTUP_C_TOLERANCE;
conf->app_balance_conf.startup_speed = APPCONF_BALANCE_STARTUP_SPEED;
conf->app_balance_conf.deadzone = APPCONF_BALANCE_DEADZONE;
conf->app_balance_conf.current_boost = APPCONF_BALANCE_CURRENT_BOOST;
conf->imu_conf.type = APPCONF_IMU_TYPE;
conf->imu_conf.mode = APPCONF_IMU_AHRS_MODE;
conf->imu_conf.sample_rate_hz = APPCONF_IMU_SAMPLE_RATE_HZ;

View File

@ -9,7 +9,7 @@
// Constants
#define MCCONF_SIGNATURE 503309878
#define APPCONF_SIGNATURE 583966563
#define APPCONF_SIGNATURE 3900592330
// Functions
int32_t confgenerator_serialize_mcconf(uint8_t *buffer, const mc_configuration *conf);

View File

@ -317,7 +317,8 @@ typedef enum {
APP_ADC_UART,
APP_NUNCHUK,
APP_NRF,
APP_CUSTOM
APP_CUSTOM,
APP_BALANCE
} app_use;
// Throttle curve mode
@ -488,6 +489,36 @@ typedef struct {
bool send_crc_ack;
} nrf_config;
// External LED state
typedef enum {
PITCH = 0,
ROLL,
YAW
} AXIS;
typedef struct {
float kp;
float ki;
float kd;
uint16_t hertz;
AXIS m_axis;
AXIS c_axis;
float m_fault;
float c_fault;
bool use_switches;
float overspeed_duty;
float tiltback_duty;
float tiltback_angle;
float tiltback_speed;
float tiltback_high_voltage;
float tiltback_low_voltage;
float startup_m_tolerance;
float startup_c_tolerance;
float startup_speed;
float deadzone;
float current_boost;
} balance_config;
// CAN status modes
typedef enum {
CAN_STATUS_DISABLED = 0,
@ -575,6 +606,9 @@ typedef struct {
// NRF application settings
nrf_config app_nrf_conf;
// Balance application settings
balance_config app_balance_conf;
// IMU Settings
imu_config imu_conf;
} app_configuration;
@ -660,6 +694,7 @@ typedef enum {
COMM_PLOT_DATA,
COMM_PLOT_ADD_GRAPH,
COMM_PLOT_SET_GRAPH,
COMM_GET_DECODED_BALANCE,
} COMM_PACKET_ID;
// CAN commands

243
hwconf/hw_a200s_v2.c Normal file
View File

@ -0,0 +1,243 @@
/*
Copyright 2018 Benjamin Vedder benjamin@vedder.se
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "hw.h"
#include "ch.h"
#include "hal.h"
#include "stm32f4xx_conf.h"
#include "utils.h"
#include <math.h>
#include "mc_interface.h"
// Variables
static volatile bool i2c_running = false;
// I2C configuration
static const I2CConfig i2cfg = {
OPMODE_I2C,
100000,
STD_DUTY_CYCLE
};
void hw_init_gpio(void) {
// GPIO clock enable
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE);
// LEDs
palSetPadMode(LED_GREEN_GPIO, LED_GREEN_PIN,
PAL_MODE_OUTPUT_PUSHPULL |
PAL_STM32_OSPEED_HIGHEST);
palSetPadMode(LED_RED_GPIO, LED_RED_PIN,
PAL_MODE_OUTPUT_PUSHPULL |
PAL_STM32_OSPEED_HIGHEST);
// GPIOA Configuration: Channel 1 to 3 as alternate function push-pull
palSetPadMode(GPIOA, 8, PAL_MODE_ALTERNATE(GPIO_AF_TIM1) |
PAL_STM32_OSPEED_HIGHEST |
PAL_STM32_PUDR_FLOATING);
palSetPadMode(GPIOA, 9, PAL_MODE_ALTERNATE(GPIO_AF_TIM1) |
PAL_STM32_OSPEED_HIGHEST |
PAL_STM32_PUDR_FLOATING);
palSetPadMode(GPIOA, 10, PAL_MODE_ALTERNATE(GPIO_AF_TIM1) |
PAL_STM32_OSPEED_HIGHEST |
PAL_STM32_PUDR_FLOATING);
palSetPadMode(GPIOB, 13, PAL_MODE_ALTERNATE(GPIO_AF_TIM1) |
PAL_STM32_OSPEED_HIGHEST |
PAL_STM32_PUDR_FLOATING);
palSetPadMode(GPIOB, 14, PAL_MODE_ALTERNATE(GPIO_AF_TIM1) |
PAL_STM32_OSPEED_HIGHEST |
PAL_STM32_PUDR_FLOATING);
palSetPadMode(GPIOB, 15, PAL_MODE_ALTERNATE(GPIO_AF_TIM1) |
PAL_STM32_OSPEED_HIGHEST |
PAL_STM32_PUDR_FLOATING);
// Hall sensors
palSetPadMode(HW_HALL_ENC_GPIO1, HW_HALL_ENC_PIN1, PAL_MODE_INPUT_PULLUP);
palSetPadMode(HW_HALL_ENC_GPIO2, HW_HALL_ENC_PIN2, PAL_MODE_INPUT_PULLUP);
palSetPadMode(HW_HALL_ENC_GPIO3, HW_HALL_ENC_PIN3, PAL_MODE_INPUT_PULLUP);
// ADC Pins
palSetPadMode(GPIOA, 0, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOA, 1, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOA, 2, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOA, 3, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOA, 5, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOA, 6, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOB, 0, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOB, 1, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOC, 0, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOC, 1, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOC, 2, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOC, 3, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOC, 4, PAL_MODE_INPUT_ANALOG);
palSetPadMode(GPIOC, 5, PAL_MODE_INPUT_ANALOG);
}
void hw_setup_adc_channels(void) {
// ADC1 regular channels
ADC_RegularChannelConfig(ADC1, ADC_Channel_0, 1, ADC_SampleTime_15Cycles); // 0 SENS1
ADC_RegularChannelConfig(ADC1, ADC_Channel_10, 2, ADC_SampleTime_15Cycles); // 3 CURR1
ADC_RegularChannelConfig(ADC1, ADC_Channel_5, 3, ADC_SampleTime_15Cycles); // 6 EXT
ADC_RegularChannelConfig(ADC1, ADC_Channel_14, 4, ADC_SampleTime_15Cycles); // 9 TEMP_MOTOR
ADC_RegularChannelConfig(ADC1, ADC_Channel_Vrefint, 5, ADC_SampleTime_15Cycles); // 12 VREFINT
ADC_RegularChannelConfig(ADC1, ADC_Channel_8, 6, ADC_SampleTime_15Cycles); // 15 TEMP_MOS_2
// ADC2 regular channels
ADC_RegularChannelConfig(ADC2, ADC_Channel_1, 1, ADC_SampleTime_15Cycles); // 1 SENS2
ADC_RegularChannelConfig(ADC2, ADC_Channel_11, 2, ADC_SampleTime_15Cycles); // 4 CURR2
ADC_RegularChannelConfig(ADC2, ADC_Channel_6, 3, ADC_SampleTime_15Cycles); // 7 EXT2
ADC_RegularChannelConfig(ADC2, ADC_Channel_15, 4, ADC_SampleTime_15Cycles); // 10 UNUSED
ADC_RegularChannelConfig(ADC2, ADC_Channel_0, 5, ADC_SampleTime_15Cycles); // 13 UNUSED
ADC_RegularChannelConfig(ADC2, ADC_Channel_9, 6, ADC_SampleTime_15Cycles); // 16 TEMP_MOS_3
// ADC3 regular channels
ADC_RegularChannelConfig(ADC3, ADC_Channel_2, 1, ADC_SampleTime_15Cycles); // 2 SENS3
ADC_RegularChannelConfig(ADC3, ADC_Channel_12, 2, ADC_SampleTime_15Cycles); // 5 CURR3
ADC_RegularChannelConfig(ADC3, ADC_Channel_3, 3, ADC_SampleTime_15Cycles); // 8 TEMP_MOS
ADC_RegularChannelConfig(ADC3, ADC_Channel_13, 4, ADC_SampleTime_15Cycles); // 11 VIN_SENS
ADC_RegularChannelConfig(ADC3, ADC_Channel_1, 5, ADC_SampleTime_15Cycles); // 14 UNUSED
ADC_RegularChannelConfig(ADC3, ADC_Channel_2, 6, ADC_SampleTime_15Cycles); // 17 UNUSED
// Injected channels
ADC_InjectedChannelConfig(ADC1, ADC_Channel_10, 1, ADC_SampleTime_15Cycles); // CURR1
ADC_InjectedChannelConfig(ADC2, ADC_Channel_11, 1, ADC_SampleTime_15Cycles); // CURR2
ADC_InjectedChannelConfig(ADC3, ADC_Channel_12, 1, ADC_SampleTime_15Cycles); // CURR3
ADC_InjectedChannelConfig(ADC1, ADC_Channel_10, 2, ADC_SampleTime_15Cycles); // CURR1
ADC_InjectedChannelConfig(ADC2, ADC_Channel_11, 2, ADC_SampleTime_15Cycles); // CURR2
ADC_InjectedChannelConfig(ADC3, ADC_Channel_12, 2, ADC_SampleTime_15Cycles); // CURR3
ADC_InjectedChannelConfig(ADC1, ADC_Channel_10, 3, ADC_SampleTime_15Cycles); // CURR1
ADC_InjectedChannelConfig(ADC2, ADC_Channel_11, 3, ADC_SampleTime_15Cycles); // CURR2
ADC_InjectedChannelConfig(ADC3, ADC_Channel_12, 3, ADC_SampleTime_15Cycles); // CURR3
}
void hw_start_i2c(void) {
i2cAcquireBus(&HW_I2C_DEV);
if (!i2c_running) {
palSetPadMode(HW_I2C_SCL_PORT, HW_I2C_SCL_PIN,
PAL_MODE_ALTERNATE(HW_I2C_GPIO_AF) |
PAL_STM32_OTYPE_OPENDRAIN |
PAL_STM32_OSPEED_MID1 |
PAL_STM32_PUDR_PULLUP);
palSetPadMode(HW_I2C_SDA_PORT, HW_I2C_SDA_PIN,
PAL_MODE_ALTERNATE(HW_I2C_GPIO_AF) |
PAL_STM32_OTYPE_OPENDRAIN |
PAL_STM32_OSPEED_MID1 |
PAL_STM32_PUDR_PULLUP);
i2cStart(&HW_I2C_DEV, &i2cfg);
i2c_running = true;
}
i2cReleaseBus(&HW_I2C_DEV);
}
void hw_stop_i2c(void) {
i2cAcquireBus(&HW_I2C_DEV);
if (i2c_running) {
palSetPadMode(HW_I2C_SCL_PORT, HW_I2C_SCL_PIN, PAL_MODE_INPUT);
palSetPadMode(HW_I2C_SDA_PORT, HW_I2C_SDA_PIN, PAL_MODE_INPUT);
i2cStop(&HW_I2C_DEV);
i2c_running = false;
}
i2cReleaseBus(&HW_I2C_DEV);
}
/**
* Try to restore the i2c bus
*/
void hw_try_restore_i2c(void) {
if (i2c_running) {
i2cAcquireBus(&HW_I2C_DEV);
palSetPadMode(HW_I2C_SCL_PORT, HW_I2C_SCL_PIN,
PAL_STM32_OTYPE_OPENDRAIN |
PAL_STM32_OSPEED_MID1 |
PAL_STM32_PUDR_PULLUP);
palSetPadMode(HW_I2C_SDA_PORT, HW_I2C_SDA_PIN,
PAL_STM32_OTYPE_OPENDRAIN |
PAL_STM32_OSPEED_MID1 |
PAL_STM32_PUDR_PULLUP);
palSetPad(HW_I2C_SCL_PORT, HW_I2C_SCL_PIN);
palSetPad(HW_I2C_SDA_PORT, HW_I2C_SDA_PIN);
chThdSleep(1);
for(int i = 0;i < 16;i++) {
palClearPad(HW_I2C_SCL_PORT, HW_I2C_SCL_PIN);
chThdSleep(1);
palSetPad(HW_I2C_SCL_PORT, HW_I2C_SCL_PIN);
chThdSleep(1);
}
// Generate start then stop condition
palClearPad(HW_I2C_SDA_PORT, HW_I2C_SDA_PIN);
chThdSleep(1);
palClearPad(HW_I2C_SCL_PORT, HW_I2C_SCL_PIN);
chThdSleep(1);
palSetPad(HW_I2C_SCL_PORT, HW_I2C_SCL_PIN);
chThdSleep(1);
palSetPad(HW_I2C_SDA_PORT, HW_I2C_SDA_PIN);
palSetPadMode(HW_I2C_SCL_PORT, HW_I2C_SCL_PIN,
PAL_MODE_ALTERNATE(HW_I2C_GPIO_AF) |
PAL_STM32_OTYPE_OPENDRAIN |
PAL_STM32_OSPEED_MID1 |
PAL_STM32_PUDR_PULLUP);
palSetPadMode(HW_I2C_SDA_PORT, HW_I2C_SDA_PIN,
PAL_MODE_ALTERNATE(HW_I2C_GPIO_AF) |
PAL_STM32_OTYPE_OPENDRAIN |
PAL_STM32_OSPEED_MID1 |
PAL_STM32_PUDR_PULLUP);
HW_I2C_DEV.state = I2C_STOP;
i2cStart(&HW_I2C_DEV, &i2cfg);
i2cReleaseBus(&HW_I2C_DEV);
}
}
float hw_a200s_get_temp(void) {
float t1 = (1.0 / ((logf(NTC_RES(ADC_Value[ADC_IND_TEMP_MOS]) / 10000.0) / 3900.0) + (1.0 / 298.15)) - 273.15);
float t2 = (1.0 / ((logf(NTC_RES(ADC_Value[ADC_IND_TEMP_MOS_2]) / 10000.0) / 3900.0) + (1.0 / 298.15)) - 273.15);
float t3 = (1.0 / ((logf(NTC_RES(ADC_Value[ADC_IND_TEMP_MOS_3]) / 10000.0) / 3900.0) + (1.0 / 298.15)) - 273.15);
float res = 0.0;
if (t1 > t2 && t1 > t3) {
res = t1;
} else if (t2 > t1 && t2 > t3) {
res = t2;
} else {
res = t3;
}
return res;
}

269
hwconf/hw_a200s_v2.h Normal file
View File

@ -0,0 +1,269 @@
/*
Copyright 2018 Benjamin Vedder benjamin@vedder.se
This file is part of the VESC firmware.
The VESC firmware is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
The VESC firmware is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef HW_A200S_V2_H_
#define HW_A200S_V2_H_
#ifdef HW_A200S_REV_21
#define HW_NAME "A200S V2.1"
#else
#define HW_NAME "A200S V2.2"
#endif
// HW properties
#define HW_HAS_3_SHUNTS
#define HW_HAS_PHASE_SHUNTS
// Macros
#define LED_GREEN_GPIO GPIOB
#define LED_GREEN_PIN 5
#define LED_RED_GPIO GPIOB
#define LED_RED_PIN 7
#define LED_GREEN_ON() palSetPad(LED_GREEN_GPIO, LED_GREEN_PIN)
#define LED_GREEN_OFF() palClearPad(LED_GREEN_GPIO, LED_GREEN_PIN)
#define LED_RED_ON() palSetPad(LED_RED_GPIO, LED_RED_PIN)
#define LED_RED_OFF() palClearPad(LED_RED_GPIO, LED_RED_PIN)
/*
* ADC Vector
*
* 0 (1): IN0 SENS1
* 1 (2): IN1 SENS2
* 2 (3): IN2 SENS3
* 3 (1): IN10 CURR1
* 4 (2): IN11 CURR2
* 5 (3): IN12 CURR3
* 6 (1): IN5 ADC_EXT1
* 7 (2): IN6 ADC_EXT2
* 8 (3): IN3 TEMP_MOS
* 9 (1): IN14 TEMP_MOTOR
* 10 (2): IN15 ADC_EXT3
* 11 (3): IN13 AN_IN
* 12 (1): Vrefint
* 13 (2): IN0 SENS1
* 14 (3): IN1 SENS2
* 15 (1): IN8 TEMP_MOS_2
* 16 (2): IN9 TEMP_MOS_3
* 17 (3): IN3 SENS3
*/
#define HW_ADC_CHANNELS 18
#define HW_ADC_INJ_CHANNELS 3
#define HW_ADC_NBR_CONV 6
// ADC Indexes
#define ADC_IND_SENS1 0
#define ADC_IND_SENS2 1
#define ADC_IND_SENS3 2
#define ADC_IND_CURR1 3
#define ADC_IND_CURR2 4
#define ADC_IND_CURR3 5
#define ADC_IND_VIN_SENS 11
#define ADC_IND_EXT 6
#define ADC_IND_EXT2 7
#define ADC_IND_TEMP_MOS 8
#define ADC_IND_TEMP_MOS_2 15
#define ADC_IND_TEMP_MOS_3 16
#define ADC_IND_TEMP_MOTOR 9
#define ADC_IND_VREFINT 12
// ADC macros and settings
// Component parameters (can be overridden)
#ifndef V_REG
#define V_REG 3.30
#endif
#ifndef VIN_R1
#define VIN_R1 56000.0
#endif
#ifndef VIN_R2
#define VIN_R2 2200.0
#endif
#ifndef CURRENT_AMP_GAIN
#define CURRENT_AMP_GAIN 20.0
#endif
#ifndef CURRENT_SHUNT_RES
#ifdef HW_A200S_REV_21
#define CURRENT_SHUNT_RES (0.0005 / 3.0) // Older versions have 3 shunts
#else
#define CURRENT_SHUNT_RES (0.0005 / 2.0)
#endif
#endif
// Input voltage
#define GET_INPUT_VOLTAGE() ((V_REG / 4095.0) * (float)ADC_Value[ADC_IND_VIN_SENS] * ((VIN_R1 + VIN_R2) / VIN_R2))
// NTC Termistors
#define NTC_RES(adc_val) ((4095.0 * 10000.0) / adc_val - 10000.0)
#define NTC_TEMP(adc_ind) hw_a200s_get_temp()
#define NTC_RES_MOTOR(adc_val) (10000.0 / ((4095.0 / (float)adc_val) - 1.0)) // Motor temp sensor on low side
#define NTC_TEMP_MOTOR(beta) (1.0 / ((logf(NTC_RES_MOTOR(ADC_Value[ADC_IND_TEMP_MOTOR]) / 10000.0) / beta) + (1.0 / 298.15)) - 273.15)
#define NTC_TEMP_MOS1() (1.0 / ((logf(NTC_RES(ADC_Value[ADC_IND_TEMP_MOS]) / 10000.0) / 3900.0) + (1.0 / 298.15)) - 273.15)
#define NTC_TEMP_MOS2() (1.0 / ((logf(NTC_RES(ADC_Value[ADC_IND_TEMP_MOS_2]) / 10000.0) / 3900.0) + (1.0 / 298.15)) - 273.15)
#define NTC_TEMP_MOS3() (1.0 / ((logf(NTC_RES(ADC_Value[ADC_IND_TEMP_MOS_3]) / 10000.0) / 3900.0) + (1.0 / 298.15)) - 273.15)
// Voltage on ADC channel
#define ADC_VOLTS(ch) ((float)ADC_Value[ch] / 4096.0 * V_REG)
// Double samples in beginning and end for positive current measurement.
// Useful when the shunt sense traces have noise that causes offset.
#ifndef CURR1_DOUBLE_SAMPLE
#define CURR1_DOUBLE_SAMPLE 0
#endif
#ifndef CURR2_DOUBLE_SAMPLE
#define CURR2_DOUBLE_SAMPLE 0
#endif
#ifndef CURR3_DOUBLE_SAMPLE
#define CURR3_DOUBLE_SAMPLE 0
#endif
// UART Peripheral
#define HW_UART_DEV SD3
#define HW_UART_GPIO_AF GPIO_AF_USART3
#define HW_UART_TX_PORT GPIOB
#define HW_UART_TX_PIN 10
#define HW_UART_RX_PORT GPIOB
#define HW_UART_RX_PIN 11
#ifdef HW75_300_REV_2
// Permanent UART Peripheral (for NRF51)
#define HW_UART_P_BAUD 115200
#define HW_UART_P_DEV SD4
#define HW_UART_P_GPIO_AF GPIO_AF_UART4
#define HW_UART_P_TX_PORT GPIOC
#define HW_UART_P_TX_PIN 10
#define HW_UART_P_RX_PORT GPIOC
#define HW_UART_P_RX_PIN 11
#endif
// ICU Peripheral for servo decoding
#define HW_USE_SERVO_TIM4
#define HW_ICU_TIMER TIM4
#define HW_ICU_TIM_CLK_EN() RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE)
#define HW_ICU_DEV ICUD4
#define HW_ICU_CHANNEL ICU_CHANNEL_1
#define HW_ICU_GPIO_AF GPIO_AF_TIM4
#define HW_ICU_GPIO GPIOB
#define HW_ICU_PIN 6
// I2C Peripheral
#define HW_I2C_DEV I2CD2
#define HW_I2C_GPIO_AF GPIO_AF_I2C2
#define HW_I2C_SCL_PORT GPIOB
#define HW_I2C_SCL_PIN 10
#define HW_I2C_SDA_PORT GPIOB
#define HW_I2C_SDA_PIN 11
// Hall/encoder pins
#define HW_HALL_ENC_GPIO1 GPIOC
#define HW_HALL_ENC_PIN1 6
#define HW_HALL_ENC_GPIO2 GPIOC
#define HW_HALL_ENC_PIN2 7
#define HW_HALL_ENC_GPIO3 GPIOC
#define HW_HALL_ENC_PIN3 8
#define HW_ENC_TIM TIM3
#define HW_ENC_TIM_AF GPIO_AF_TIM3
#define HW_ENC_TIM_CLK_EN() RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE)
#define HW_ENC_EXTI_PORTSRC EXTI_PortSourceGPIOC
#define HW_ENC_EXTI_PINSRC EXTI_PinSource8
#define HW_ENC_EXTI_CH EXTI9_5_IRQn
#define HW_ENC_EXTI_LINE EXTI_Line8
#define HW_ENC_EXTI_ISR_VEC EXTI9_5_IRQHandler
#define HW_ENC_TIM_ISR_CH TIM3_IRQn
#define HW_ENC_TIM_ISR_VEC TIM3_IRQHandler
// SPI pins
#define HW_SPI_DEV SPID1
#define HW_SPI_GPIO_AF GPIO_AF_SPI1
#define HW_SPI_PORT_NSS GPIOA
#define HW_SPI_PIN_NSS 4
#define HW_SPI_PORT_SCK GPIOA
#define HW_SPI_PIN_SCK 5
#define HW_SPI_PORT_MOSI GPIOA
#define HW_SPI_PIN_MOSI 7
#define HW_SPI_PORT_MISO GPIOA
#define HW_SPI_PIN_MISO 6
// Measurement macros
#define ADC_V_L1 ADC_Value[ADC_IND_SENS1]
#define ADC_V_L2 ADC_Value[ADC_IND_SENS2]
#define ADC_V_L3 ADC_Value[ADC_IND_SENS3]
#define ADC_V_ZERO (ADC_Value[ADC_IND_VIN_SENS] / 2)
// Macros
#define READ_HALL1() palReadPad(HW_HALL_ENC_GPIO1, HW_HALL_ENC_PIN1)
#define READ_HALL2() palReadPad(HW_HALL_ENC_GPIO2, HW_HALL_ENC_PIN2)
#define READ_HALL3() palReadPad(HW_HALL_ENC_GPIO3, HW_HALL_ENC_PIN3)
// Override dead time. See the stm32f4 reference manual for calculating this value.
#define HW_DEAD_TIME_NSEC 660.0
// Default setting overrides
#ifndef MCCONF_L_MAX_VOLTAGE
#define MCCONF_L_MAX_VOLTAGE 60.0 // Maximum input voltage (14S)
#endif
#ifndef MCCONF_L_MIN_VOLTAGE
#define MCCONF_L_MIN_VOLTAGE 18.0 // Minimum input voltage
#endif
#ifndef MCCONF_DEFAULT_MOTOR_TYPE
#define MCCONF_DEFAULT_MOTOR_TYPE MOTOR_TYPE_FOC
#endif
#ifndef MCCONF_FOC_F_SW
#define MCCONF_FOC_F_SW 30000.0
#endif
#ifndef MCCONF_L_MAX_ABS_CURRENT
#define MCCONF_L_MAX_ABS_CURRENT 180.0 // The maximum absolute current above which a fault is generated
#endif
#ifndef MCCONF_FOC_SAMPLE_V0_V7
#define MCCONF_FOC_SAMPLE_V0_V7 true // Run control loop in both v0 and v7 (requires phase shunts)
#endif
#ifndef MCCONF_L_IN_CURRENT_MAX
#define MCCONF_L_IN_CURRENT_MAX 100.0 // Input current limit in Amperes (Upper)
#endif
#ifndef MCCONF_L_IN_CURRENT_MIN
#define MCCONF_L_IN_CURRENT_MIN -20.0 // Input current limit in Amperes (Lower)
#endif
#ifndef MCCONF_CC_GAIN
#define MCCONF_CC_GAIN 0.0026 // Current controller error gain (Turn it down a bit)
#endif
// Setting limits
#define HW_LIM_CURRENT -200.0, 200.0
#define HW_LIM_CURRENT_IN -40.0, 180.0
#define HW_LIM_CURRENT_ABS 0.0, 300.0
#define HW_LIM_VIN 18.0, 70.0
#define HW_LIM_ERPM -200e3, 200e3
#define HW_LIM_DUTY_MIN 0.0, 0.1
#define HW_LIM_DUTY_MAX 0.0, 0.99
#define HW_LIM_TEMP_FET -40.0, 110.0
// HW-specific functions
float hw_a200s_get_temp(void);
#endif /* HW_A200S_V2_H_ */

View File

@ -40,6 +40,8 @@ static ICM20948_STATE m_icm20948_state;
static BMI_STATE m_bmi_state;
static imu_config m_settings;
static float m_gyro_offset[3] = {0.0};
static systime_t init_time;
static bool imu_ready;
// Private functions
static void imu_read_callback(float *accel, float *gyro, float *mag);
@ -53,8 +55,10 @@ void imu_init(imu_config *set) {
imu_stop();
ahrs_update_all_parameters(set->accel_confidence_decay, set->mahony_kp,
set->mahony_ki, set->madgwick_beta);
imu_ready = false;
init_time = chVTGetSystemTimeX();
ahrs_update_all_parameters(1.0, 0.3, 0.0, 2.0);
ahrs_init_attitude_info(&m_att);
mpu9150_set_rate_hz(set->sample_rate_hz);
@ -149,6 +153,10 @@ void imu_stop(void) {
bmi160_wrapper_stop(&m_bmi_state);
}
bool imu_startup_done(void) {
return imu_ready;
}
float imu_get_roll(void) {
return ahrs_get_roll(&m_att);
}
@ -215,6 +223,15 @@ static void imu_read_callback(float *accel, float *gyro, float *mag) {
float dt = timer_seconds_elapsed_since(last_time);
last_time = timer_time_now();
if(!imu_ready && ST2MS(chVTGetSystemTimeX() - init_time) > 1000){
ahrs_update_all_parameters(
m_settings.accel_confidence_decay,
m_settings.mahony_kp,
m_settings.mahony_ki,
m_settings.madgwick_beta);
imu_ready = true;
}
#ifdef IMU_FLIP
accel[0] *= -1.0;
accel[2] *= -1.0;

View File

@ -33,6 +33,7 @@ void imu_init_icm20948(stm32_gpio_t *sda_gpio, int sda_pin,
void imu_init_bmi160(stm32_gpio_t *sda_gpio, int sda_pin,
stm32_gpio_t *scl_gpio, int scl_pin);
void imu_stop(void);
bool imu_startup_done(void);
float imu_get_roll(void);
float imu_get_pitch(void);
float imu_get_yaw(void);

View File

@ -115,7 +115,7 @@ void mpu9150_init(stm32_gpio_t *sda_gpio, int sda_pin,
terminal_read_reg);
uint8_t res = read_single_reg(MPU9150_WHO_AM_I);
if (res == 0x68 || res == 0x69 || res == 0x71) {
if (res == 0x68 || res == 0x69 || res == 0x71 || res == 0x73) {
mpu_found = true;
if (!mpu_tp) {
should_stop = false;