► Warning fixes

- Changed all float constants to use f suffix to prevent double conversions
- Removed compile warnings due to HAL_GPIO_* related calls
- Added comms.h with prototypes for functions which were used in main()
- Casts and externs to fix compile warnings in various files.
- Made a bunch of file-local variables static.
- Fixed buzzerFreq/buzzerPattern extern declarations with correct type (uint8_t)
- Since this is C, void func() { } needs to be void func(void) { }, so fixed that in all instances.
These updates follows from @trollcop
This commit is contained in:
EmanuelFeru
2019-06-10 20:18:37 +02:00
parent 9fdbba1c37
commit 43b4f4aa20
8 changed files with 120 additions and 91 deletions

28
Inc/comms.h Normal file
View File

@ -0,0 +1,28 @@
/*
* This file is part of the hoverboard-firmware-hack project.
*
* Copyright (C) 2017-2018 Rene Hopf <renehopf@mac.com>
* Copyright (C) 2017-2018 Nico Stute <crinq@crinq.de>
* Copyright (C) 2017-2018 Niklas Fauth <niklas.fauth@kit.fail>
*
* 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/>.
*/
#pragma once
#include "stm32f1xx_hal.h"
void setScopeChannel(uint8_t ch, int16_t val);
void consoleScope(void);
void consoleLog(char *message);

View File

@ -15,23 +15,23 @@
// How to calibrate: connect GND and RX of a 3.3v uart-usb adapter to the right sensor board cable (be careful not to use the red wire of the cable. 15v will destroye verything.). if you are using nunchuck, disable it temporarily. enable DEBUG_SERIAL_USART3 and DEBUG_SERIAL_ASCII use asearial terminal.
// Battery voltage calibration: connect power source. see <How to calibrate>. write value nr 5 to BAT_CALIB_ADC. make and flash firmware. then you can verify voltage on value 6 (devide it by 100.0 to get calibrated voltage).
#define BAT_CALIB_REAL_VOLTAGE 43.0 // input voltage measured by multimeter
#define BAT_CALIB_REAL_VOLTAGE 43.0f // input voltage measured by multimeter
#define BAT_CALIB_ADC 1704 // adc-value measured by mainboard (value nr 5 on UART debug output)
#define BAT_NUMBER_OF_CELLS 10 // normal Hoverboard battery: 10s
#define BAT_LOW_LVL1_ENABLE 0 // to beep or not to beep, 1 or 0
#define BAT_LOW_LVL1 3.6 // gently beeps at this voltage level. [V/cell]
#define BAT_LOW_LVL1 3.6f // gently beeps at this voltage level. [V/cell]
#define BAT_LOW_LVL2_ENABLE 1 // to beep or not to beep, 1 or 0
#define BAT_LOW_LVL2 3.5 // your battery is almost empty. Charge now! [V/cell]
#define BAT_LOW_DEAD 3.37 // undervoltage poweroff. (while not driving) [V/cell]
#define BAT_LOW_LVL2 3.5f // your battery is almost empty. Charge now! [V/cell]
#define BAT_LOW_DEAD 3.37f // undervoltage poweroff. (while not driving) [V/cell]
#define DC_CUR_LIMIT 15 // DC current limit in amps per motor. so 15 means it will draw 30A out of your battery. it does not disable motors, it is a soft current limit.
// Board overheat detection: the sensor is inside the STM/GD chip. it is very inaccurate without calibration (up to 45°C). so only enable this funcion after calibration! let your board cool down. see <How to calibrate>. get the real temp of the chip by thermo cam or another temp-sensor taped on top of the chip and write it to TEMP_CAL_LOW_DEG_C. write debug value 8 to TEMP_CAL_LOW_ADC. drive around to warm up the board. it should be at least 20°C warmer. repeat it for the HIGH-values. enable warning and/or poweroff and make and flash firmware.
#define TEMP_CAL_LOW_ADC 1655 // temperature 1: ADC value
#define TEMP_CAL_LOW_DEG_C 35.8 // temperature 1: measured temperature [°C]
#define TEMP_CAL_LOW_DEG_C 35.8f // temperature 1: measured temperature [°C]
#define TEMP_CAL_HIGH_ADC 1588 // temperature 2: ADC value
#define TEMP_CAL_HIGH_DEG_C 48.9 // temperature 2: measured temperature [°C]
#define TEMP_CAL_HIGH_DEG_C 48.9f // temperature 2: measured temperature [°C]
#define TEMP_WARNING_ENABLE 0 // to beep or not to beep, 1 or 0, DO NOT ACTIVITE WITHOUT CALIBRATION!
#define TEMP_WARNING 60 // annoying fast beeps [°C]
#define TEMP_POWEROFF_ENABLE 0 // to poweroff or not to poweroff, 1 or 0, DO NOT ACTIVITE WITHOUT CALIBRATION!
@ -100,23 +100,23 @@
// outputs:
// - speedR and speedL: normal driving -1000 to 1000
#define FILTER 0.1 // lower value == softer filter. do not use values <0.01, you will get float precision issues.
#define SPEED_COEFFICIENT 1.0 //0.5 // higher value == stronger. 0.0 to ~2.0?
#define STEER_COEFFICIENT 0.5//0.5 // higher value == stronger. if you do not want any steering, set it to 0.0; 0.0 to 1.0
#define FILTER 0.1f // lower value == softer filter. do not use values <0.01, you will get float precision issues.
#define SPEED_COEFFICIENT 1.0f // higher value == stronger. 0.0 to ~2.0?
#define STEER_COEFFICIENT 0.5f // higher value == stronger. if you do not want any steering, set it to 0.0; 0.0 to 1.0
#define INVERT_R_DIRECTION
#define INVERT_L_DIRECTION
#define BEEPS_BACKWARD 0 // 0 or 1
// ###### SIMPLE BOBBYCAR ######
// for better bobbycar code see: https://github.com/larsmm/hoverboard-firmware-hack-bbcar
// #define FILTER 0.1
// #define SPEED_COEFFICIENT -1
// #define STEER_COEFFICIENT 0
// #define FILTER 0.1f
// #define SPEED_COEFFICIENT -1f
// #define STEER_COEFFICIENT 0f
// ###### ARMCHAIR ######
// #define FILTER 0.05
// #define SPEED_COEFFICIENT 0.5
// #define STEER_COEFFICIENT -0.2
// #define FILTER 0.05f
// #define SPEED_COEFFICIENT 0.5f
// #define STEER_COEFFICIENT -0.2f
// ############################### VALIDATE SETTINGS ###############################

View File

@ -123,7 +123,7 @@
#define DELAY_TIM_FREQUENCY_US 1000000
#define MOTOR_AMP_CONV_DC_AMP 0.02 // A per bit (12) on ADC.
#define MOTOR_AMP_CONV_DC_AMP 0.02f // A per bit (12) on ADC.
#define MILLI_R (R * 1000)
#define MILLI_PSI (PSI * 1000)
@ -131,16 +131,16 @@
#define NO 0
#define YES 1
#define ABS(a) (((a) < 0.0) ? -(a) : (a))
#define ABS(a) (((a) < 0.0f) ? -(a) : (a))
#define LIMIT(x, lowhigh) (((x) > (lowhigh)) ? (lowhigh) : (((x) < (-lowhigh)) ? (-lowhigh) : (x)))
#define SAT(x, lowhigh) (((x) > (lowhigh)) ? (1.0) : (((x) < (-lowhigh)) ? (-1.0) : (0.0)))
#define SAT2(x, low, high) (((x) > (high)) ? (1.0) : (((x) < (low)) ? (-1.0) : (0.0)))
#define SAT(x, lowhigh) (((x) > (lowhigh)) ? (1.0f) : (((x) < (-lowhigh)) ? (-1.0f) : (0.0f)))
#define SAT2(x, low, high) (((x) > (high)) ? (1.0f) : (((x) < (low)) ? (-1.0f) : (0.0f)))
#define STEP(from, to, step) (((from) < (to)) ? (MIN((from) + (step), (to))) : (MAX((from) - (step), (to))))
#define DEG(a) ((a)*M_PI / 180.0)
#define RAD(a) ((a)*180.0 / M_PI)
#define SIGN(a) (((a) < 0.0) ? (-1.0) : (((a) > 0.0) ? (1.0) : (0.0)))
#define DEG(a) ((a)*M_PI / 180.0f)
#define RAD(a) ((a)*180.0f / M_PI)
#define SIGN(a) (((a) < 0.0f) ? (-1.0f) : (((a) > 0.0f) ? (1.0f) : (0.0f)))
#define CLAMP(x, low, high) (((x) > (high)) ? (high) : (((x) < (low)) ? (low) : (x)))
#define SCALE(value, high, max) MIN(MAX(((max) - (value)) / ((max) - (high)), 0.0), 1.0)
#define SCALE(value, high, max) MIN(MAX(((max) - (value)) / ((max) - (high)), 0.0f), 1.0f)
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
#define MAX(a, b) (((a) > (b)) ? (a) : (b))
#define MIN3(a, b, c) MIN(a, MIN(b, c))

View File

@ -52,28 +52,28 @@ extern volatile adc_buf_t adc_buffer;
extern volatile uint32_t timeout;
uint32_t buzzerFreq = 0;
uint32_t buzzerPattern = 0;
uint32_t buzzerTimer = 0;
uint8_t buzzerFreq = 0;
uint8_t buzzerPattern = 0;
static uint32_t buzzerTimer = 0;
uint8_t enable = 0;
const int pwm_res = 64000000 / 2 / PWM_FREQ; // = 2000
static const uint16_t pwm_res = 64000000 / 2 / PWM_FREQ; // = 2000
int offsetcount = 0;
int offsetrl1 = 2000;
int offsetrl2 = 2000;
int offsetrr1 = 2000;
int offsetrr2 = 2000;
int offsetdcl = 2000;
int offsetdcr = 2000;
static int offsetcount = 0;
static int offsetrl1 = 2000;
static int offsetrl2 = 2000;
static int offsetrr1 = 2000;
static int offsetrr2 = 2000;
static int offsetdcl = 2000;
static int offsetdcr = 2000;
float batteryVoltage = BAT_NUMBER_OF_CELLS * 4.0;
//scan 8 channels with 2ADCs @ 20 clk cycles per sample
//meaning ~80 ADC clock cycles @ 8MHz until new DMA interrupt =~ 100KHz
//=640 cpu cycles
void DMA1_Channel1_IRQHandler() {
void DMA1_Channel1_IRQHandler(void) {
DMA1->IFCR = DMA_IFCR_CTCIF1;
// HAL_GPIO_WritePin(LED_PORT, LED_PIN, 1);
@ -91,7 +91,7 @@ void DMA1_Channel1_IRQHandler() {
}
if (buzzerTimer % 1000 == 0) { // because you get float rounding errors if it would run every time
batteryVoltage = batteryVoltage * 0.99 + ((float)adc_buffer.batt1 * ((float)BAT_CALIB_REAL_VOLTAGE / (float)BAT_CALIB_ADC)) * 0.01;
batteryVoltage = batteryVoltage * 0.99f + ((float)adc_buffer.batt1 * ((float)BAT_CALIB_REAL_VOLTAGE / (float)BAT_CALIB_ADC)) * 0.01f;
}
//disable PWM when current limit is reached (current chopping)
@ -153,9 +153,9 @@ void DMA1_Channel1_IRQHandler() {
// motAngleLeft = rtY_Left.a_elecAngle;
/* Apply commands */
LEFT_TIM->LEFT_TIM_U = CLAMP(ul + pwm_res / 2, 10, pwm_res-10);
LEFT_TIM->LEFT_TIM_V = CLAMP(vl + pwm_res / 2, 10, pwm_res-10);
LEFT_TIM->LEFT_TIM_W = CLAMP(wl + pwm_res / 2, 10, pwm_res-10);
LEFT_TIM->LEFT_TIM_U = (uint16_t)CLAMP(ul + pwm_res / 2, 10, pwm_res-10);
LEFT_TIM->LEFT_TIM_V = (uint16_t)CLAMP(vl + pwm_res / 2, 10, pwm_res-10);
LEFT_TIM->LEFT_TIM_W = (uint16_t)CLAMP(wl + pwm_res / 2, 10, pwm_res-10);
// =================================================================
@ -182,9 +182,9 @@ void DMA1_Channel1_IRQHandler() {
// motAngleRight = rtY_Right.a_elecAngle;
/* Apply commands */
RIGHT_TIM->RIGHT_TIM_U = CLAMP(ur + pwm_res / 2, 10, pwm_res-10);
RIGHT_TIM->RIGHT_TIM_V = CLAMP(vr + pwm_res / 2, 10, pwm_res-10);
RIGHT_TIM->RIGHT_TIM_W = CLAMP(wr + pwm_res / 2, 10, pwm_res-10);
RIGHT_TIM->RIGHT_TIM_U = (uint16_t)CLAMP(ur + pwm_res / 2, 10, pwm_res-10);
RIGHT_TIM->RIGHT_TIM_V = (uint16_t)CLAMP(vr + pwm_res / 2, 10, pwm_res-10);
RIGHT_TIM->RIGHT_TIM_W = (uint16_t)CLAMP(wr + pwm_res / 2, 10, pwm_res-10);
// =================================================================
/* Indicate task complete */

View File

@ -1,9 +1,10 @@
#include <stdio.h>
#include <string.h>
#include "stm32f1xx_hal.h"
#include "defines.h"
#include "setup.h"
#include "config.h"
#include "stdio.h"
#include "string.h"
#include "comms.h"
UART_HandleTypeDef huart2;
@ -16,15 +17,15 @@ UART_HandleTypeDef huart2;
#endif
volatile uint8_t uart_buf[100];
volatile int16_t ch_buf[8];
static volatile uint8_t uart_buf[100];
static volatile int16_t ch_buf[8];
//volatile char char_buf[300];
void setScopeChannel(uint8_t ch, int16_t val) {
ch_buf[ch] = val;
}
void consoleScope() {
void consoleScope(void) {
#if defined DEBUG_SERIAL_SERVOTERM && (defined DEBUG_SERIAL_USART2 || defined DEBUG_SERIAL_USART3)
uart_buf[0] = 0xff;
uart_buf[1] = CLAMP(ch_buf[0]+127, 0, 255);
@ -46,12 +47,12 @@ void consoleScope() {
#endif
#if defined DEBUG_SERIAL_ASCII && (defined DEBUG_SERIAL_USART2 || defined DEBUG_SERIAL_USART3)
memset(uart_buf, 0, sizeof(uart_buf));
sprintf(uart_buf, "1:%i 2:%i 3:%i 4:%i 5:%i 6:%i 7:%i 8:%i\r\n", ch_buf[0], ch_buf[1], ch_buf[2], ch_buf[3], ch_buf[4], ch_buf[5], ch_buf[6], ch_buf[7]);
memset((void *)(uintptr_t)uart_buf, 0, sizeof(uart_buf));
sprintf((char *)(uintptr_t)uart_buf, "1:%i 2:%i 3:%i 4:%i 5:%i 6:%i 7:%i 8:%i\r\n", ch_buf[0], ch_buf[1], ch_buf[2], ch_buf[3], ch_buf[4], ch_buf[5], ch_buf[6], ch_buf[7]);
if(UART_DMA_CHANNEL->CNDTR == 0) {
UART_DMA_CHANNEL->CCR &= ~DMA_CCR_EN;
UART_DMA_CHANNEL->CNDTR = strlen(uart_buf);
UART_DMA_CHANNEL->CNDTR = strlen((char *)(uintptr_t)uart_buf);
UART_DMA_CHANNEL->CMAR = (uint32_t)uart_buf;
UART_DMA_CHANNEL->CCR |= DMA_CCR_EN;
}
@ -60,5 +61,5 @@ void consoleScope() {
void consoleLog(char *message)
{
HAL_UART_Transmit_DMA(&huart2, (uint8_t *)message, strlen(message));
HAL_UART_Transmit_DMA(&huart2, (uint8_t *)message, (uint16_t)strlen(message));
}

View File

@ -1,10 +1,10 @@
#include <stdbool.h>
#include <string.h>
#include "stm32f1xx_hal.h"
#include "defines.h"
#include "setup.h"
#include "config.h"
#include <stdbool.h>
#include <string.h>
TIM_HandleTypeDef TimHandle;
uint8_t ppm_count = 0;
@ -14,8 +14,8 @@ uint8_t nunchuck_data[6] = {0};
uint8_t i2cBuffer[2];
extern I2C_HandleTypeDef hi2c2;
DMA_HandleTypeDef hdma_i2c2_rx;
DMA_HandleTypeDef hdma_i2c2_tx;
extern DMA_HandleTypeDef hdma_i2c2_rx;
extern DMA_HandleTypeDef hdma_i2c2_tx;
#ifdef CONTROL_PPM
uint16_t ppm_captured_value[PPM_NUM_CHANNELS + 1] = {500, 500};
@ -26,7 +26,7 @@ bool ppm_valid = true;
#define IN_RANGE(x, low, up) (((x) >= (low)) && ((x) <= (up)))
void PPM_ISR_Callback() {
void PPM_ISR_Callback(void) {
// Dummy loop with 16 bit count wrap around
uint16_t rc_delay = TIM2->CNT;
TIM2->CNT = 0;
@ -48,7 +48,7 @@ void PPM_ISR_Callback() {
}
// SysTick executes once each ms
void PPM_SysTick_Callback() {
void PPM_SysTick_Callback(void) {
ppm_timeout++;
// Stop after 500 ms without PPM signal
if(ppm_timeout > 500) {
@ -60,7 +60,7 @@ void PPM_SysTick_Callback() {
}
}
void PPM_Init() {
void PPM_Init(void) {
GPIO_InitTypeDef GPIO_InitStruct;
/*Configure GPIO pin : PA3 */
GPIO_InitStruct.Pin = GPIO_PIN_3;
@ -84,7 +84,7 @@ void PPM_Init() {
}
#endif
void Nunchuck_Init() {
void Nunchuck_Init(void) {
//-- START -- init WiiNunchuck
i2cBuffer[0] = 0xF0;
i2cBuffer[1] = 0x55;
@ -99,7 +99,7 @@ void Nunchuck_Init() {
HAL_Delay(10);
}
void Nunchuck_Read() {
void Nunchuck_Read(void) {
i2cBuffer[0] = 0x00;
HAL_I2C_Master_Transmit(&hi2c2,0xA4,(uint8_t*)i2cBuffer, 1, 100);
HAL_Delay(5);

View File

@ -19,10 +19,12 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdlib.h> // for abs()
#include "stm32f1xx_hal.h"
#include "defines.h"
#include "setup.h"
#include "config.h"
#include "comms.h"
//#include "hd44780.h"
// Matlab includes and defines - from auto-code generation
@ -47,6 +49,7 @@ ExtY rtY_Right; /* External outputs */
// ###############################################################################
void SystemClock_Config(void);
void poweroff(void);
extern TIM_HandleTypeDef htim_left;
extern TIM_HandleTypeDef htim_right;
@ -57,8 +60,8 @@ extern volatile adc_buf_t adc_buffer;
extern I2C_HandleTypeDef hi2c2;
extern UART_HandleTypeDef huart2;
int cmd1; // normalized input values. -1000 to 1000
int cmd2;
static int cmd1; // normalized input values. -1000 to 1000
static int cmd2;
typedef struct{
int16_t steer;
@ -66,12 +69,12 @@ typedef struct{
//uint32_t crc;
} Serialcommand;
volatile Serialcommand command;
static volatile Serialcommand command;
uint8_t button1, button2;
static uint8_t button1, button2;
int steer; // global variable for steering. -1000 to 1000
int speed; // global variable for speed. -1000 to 1000
static int steer; // global variable for steering. -1000 to 1000
static int speed; // global variable for speed. -1000 to 1000
extern volatile int pwml; // global variable for pwm left. -1000 to 1000
extern volatile int pwmr; // global variable for pwm right. -1000 to 1000
@ -84,22 +87,20 @@ extern uint8_t enable; // global variable for motor enable
extern volatile uint32_t timeout; // global variable for timeout
extern float batteryVoltage; // global variable for battery voltage
uint32_t inactivity_timeout_counter;
static uint32_t inactivity_timeout_counter;
extern uint8_t nunchuck_data[6];
#ifdef CONTROL_PPM
extern volatile uint16_t ppm_captured_value[PPM_NUM_CHANNELS+1];
#endif
int milli_vel_error_sum = 0;
void poweroff() {
void poweroff(void) {
// if (abs(speed) < 20) { // wait for the speed to drop, then shut down -> this is commented out for SAFETY reasons
buzzerPattern = 0;
enable = 0;
for (int i = 0; i < 8; i++) {
buzzerFreq = i;
buzzerFreq = (uint8_t)i;
HAL_Delay(100);
}
HAL_GPIO_WritePin(OFF_PORT, OFF_PIN, 0);
@ -172,7 +173,7 @@ int main(void) {
// ###############################################################################
for (int i = 8; i >= 0; i--) {
buzzerFreq = i;
buzzerFreq = (uint8_t)i;
HAL_Delay(100);
}
buzzerFreq = 0;
@ -267,12 +268,12 @@ int main(void) {
// cmd1 = 0;
// ####### LOW-PASS FILTER #######
steer = steer * (1.0 - FILTER) + cmd1 * FILTER;
speed = speed * (1.0 - FILTER) + cmd2 * FILTER;
steer = (int)(steer * (1.0f - FILTER) + cmd1 * FILTER);
speed = (int)(speed * (1.0f - FILTER) + cmd2 * FILTER);
// ####### MIXER #######
speedR = CLAMP(speed * SPEED_COEFFICIENT - steer * STEER_COEFFICIENT, -1000, 1000);
speedL = CLAMP(speed * SPEED_COEFFICIENT + steer * STEER_COEFFICIENT, -1000, 1000);
speedR = CLAMP((int)(speed * SPEED_COEFFICIENT - steer * STEER_COEFFICIENT), -1000, 1000);
speedL = CLAMP((int)(speed * SPEED_COEFFICIENT + steer * STEER_COEFFICIENT), -1000, 1000);
#ifdef ADDITIONAL_CODE
@ -300,7 +301,7 @@ int main(void) {
if (inactivity_timeout_counter % 25 == 0) {
// ####### CALC BOARD TEMPERATURE #######
board_temp_adc_filtered = board_temp_adc_filtered * 0.99 + (float)adc_buffer.temp * 0.01;
board_temp_adc_filtered = board_temp_adc_filtered * 0.99f + (float)adc_buffer.temp * 0.01f;
board_temp_deg_c = ((float)TEMP_CAL_HIGH_DEG_C - (float)TEMP_CAL_LOW_DEG_C) / ((float)TEMP_CAL_HIGH_ADC - (float)TEMP_CAL_LOW_ADC) * (board_temp_adc_filtered - (float)TEMP_CAL_LOW_ADC) + (float)TEMP_CAL_LOW_DEG_C;
// ####### DEBUG SERIAL OUT #######
@ -308,15 +309,14 @@ int main(void) {
// setScopeChannel(0, (int)adc_buffer.l_tx2); // 1: ADC1
// setScopeChannel(1, (int)adc_buffer.l_rx2); // 2: ADC2
#endif
setScopeChannel(0, (int)speedR); // 1: output command: [-1000, 1000]
setScopeChannel(1, (int)speedL); // 2: output command: [-1000, 1000]
setScopeChannel(2, (int)rtY_Right.n_mot); // 3: Real motor speed [rpm]
setScopeChannel(3, (int)rtY_Left.n_mot); // 4: Real motor speed [rpm]
setScopeChannel(4, (int)adc_buffer.batt1); // 5: for battery voltage calibration
setScopeChannel(5, (int)(batteryVoltage * 100.0f)); // 6: for verifying battery voltage calibration
setScopeChannel(6, (int)board_temp_adc_filtered); // 7: for board temperature calibration
setScopeChannel(7, (int)board_temp_deg_c); // 8: for verifying board temperature calibration
setScopeChannel(0, (int16_t)speedR); // 1: output command: [-1000, 1000]
setScopeChannel(1, (int16_t)speedL); // 2: output command: [-1000, 1000]
setScopeChannel(2, (int16_t)rtY_Right.n_mot); // 3: Real motor speed [rpm]
setScopeChannel(3, (int16_t)rtY_Left.n_mot); // 4: Real motor speed [rpm]
setScopeChannel(4, (int16_t)adc_buffer.batt1); // 5: for battery voltage calibration
setScopeChannel(5, (int16_t)(batteryVoltage * 100.0f)); // 6: for verifying battery voltage calibration
setScopeChannel(6, (int16_t)board_temp_adc_filtered); // 7: for board temperature calibration
setScopeChannel(7, (int16_t)board_temp_deg_c); // 8: for verifying board temperature calibration
consoleScope();
}

View File

@ -53,7 +53,7 @@ volatile adc_buf_t adc_buffer;
#ifdef CONTROL_SERIAL_USART2
void UART_Control_Init() {
void UART_Control_Init(void) {
GPIO_InitTypeDef GPIO_InitStruct;
__HAL_RCC_USART2_CLK_ENABLE();
/* DMA1_Channel6_IRQn interrupt configuration */
@ -123,7 +123,7 @@ HAL_DMA_Init(&hdma_usart2_tx);
#endif
#ifdef DEBUG_SERIAL_USART3
void UART_Init() {
void UART_Init(void) {
__HAL_RCC_USART3_CLK_ENABLE();
__HAL_RCC_DMA1_CLK_ENABLE();
@ -156,7 +156,7 @@ void UART_Init() {
#endif
#ifdef DEBUG_SERIAL_USART2
void UART_Init() {
void UART_Init(void) {
__HAL_RCC_USART2_CLK_ENABLE();
__HAL_RCC_DMA1_CLK_ENABLE();
@ -189,7 +189,7 @@ void UART_Init() {
#endif
/*
void UART_Init() {
void UART_Init(void) {
__HAL_RCC_USART2_CLK_ENABLE();
__HAL_RCC_DMA1_CLK_ENABLE();
@ -224,7 +224,7 @@ void UART_Init() {
DMA_HandleTypeDef hdma_i2c2_rx;
DMA_HandleTypeDef hdma_i2c2_tx;
void I2C_Init()
void I2C_Init(void)
{
__HAL_RCC_I2C2_CLK_ENABLE();