SBB Micro
Source code for the self-balancing-bike microcontroller unit (Teensy 4.1-based). 🚀️
Loading...
Searching...
No Matches
config.h File Reference

General configurations for the source code. More...

Go to the source code of this file.

Macros

#define USED_SPI   SPI1
 Used SPI for sensor IO bus.
 
#define SPISPEED_IMU   10e6
 Speed of IMU SPI, max is 10e6.
 
#define SPISPEED_MAG   10e6
 Speed of MAG SPI, max is 10e6.
 
#define SPISPEED_DAC   10e6
 Speed of MAG SPI, max is 20e6.
 
#define UART_SPEEDSENS   Serial7
 Used UART for speed sensor bus.
 
#define BAUD_SPEEDSENS   4e6
 Baudrate of the UART for speed sensor bus.
 
#define UART_GPS   Serial2
 Used UART for GPS sensor bus.
 
#define BAUD_GPS_DEF   9600
 Default baudrate of GPS sensor (for init only).
 
#define BAUD_GPS   57600
 Actual baudrate of GPS sensor.
 
#define GPS_EXTBUFSIZE   128
 Extra buffer size for GPS sensor UART.
 
#define UART_SBUS   Serial8
 Used UART for SBUS communication. /details The UART used for the SBUS receiver. This runs with a baudrate of 100000. Initialization and setting is performed by the SBUS library.
 
#define ADC_RES   12
 ADC resolution (in bits).
 
#define ADC_AVERAGE   8
 ADC averaging 1/2/8/16 (samples). The more the averaging, the less the noise, but the more the reading time.
 
#define DAC_RES   12
 DAC resolution (in bits).
 
#define DAC_MTR_CH   0
 DAC channel for motor control.
 
#define DAC_THROTTLE_CH   1
 DAC channel for throttle control.
 
#define PWM_RES   12
 PWM resolution in bit (max is 14).
 
#define PWM_FREQ   5e3
 PWM frequency (max is 5kHz).
 
#define PWM_MIN   0.1F
 Minimum PWM value for motor current reference.
 
#define PWM_MAX   0.9F
 Maximum PWM value for motor current reference.
 
#define CS_IMU   0
 Chip select pin of IMU.
 
#define CS_MAG   2
 Chip select pin of MAG.
 
#define CS_DAC   3
 Chip select pin of DAC.
 
#define STEER_POS   A16
 Steer position analog input pin.
 
#define STEER_SPEED   A0
 Steer speed analog input pin.
 
#define ACT_CURR   A1
 Actual current analog input pin.
 
#define RIDER_TRQ   A17
 Rider torque analog input pin.
 
#define VOLTAGE   A15
 Battery voltage analog input pin.
 
#define FORK_DISP   A14
 Front fork displacement analog input pin.
 
#define PWM_PIN   18
 PWM pin for motor current reference.
 
#define MTR_EN_PIN   16
 Digital out for motor enable.
 
#define MTR_DIR_PIN   17
 Digital out for motor direction.
 
#define RELAY_EN_PIN   33
 Digital out for relay enable.
 
#define BR_DIR_PIN   21
 Digital out for brake motor direction.
 
#define BR_STEP_PIN   22
 Digital out for brake motor step.
 
#define BR_SLEEP_PIN   23
 Digital out for brake motor sleep.
 
#define ONOFF_STATE_PIN   36
 Digital in for on/off buttun state (diode between onoff and this).
 
#define SAMPLING_TIME   1e3
 Sampling time of the control loop (us).
 
#define SPEED_SAMPLING_FAC   1
 Sampling factor of speed sensor (expressed in units of SAMPLING_TIME).
 
#define IMU_SAMPLING_FAC   1
 Sampling factor of IMU (expressed in units of SAMPLING_TIME).
 
#define MAG_SAMPLING_FAC   5
 Sampling factor of magnetometer (expressed in units of SAMPLING_TIME).
 
#define SBUS_SAMPLING_FAC   14
 Sampling factor of the SBUSr receiver.
 
#define DEF_LED   500
 Sampling factor of led in default mode (expressed in units of SAMPLING_TIME).
 
#define LOG_LED   500
 Sampling factor of led in log mode (expressed in units of SAMPLING_TIME).
 
#define MTP_LED   250
 Sampling factor of led in mtp mode (expressed in units of SAMPLING_TIME).
 
#define ERR_LED   10000
 Sampling factor of led in error mode (expressed in units of SAMPLING_TIME).
 
#define MTPWAIT_LED   100
 Sampling factor of led in mtp wait mode (expressed in units of SAMPLING_TIME).
 
#define ACC_ODR   3333
 Output data rate of accelerometer (sps).
 
#define GYRO_ODR   3333
 Output data rate of gyrometer (sps).
 
#define MAG_ODR   200
 Output data rate of magnetometer (sps).
 
#define SPEED_SCALE   1.0e-3F
 Speed scale.
 
#define DIST_SCALE   0.25F
 Distance scale.
 
#define ACC_SCALE   (-1.0e-3F*9.806F)
 Acceleration scale.
 
#define GYRO_SCALE   (1.0e-3F*PI/180.0F)
 Gyrometer scale.
 
#define MAG_SCALE   0.1F
 Magnetometer scale.
 
#define GPSSPEED_SCALE   0.5144F
 GPS speed scale.
 
#define GAIN_RIDERTRQ   0.141F
 Gain of rider torque (Nm/(mV/V), with 5V supply).
 
#define OFFSET_RIDERTRQ   -(324.11*GAIN_RIDERTRQ)
 Offset of rider torque (mV/V).
 
#define GAIN_STEERPOS   50.9F/180.0F*PI
 Fain of steer position.
 
#define OFFSET_STEERPOS   -30.7F/180.0F*PI
 Offset of steer position.
 
#define GAIN_STEERVEL   (2.0F*1000.0F/60.0F*2.0F*PI)
 Gain of steer velocity.
 
#define OFFSET_STEERVEL   (-1000.0F/60.0F*2.0F*PI)
 Offset of steer velocity.
 
#define GAIN_ACTCURR   2*MAX_REFCUR
 Gain of actual motor current.
 
#define OFFSET_ACTCURR   -MAX_REFCUR
 Offset of actual motor current.
 
#define GAIN_VOLTAGE   3.3F*1.027F*160.0F/10.0F
 Gain of voltage.
 
#define OFFSET_VOLTAGE   0.0F
 Offset of voltage.
 
#define GAIN_FORKDISP   -152.935F
 Fain of front fork displacement.
 
#define OFFSET_FORKDISP   0.107F
 Offset of front fork displacement.
 
#define GYROX_OFFSET   +0.0059F/GYRO_SCALE
 Offset of gyro x.
 
#define GYROY_OFFSET   -0.0066F/GYRO_SCALE
 Offset of gyro y.
 
#define GYROZ_OFFSET   -0.0080F/GYRO_SCALE
 Offset of gyro z.
 
#define NUM_CH_SBUS   7
 Number channels from SBUS.
 
#define MAX_SBUS   1811
 Maximum value from SBUS.
 
#define MIN_SBUS   172
 Minimum value from SBUS.
 
#define ZERO_SBUS   992
 Zero-value for SBUS.
 
#define TRESHOLD_LOGIC_SBUS   1400
 Treshold for SBUS logic channels.
 
#define TRESHOLD_POS_SBUS   1400
 Treshold for positive value.
 
#define TRESHOLD_NEG_SBUS   600
 Treshold for negative value.
 
#define MAX_MISSING_SBUS   10*SBUS_SAMPLING_FAC
 Maximum missing packets for SBUS.
 
#define MAX_REF_INPUT   1
 Maximum value for input reference.
 
#define MIN_REF_INPUT   -1
 Minimum value for input reference.
 
#define SBUS_THROTTLE_CH   2
 Throttle channel in SBUS.
 
#define SBUS_ROLL_CH   1
 Roll channel in SBUS.
 
#define SBUS_EN_CH   5
 Enable channel in SBUS.
 
#define SBUS_BR_CH   6
 brake channel in SBUS.
 
#define SBUS_THR_OR   3
 Direct throttle channel in SBUS.
 
#define SBUS_SEL_CH   7
 3 selector channel in SBUS.
 
#define MAX_REFCUR   10
 Maximum reference current.
 
#define MAX_REFTHROTTLE   1.0F
 Maximum throttle value.
 
#define MIN_VOLTAGE   15
 Minimum battery voltage (undervoltage) (V).
 
#define MAX_VOLTAGE   40
 Maximum battery voltage (overvoltage) (V).
 
#define MAX_STEER_ANGLE   0.35
 Maximum steering angle.
 
#define MAX_BR_SPEED   10
 Maximum brake motor speed (mm/s).
 
#define MAX_BR_ACC   25
 Maximum brake motor acceleration (mm/s2).
 
#define BR_STEPS   200
 Number of steps of the brake motor.
 
#define BR_SPEED_RATIO   1
 Speed ratio of the brake motor to brake lever (mm/revolution).
 
#define MAX_BR_DISP   12.0F
 Maximum brake lever displacement (mm).
 
#define CONVERT_RIDERTRQ_TO_NM(X)
 Convert rider torque to Nm.
 
#define CONVERT_STEERPOS_TO_RAD(X)
 Convert steer position to radiants.
 
#define CONVERT_STEERVEL_TO_RADPS(X)
 Convert steer rate to rad/s.
 
#define CONVERT_ACTCURR_TO_A(X)
 Convert steer rate to rad/s.
 
#define CONVERT_CURRENT_TO_PWM(X)
 Convert reference current to PWM value.
 
#define CONVERT_CURRENT_TO_DAC(X)
 Convert reference current to DAC value.
 
#define CONVERT_TRHOTTLE_TO_DAC(X)
 Convert reference throttle to DAC value.
 
#define CONVERT_VOLTAGE_TO_V(X)
 Convert battery voltage to volts.
 
#define CONVERT_FORKDISP_TO_MM(X)
 Convert fork displacement to millimiters.
 
#define CONVERT_CHANNEL_TO_FLOAT(X, XMIN, XMAX)
 Convert SBUS channel to float.
 
#define CONVERT_BRLEV_TO_STEPS(X)
 Convert brake lever position to motor steps.
 
#define CONVERT_TRHOTTLE_TO_STEPS(X)
 Convert throttle to motor steps.
 
#define USB_CONNECTED   (!bitRead(USB1_PORTSC1,7))
 Macro for checking the USB connection status-.
 
#define MTR_EN_STATE   HIGH
 Enable state for steer motor.
 
#define RELAY_EN_STATE   HIGH
 Enable state for relay.
 
#define BR_SLEEP_STATE   HIGH
 Enable state for brake motor.
 
#define MTR_ENABLE   digitalWriteFast(MTR_EN_PIN, MTR_EN_STATE), delay(100)
 Macro for motor enable.
 
#define RELAY_ENABLE   digitalWriteFast(RELAY_EN_PIN, RELAY_EN_STATE), delay(500)
 Macro for relay enable.
 
#define BR_ENABLE   digitalWriteFast(BR_SLEEP_PIN, BR_SLEEP_STATE)
 Macro for brake motor enable.
 
#define BR_DISABLE   digitalWriteFast(BR_SLEEP_PIN, !BR_SLEEP_STATE)
 Macro for brake motor enable.
 
#define LEDON   digitalWriteFast(LED_BUILTIN, HIGH)
 Macro for LED on.
 
#define LEDOFF   digitalWriteFast(LED_BUILTIN, LOW)
 Macro for LED off.
 
#define POWER_OFF   SNVS_LPCR |= (1<<6)
 Macro for turning off the microcontroller.
 
#define CPU_FREQ   600e6
 CPU clock speed (Hz). /warning Maximum value is 816e6 without cooling.
 
#define MTR_CTRL_MODE   1
 Control mode of steer motor (0=PWM or 1=DAC).
 
#define EN_LONG_CTRL   0
 Enable the longitudinal control.
 
#define EN_REMOTE_CTRL   0
 Enable the remote controller.
 
#define CW   LOW
 Digital pin state for clockwise torque.
 
#define NUM_ZERO_SAMPLES   500
 Samples used to perform the zero of sensors.
 
#define STEERVEL_RATIO   (-36.0*1.25)
 Speed ratio of steer velocity.
 
#define FULLEXT_FORKDISP   0
 Fork displacement at full extended suspension (in mm).
 
#define NAN_VAL   0xFFC00000
 NaN value used for invalid data.
 
#define YINCL_MCUBOX   1.3426
 Pitch iinclination of MCU box (in rad).
 
#define IMP_DUR   100
 Impulse duration (ms).
 
#define IMP_AMP   -10.0
 Impulse amplitude (A).
 

Variables

const float imu_rotMat [3][3]
 Rotation matrix from IMU frame to SAE body-fixed frame.
 
const float mag_rotMat [3][3]
 Rotation matrix from MAG frame to SAE body-fixed frame.
 

Detailed Description

General configurations for the source code.

Configuration file with defines and macros for the source code of the SBB Micro code. This includes PIN definitions, BUS settings, DAC settings, definitions of constants and factors, conversions of raw data, and other user-defined parameters.

Note
Building is necessary for changes to take effect.
See also
Configurations Bus settings Pin settings Constants Macros User paramters