Initial commit

This commit is contained in:
EmanuelFeru
2020-02-07 16:37:13 +01:00
commit 23929c5884
386 changed files with 235248 additions and 0 deletions

82
Inc/config.h Normal file
View File

@@ -0,0 +1,82 @@
/**
* This file is part of the hoverboard-sideboard-hack project.
*
* Copyright (C) 2020-2021 Emanuel FERU <aerdronix@gmail.com>
*
* 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/>.
*/
// Define to prevent recursive inclusion
#ifndef CONFIG_H
#define CONFIG_H
/* ==================================== VARIANT SELECTION ==================================== */
#if !defined(PLATFORMIO)
#define VARIANT_DEBUG // Variant for debugging and checking the capabilities of the side-board
//#define VARIANT_HOVERBOARD // Variant for using the side-boards connected to the Hoverboard mainboard
#endif
/* ==================================== DO NOT TOUCH SETTINGS ==================================== */
//#define PRINTF_FLOAT_SUPPORT // [-] Uncomment this for printf to support float. It will increase code size!
#define BYPASS_CUBEMX_DEFINES // [-] Use this flag to bypass the Ports definitions generated by CUBE MX in main.h and use the ones in defines.h
#define MPU6050 // [-] Define IMU sensor type
#define MPU_GYRO_FSR 2000 // [deg/s] Set Gyroscope Full Scale Range: 250 deg/s, 500 deg/s, 1000 deg/s, 2000 deg/s. !! DMP sensor fusion works only with 2000 deg/s !!
#define MPU_ACCEL_FSR 2 // [g] Set Acceleromenter Full Scale Range: 2g, 4g, 8g, 16g. !! DMP sensor fusion works only with 2g !!
#ifdef BYPASS_CUBEMX_DEFINES
#define MPU_I2C_SPEED 400000 // [bit/s] Define I2C speed for communicating with the MPU6050
#endif
#define DELAY_IN_MAIN_LOOP 1 // [ms] Delay in the main loop
/* =============================================================================================== */
/* ==================================== SETTINGS MPU-6050 ==================================== */
#define MPU_DMP_ENABLE // [-] Enable flag for MPU-6050 DMP (Digital Motion Processing) functionality.
#define MPU_DEFAULT_HZ 20 // [Hz] Default MPU frequecy: must be between 1Hz and 200Hz.
#define TEMP_READ_MS 500 // [ms] Temperature read time interval
#define PEDO_READ_MS 1000 // [ms] Pedometer read time interval
// #define USE_CAL_HW_REGISTERS // [-] Uncommnent this to SAVE the sensor calibration to the MPU-6050 registers after the Self-test was run
// DMP Tap Detection Settings
#define DMP_TAP_AXES TAP_XYZ // [-] Set which axes will register a tap: TAP_XYZ, TAP_X, TAP_Y, TAP_Z
#define DMP_TAP_THRESH 250 // [mg/ms] Set tap threshold for the selected axis.
#define DMP_TAP_COUNT 1 // [-] Set minimum number of taps needed for an interrupt. Minimum consecutive taps: 1 to 4
#define DMP_TAP_TIME 100 // [ms] Set time length between valid taps.
#define DMP_TAP_TIME_MULTI 500 // [ms] Set max time between taps to register as a multi-tap.
#define DMP_SHAKE_REJECT_THRESH 200 // [deg/s] Set shake rejection threshold in degree per second (dps). If the DMP detects a gyro sample larger than the thresh, taps are rejected.
#define DMP_SHAKE_REJECT_TIME 40 // [ms] Set shake rejection time. Sets the length of time that the gyro must be outside of the DMP_SHAKE_REJECT_THRESH before taps are rejected. A mandatory 60 ms is added to this parameter.
#define DMP_SHAKE_REJECT_TIMEOUT 10 // [ms] Set shake rejection timeout. Sets the length of time after a shake rejection that the gyro must stay inside of the threshold before taps can be detected again. A mandatory 60 ms is added to this parameter.
/* ==================================== SETTINGS USART ==================================== */
#if defined(VARIANT_DEBUG)
#define SERIAL_DEBUG // [-] Define for Serial Debug via the serial port
#elif defined(VARIANT_HOVERBOARD)
#define SERIAL_CONTROL // [-] Define for Serial Control via the serial port
#define SERIAL_FEEDBACK // [-] Define for Serial Feedback via the serial port
#endif
#ifdef BYPASS_CUBEMX_DEFINES
#define USART_MAIN_BAUD 38400 // [bit/s] MAIN Serial Tx/Rx baud rate
#endif
#define SERIAL_START_FRAME 0xAAAA // [-] Start frame definition for reliable serial communication
#define SERIAL_TIMEOUT 300 // [-] Numer of wrong received data for Serial timeout detection
/* ==================================== VALIDATE SETTINGS ==================================== */
#if defined(SERIAL_DEBUG) && defined(SERIAL_CONTROL)
#error SERIAL_DEBUG and SERIAL_CONTROL not allowed. It is on the same cable.
#endif
#endif

131
Inc/defines.h Normal file
View File

@@ -0,0 +1,131 @@
/**
* This file is part of the hoverboard-sideboard-hack project.
*
* Copyright (C) 2020-2021 Emanuel FERU <aerdronix@gmail.com>
*
* 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/>.
*/
// Define to prevent recursive inclusion
#ifndef DEFINES_H
#define DEFINES_H
// Includes
#include "stm32f1xx_hal.h"
#include "config.h"
#include "util.h"
#define UART_DMA_CHANNEL_TX DMA1_Channel7
#define UART_DMA_CHANNEL_RX DMA1_Channel6
#if defined(PRINTF_FLOAT_SUPPORT) && defined(SERIAL_DEBUG) && defined(__GNUC__)
asm(".global _printf_float"); // this is the magic trick for printf to support float
#endif
/* =========================== Defines General =========================== */
// #define _BV(bit) (1 << (bit))
// #define ARRAYNUM(arr_nanme) (uint32_t)(sizeof(arr_nanme) / sizeof(*(arr_nanme)))
#define min(a, b) (((a) < (b)) ? (a) : (b))
#define max(a, b) (((a) > (b)) ? (a) : (b))
#define i2c_write i2c_writeBytes
#define i2c_read i2c_readBytes
#define delay_ms HAL_Delay
#define get_ms get_tick_count_ms
#ifdef BYPASS_CUBEMX_DEFINES
/* =========================== Defines LEDs =========================== */
#define LED1_GPIO_Port GPIOA
#define LED1_Pin GPIO_PIN_0 // RED
#define LED2_GPIO_Port GPIOB
#define LED2_Pin GPIO_PIN_9 // GREEN
#define LED3_GPIO_Port GPIOB
#define LED3_Pin GPIO_PIN_8 // YELLOW
#define LED4_GPIO_Port GPIOB
#define LED4_Pin GPIO_PIN_5 // BLUE1
#define LED5_GPIO_Port GPIOB
#define LED5_Pin GPIO_PIN_4 // BLUE2
/* =========================== Defines SENSORS =========================== */
#define SENSOR1_GPIO_Port GPIOA
#define SENSOR1_Pin GPIO_PIN_4
#define SENSOR2_GPIO_Port GPIOC
#define SENSOR2_Pin GPIO_PIN_14
/* =========================== Defines AUX =========================== */
#define AUX1_PU_GPIO_Port GPIOC
#define AUX1_PU_Pin GPIO_PIN_15
#define AUX2_GPIO_Port GPIOA
#define AUX2_Pin GPIO_PIN_1
#define AUX3_PU_GPIO_Port GPIOB
#define AUX3_PU_Pin GPIO_PIN_11
/* =========================== Defines I2C =========================== */
#define MPU_SCL_GPIO_Port GPIOB
#define MPU_SCL_Pin GPIO_PIN_6
#define MPU_SDA_GPIO_Port GPIOB
#define MPU_SDA_Pin GPIO_PIN_7
// #define I2C_OWN_ADDRESS7 0x24
#endif
/* =========================== Defines MPU-6050 =========================== */
#define log_i printf // redirect the log_i debug function to printf
#define RAD2DEG 57.295779513082323 // RAD2DEG = 180/pi. Example: angle[deg] = angle[rad] * RAD2DEG
#define ACCEL_ON (0x01)
#define GYRO_ON (0x02)
#define COMPASS_ON (0x04)
#define PRINT_ACCEL (0x01)
#define PRINT_GYRO (0x02)
#define PRINT_QUAT (0x04)
#define PRINT_EULER (0x08)
#define PRINT_TEMP (0x10)
#define PRINT_PEDO (0x20)
typedef struct{
int16_t x;
int16_t y;
int16_t z;
} Gyro;
typedef struct{
int16_t x;
int16_t y;
int16_t z;
} Accel;
typedef struct{
int32_t w;
int32_t x;
int32_t y;
int32_t z;
} Quaternion;
typedef struct{
int16_t roll;
int16_t pitch;
int16_t yaw;
} Euler;
typedef struct {
Gyro gyro;
Accel accel;
Quaternion quat;
Euler euler;
int16_t temp;
} MPU_Data;
#endif

56
Inc/dma.h Normal file
View File

@@ -0,0 +1,56 @@
/**
******************************************************************************
* File Name : dma.h
* Description : This file contains all the function prototypes for
* the dma.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __dma_H
#define __dma_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* DMA memory to memory transfer handles -------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
void MX_DMA_Init(void);
/* USER CODE BEGIN Prototypes */
/* USER CODE END Prototypes */
#ifdef __cplusplus
}
#endif
#endif /* __dma_H */
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

57
Inc/gpio.h Normal file
View File

@@ -0,0 +1,57 @@
/**
******************************************************************************
* File Name : gpio.h
* Description : This file contains all the functions prototypes for
* the gpio
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __gpio_H
#define __gpio_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
void MX_GPIO_Init(void);
/* USER CODE BEGIN Prototypes */
/* USER CODE END Prototypes */
#ifdef __cplusplus
}
#endif
#endif /*__ pinoutConfig_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

58
Inc/i2c.h Normal file
View File

@@ -0,0 +1,58 @@
/**
******************************************************************************
* File Name : I2C.h
* Description : This file provides code for the configuration
* of the I2C instances.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __i2c_H
#define __i2c_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
extern I2C_HandleTypeDef hi2c1;
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
void MX_I2C1_Init(void);
/* USER CODE BEGIN Prototypes */
/* USER CODE END Prototypes */
#ifdef __cplusplus
}
#endif
#endif /*__ i2c_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

99
Inc/main.h Normal file
View File

@@ -0,0 +1,99 @@
/* USER CODE BEGIN Header */
/**
* This file is part of the hoverboard-sideboard-hack project.
*
* Copyright (C) 2020-2021 Emanuel FERU <aerdronix@gmail.com>
*
* 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/>.
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MAIN_H
#define __MAIN_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f1xx_hal.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "defines.h"
#include "config.h"
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
void Error_Handler(void);
/* USER CODE BEGIN EFP */
#if !defined(BYPASS_CUBEMX_DEFINES)
/* USER CODE END EFP */
/* Private defines -----------------------------------------------------------*/
#define USART_MAIN_BAUD 38400
#define MPU_I2C_SPEED 400000
#define SENSOR2_Pin GPIO_PIN_14
#define SENSOR2_GPIO_Port GPIOC
#define AUX1_PU_Pin GPIO_PIN_15
#define AUX1_PU_GPIO_Port GPIOC
#define LED1_Pin GPIO_PIN_0
#define LED1_GPIO_Port GPIOA
#define AUX2_Pin GPIO_PIN_1
#define AUX2_GPIO_Port GPIOA
#define SENSOR1_Pin GPIO_PIN_4
#define SENSOR1_GPIO_Port GPIOA
#define AUX3_PU_Pin GPIO_PIN_11
#define AUX3_PU_GPIO_Port GPIOB
#define LED5_Pin GPIO_PIN_4
#define LED5_GPIO_Port GPIOB
#define LED4_Pin GPIO_PIN_5
#define LED4_GPIO_Port GPIOB
#define MPU_SCL_Pin GPIO_PIN_6
#define MPU_SCL_GPIO_Port GPIOB
#define MPU_SDA_Pin GPIO_PIN_7
#define MPU_SDA_GPIO_Port GPIOB
#define LED3_Pin GPIO_PIN_8
#define LED3_GPIO_Port GPIOB
#define LED2_Pin GPIO_PIN_9
#define LED2_GPIO_Port GPIOB
/* USER CODE BEGIN Private defines */
#endif
/* USER CODE END Private defines */
#ifdef __cplusplus
}
#endif
#endif /* __MAIN_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

144
Inc/mpu6050.h Normal file
View File

@@ -0,0 +1,144 @@
/**
* This file was taken from InvenSense MotionApps v6.12 library and
* refactored for the hoverboard-sideboard-hack project.
*
* Copyright (C) 2020-2021 Emanuel FERU <aerdronix@gmail.com>
* Copyright (C) 2011-2012 InvenSense Corporation, All Rights Reserved.
*
* 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/>.
*/
// Define to prevent recursive inclusion
#ifndef MPU6050_H
#define MPU6050_H
#include <stdint.h>
#include "defines.h"
//--------------------------------------------
#define INV_X_GYRO (0x40)
#define INV_Y_GYRO (0x20)
#define INV_Z_GYRO (0x10)
#define INV_XYZ_GYRO (INV_X_GYRO | INV_Y_GYRO | INV_Z_GYRO)
#define INV_XYZ_ACCEL (0x08)
#define INV_XYZ_COMPASS (0x01)
#define MPU_INT_STATUS_DATA_READY (0x0001)
#define MPU_INT_STATUS_DMP (0x0002)
#define MPU_INT_STATUS_PLL_READY (0x0004)
#define MPU_INT_STATUS_I2C_MST (0x0008)
#define MPU_INT_STATUS_FIFO_OVERFLOW (0x0010)
#define MPU_INT_STATUS_ZMOT (0x0020)
#define MPU_INT_STATUS_MOT (0x0040)
#define MPU_INT_STATUS_FREE_FALL (0x0080)
#define MPU_INT_STATUS_DMP_0 (0x0100)
#define MPU_INT_STATUS_DMP_1 (0x0200)
#define MPU_INT_STATUS_DMP_2 (0x0400)
#define MPU_INT_STATUS_DMP_3 (0x0800)
#define MPU_INT_STATUS_DMP_4 (0x1000)
#define MPU_INT_STATUS_DMP_5 (0x2000)
/* Set up APIs */
int mpu_init(void);
int mpu_init_slave(void);
int mpu_set_bypass(unsigned char bypass_on);
/* Configuration APIs */
int mpu_lp_accel_mode(unsigned short rate);
int mpu_lp_motion_interrupt(unsigned short thresh, unsigned char time, unsigned short lpa_freq);
int mpu_set_int_level(unsigned char active_low);
int mpu_set_int_latched(unsigned char enable);
int mpu_set_dmp_state(unsigned char enable);
int mpu_get_dmp_state(unsigned char *enabled);
int mpu_get_lpf(unsigned short *lpf);
int mpu_set_lpf(unsigned short lpf);
int mpu_get_gyro_fsr(unsigned short *fsr);
int mpu_set_gyro_fsr(unsigned short fsr);
int mpu_get_accel_fsr(unsigned char *fsr);
int mpu_set_accel_fsr(unsigned char fsr);
int mpu_get_compass_fsr(unsigned short *fsr);
int mpu_get_gyro_sens(float *sens);
int mpu_get_accel_sens(unsigned short *sens);
int mpu_get_sample_rate(unsigned short *rate);
int mpu_set_sample_rate(unsigned short rate);
int mpu_get_compass_sample_rate(unsigned short *rate);
int mpu_set_compass_sample_rate(unsigned short rate);
int mpu_get_fifo_config(unsigned char *sensors);
int mpu_configure_fifo(unsigned char sensors);
int mpu_get_power_state(unsigned char *power_on);
int mpu_set_sensors(unsigned char sensors);
int mpu_read_6500_accel_bias(long *accel_bias);
int mpu_set_gyro_bias_reg(long * gyro_bias);
int mpu_set_accel_bias_6500_reg(const long *accel_bias);
int mpu_read_6050_accel_bias(long *accel_bias);
int mpu_set_accel_bias_6050_reg(const long *accel_bias);
/* Data getter/setter APIs */
int mpu_get_gyro_reg(short *data, unsigned long *timestamp);
int mpu_get_accel_reg(short *data, unsigned long *timestamp);
int mpu_get_compass_reg(short *data, unsigned long *timestamp);
int mpu_get_temperature(long *data, unsigned long *timestamp);
int mpu_get_int_status(short *status);
int mpu_read_fifo(short *gyro, short *accel, unsigned long *timestamp,
unsigned char *sensors, unsigned char *more);
int mpu_read_fifo_stream(unsigned short length, unsigned char *data,
unsigned char *more);
int mpu_reset_fifo(void);
int mpu_write_mem(unsigned short mem_addr, unsigned short length,
unsigned char *data);
int mpu_read_mem(unsigned short mem_addr, unsigned short length,
unsigned char *data);
int mpu_load_firmware(unsigned short length, const unsigned char *firmware,
unsigned short start_addr, unsigned short sample_rate);
int mpu_reg_dump(void);
int mpu_read_reg(unsigned char reg, unsigned char *data);
int mpu_run_self_test(long *gyro, long *accel);
int mpu_run_6500_self_test(long *gyro, long *accel, unsigned char debug);
void mpu_start_self_test(void);
void mpu_setup_gyro(void);
/* MPU configuration */
int mpu_config(void);
/* MPU get packet data */
void mpu_get_data(void);
/* Data post-processing */
void mpu_read_gyro_raw(void);
void mpu_read_accel_raw(void);
void mpu_calc_euler_angles(void);
void mpu_tap_func(unsigned char direction, unsigned char count);
void mpu_android_orient_func(unsigned char orientation);
/* Handle user input commands */
void mpu_handle_input(char c);
void mpu_print_to_console(void);
#endif

107
Inc/mpu6050_dmp.h Normal file
View File

@@ -0,0 +1,107 @@
/**
* This file was taken from InvenSense MotionApps v6.12 library and
* refactored for the hoverboard-sideboard-hack project.
*
* Copyright (C) 2020-2021 Emanuel FERU <aerdronix@gmail.com>
* Copyright (C) 2011-2012 InvenSense Corporation, All Rights Reserved.
*
* 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/>.
*/
// Define to prevent recursive inclusion
#ifndef MPU6050_DMP_H
#define MPU6050_DMP_H
#include <stdint.h>
#define TAP_X (0x01)
#define TAP_Y (0x02)
#define TAP_Z (0x04)
#define TAP_XYZ (0x07)
#define TAP_X_UP (0x01)
#define TAP_X_DOWN (0x02)
#define TAP_Y_UP (0x03)
#define TAP_Y_DOWN (0x04)
#define TAP_Z_UP (0x05)
#define TAP_Z_DOWN (0x06)
#define ANDROID_ORIENT_PORTRAIT (0x00)
#define ANDROID_ORIENT_LANDSCAPE (0x01)
#define ANDROID_ORIENT_REVERSE_PORTRAIT (0x02)
#define ANDROID_ORIENT_REVERSE_LANDSCAPE (0x03)
#define DMP_INT_GESTURE (0x01)
#define DMP_INT_CONTINUOUS (0x02)
#define DMP_FEATURE_TAP (0x001)
#define DMP_FEATURE_ANDROID_ORIENT (0x002)
#define DMP_FEATURE_LP_QUAT (0x004)
#define DMP_FEATURE_PEDOMETER (0x008)
#define DMP_FEATURE_6X_LP_QUAT (0x010)
#define DMP_FEATURE_GYRO_CAL (0x020)
#define DMP_FEATURE_SEND_RAW_ACCEL (0x040)
#define DMP_FEATURE_SEND_RAW_GYRO (0x080)
#define DMP_FEATURE_SEND_CAL_GYRO (0x100)
#define INV_WXYZ_QUAT (0x100)
/* Set up functions. */
int dmp_load_motion_driver_firmware(void);
int dmp_set_fifo_rate(unsigned short rate);
int dmp_get_fifo_rate(unsigned short *rate);
int dmp_enable_feature(unsigned short mask);
int dmp_get_enabled_features(unsigned short *mask);
int dmp_set_interrupt_mode(unsigned char mode);
int dmp_set_orientation(unsigned short orient);
int dmp_set_gyro_bias(long *bias);
int dmp_set_accel_bias(long *bias);
/* Tap functions. */
int dmp_register_tap_cb(void (*func)(unsigned char, unsigned char));
int dmp_set_tap_thresh(unsigned char axis, unsigned short thresh);
int dmp_set_tap_axes(unsigned char axis);
int dmp_set_tap_count(unsigned char min_taps);
int dmp_set_tap_time(unsigned short time);
int dmp_set_tap_time_multi(unsigned short time);
int dmp_set_shake_reject_thresh(long sf, unsigned short thresh);
int dmp_set_shake_reject_time(unsigned short time);
int dmp_set_shake_reject_timeout(unsigned short time);
/* Android orientation functions. */
int dmp_register_android_orient_cb(void (*func)(unsigned char));
/* LP quaternion functions. */
int dmp_enable_lp_quat(unsigned char enable);
int dmp_enable_6x_lp_quat(unsigned char enable);
/* Pedometer functions. */
int dmp_get_pedometer_step_count(unsigned long *count);
int dmp_set_pedometer_step_count(unsigned long count);
int dmp_get_pedometer_walk_time(unsigned long *time);
int dmp_set_pedometer_walk_time(unsigned long time);
/* DMP gyro calibration functions. */
int dmp_enable_gyro_cal(unsigned char enable);
/* Read function. This function should be called whenever the MPU interrupt is
* detected.
*/
int dmp_read_fifo(short *gyro, short *accel, long *quat,
unsigned long *timestamp, short *sensors, unsigned char *more);
#endif

495
Inc/mpu6050_dmpKey.h Normal file
View File

@@ -0,0 +1,495 @@
/*
$License:
Copyright (C) 2011 InvenSense Corporation, All Rights Reserved.
$
*/
#ifndef DMPKEY_H__
#define DMPKEY_H__
#define KEY_CFG_25 (0)
#define KEY_CFG_24 (KEY_CFG_25 + 1)
#define KEY_CFG_26 (KEY_CFG_24 + 1)
#define KEY_CFG_27 (KEY_CFG_26 + 1)
#define KEY_CFG_21 (KEY_CFG_27 + 1)
#define KEY_CFG_20 (KEY_CFG_21 + 1)
#define KEY_CFG_TAP4 (KEY_CFG_20 + 1)
#define KEY_CFG_TAP5 (KEY_CFG_TAP4 + 1)
#define KEY_CFG_TAP6 (KEY_CFG_TAP5 + 1)
#define KEY_CFG_TAP7 (KEY_CFG_TAP6 + 1)
#define KEY_CFG_TAP0 (KEY_CFG_TAP7 + 1)
#define KEY_CFG_TAP1 (KEY_CFG_TAP0 + 1)
#define KEY_CFG_TAP2 (KEY_CFG_TAP1 + 1)
#define KEY_CFG_TAP3 (KEY_CFG_TAP2 + 1)
#define KEY_CFG_TAP_QUANTIZE (KEY_CFG_TAP3 + 1)
#define KEY_CFG_TAP_JERK (KEY_CFG_TAP_QUANTIZE + 1)
#define KEY_CFG_DR_INT (KEY_CFG_TAP_JERK + 1)
#define KEY_CFG_AUTH (KEY_CFG_DR_INT + 1)
#define KEY_CFG_TAP_SAVE_ACCB (KEY_CFG_AUTH + 1)
#define KEY_CFG_TAP_CLEAR_STICKY (KEY_CFG_TAP_SAVE_ACCB + 1)
#define KEY_CFG_FIFO_ON_EVENT (KEY_CFG_TAP_CLEAR_STICKY + 1)
#define KEY_FCFG_ACCEL_INPUT (KEY_CFG_FIFO_ON_EVENT + 1)
#define KEY_FCFG_ACCEL_INIT (KEY_FCFG_ACCEL_INPUT + 1)
#define KEY_CFG_23 (KEY_FCFG_ACCEL_INIT + 1)
#define KEY_FCFG_1 (KEY_CFG_23 + 1)
#define KEY_FCFG_3 (KEY_FCFG_1 + 1)
#define KEY_FCFG_2 (KEY_FCFG_3 + 1)
#define KEY_CFG_3D (KEY_FCFG_2 + 1)
#define KEY_CFG_3B (KEY_CFG_3D + 1)
#define KEY_CFG_3C (KEY_CFG_3B + 1)
#define KEY_FCFG_5 (KEY_CFG_3C + 1)
#define KEY_FCFG_4 (KEY_FCFG_5 + 1)
#define KEY_FCFG_7 (KEY_FCFG_4 + 1)
#define KEY_FCFG_FSCALE (KEY_FCFG_7 + 1)
#define KEY_FCFG_AZ (KEY_FCFG_FSCALE + 1)
#define KEY_FCFG_6 (KEY_FCFG_AZ + 1)
#define KEY_FCFG_LSB4 (KEY_FCFG_6 + 1)
#define KEY_CFG_12 (KEY_FCFG_LSB4 + 1)
#define KEY_CFG_14 (KEY_CFG_12 + 1)
#define KEY_CFG_15 (KEY_CFG_14 + 1)
#define KEY_CFG_16 (KEY_CFG_15 + 1)
#define KEY_CFG_18 (KEY_CFG_16 + 1)
#define KEY_CFG_6 (KEY_CFG_18 + 1)
#define KEY_CFG_7 (KEY_CFG_6 + 1)
#define KEY_CFG_4 (KEY_CFG_7 + 1)
#define KEY_CFG_5 (KEY_CFG_4 + 1)
#define KEY_CFG_2 (KEY_CFG_5 + 1)
#define KEY_CFG_3 (KEY_CFG_2 + 1)
#define KEY_CFG_1 (KEY_CFG_3 + 1)
#define KEY_CFG_EXTERNAL (KEY_CFG_1 + 1)
#define KEY_CFG_8 (KEY_CFG_EXTERNAL + 1)
#define KEY_CFG_9 (KEY_CFG_8 + 1)
#define KEY_CFG_ORIENT_3 (KEY_CFG_9 + 1)
#define KEY_CFG_ORIENT_2 (KEY_CFG_ORIENT_3 + 1)
#define KEY_CFG_ORIENT_1 (KEY_CFG_ORIENT_2 + 1)
#define KEY_CFG_GYRO_SOURCE (KEY_CFG_ORIENT_1 + 1)
#define KEY_CFG_ORIENT_IRQ_1 (KEY_CFG_GYRO_SOURCE + 1)
#define KEY_CFG_ORIENT_IRQ_2 (KEY_CFG_ORIENT_IRQ_1 + 1)
#define KEY_CFG_ORIENT_IRQ_3 (KEY_CFG_ORIENT_IRQ_2 + 1)
#define KEY_FCFG_MAG_VAL (KEY_CFG_ORIENT_IRQ_3 + 1)
#define KEY_FCFG_MAG_MOV (KEY_FCFG_MAG_VAL + 1)
#define KEY_CFG_LP_QUAT (KEY_FCFG_MAG_MOV + 1)
/* MPU6050 keys */
#define KEY_CFG_ACCEL_FILTER (KEY_CFG_LP_QUAT + 1)
#define KEY_CFG_MOTION_BIAS (KEY_CFG_ACCEL_FILTER + 1)
#define KEY_TEMPLABEL (KEY_CFG_MOTION_BIAS + 1)
#define KEY_D_0_22 (KEY_TEMPLABEL + 1)
#define KEY_D_0_24 (KEY_D_0_22 + 1)
#define KEY_D_0_36 (KEY_D_0_24 + 1)
#define KEY_D_0_52 (KEY_D_0_36 + 1)
#define KEY_D_0_96 (KEY_D_0_52 + 1)
#define KEY_D_0_104 (KEY_D_0_96 + 1)
#define KEY_D_0_108 (KEY_D_0_104 + 1)
#define KEY_D_0_163 (KEY_D_0_108 + 1)
#define KEY_D_0_188 (KEY_D_0_163 + 1)
#define KEY_D_0_192 (KEY_D_0_188 + 1)
#define KEY_D_0_224 (KEY_D_0_192 + 1)
#define KEY_D_0_228 (KEY_D_0_224 + 1)
#define KEY_D_0_232 (KEY_D_0_228 + 1)
#define KEY_D_0_236 (KEY_D_0_232 + 1)
#define KEY_DMP_PREVPTAT (KEY_D_0_236 + 1)
#define KEY_D_1_2 (KEY_DMP_PREVPTAT + 1)
#define KEY_D_1_4 (KEY_D_1_2 + 1)
#define KEY_D_1_8 (KEY_D_1_4 + 1)
#define KEY_D_1_10 (KEY_D_1_8 + 1)
#define KEY_D_1_24 (KEY_D_1_10 + 1)
#define KEY_D_1_28 (KEY_D_1_24 + 1)
#define KEY_D_1_36 (KEY_D_1_28 + 1)
#define KEY_D_1_40 (KEY_D_1_36 + 1)
#define KEY_D_1_44 (KEY_D_1_40 + 1)
#define KEY_D_1_72 (KEY_D_1_44 + 1)
#define KEY_D_1_74 (KEY_D_1_72 + 1)
#define KEY_D_1_79 (KEY_D_1_74 + 1)
#define KEY_D_1_88 (KEY_D_1_79 + 1)
#define KEY_D_1_90 (KEY_D_1_88 + 1)
#define KEY_D_1_92 (KEY_D_1_90 + 1)
#define KEY_D_1_96 (KEY_D_1_92 + 1)
#define KEY_D_1_98 (KEY_D_1_96 + 1)
#define KEY_D_1_100 (KEY_D_1_98 + 1)
#define KEY_D_1_106 (KEY_D_1_100 + 1)
#define KEY_D_1_108 (KEY_D_1_106 + 1)
#define KEY_D_1_112 (KEY_D_1_108 + 1)
#define KEY_D_1_128 (KEY_D_1_112 + 1)
#define KEY_D_1_152 (KEY_D_1_128 + 1)
#define KEY_D_1_160 (KEY_D_1_152 + 1)
#define KEY_D_1_168 (KEY_D_1_160 + 1)
#define KEY_D_1_175 (KEY_D_1_168 + 1)
#define KEY_D_1_176 (KEY_D_1_175 + 1)
#define KEY_D_1_178 (KEY_D_1_176 + 1)
#define KEY_D_1_179 (KEY_D_1_178 + 1)
#define KEY_D_1_218 (KEY_D_1_179 + 1)
#define KEY_D_1_232 (KEY_D_1_218 + 1)
#define KEY_D_1_236 (KEY_D_1_232 + 1)
#define KEY_D_1_240 (KEY_D_1_236 + 1)
#define KEY_D_1_244 (KEY_D_1_240 + 1)
#define KEY_D_1_250 (KEY_D_1_244 + 1)
#define KEY_D_1_252 (KEY_D_1_250 + 1)
#define KEY_D_2_12 (KEY_D_1_252 + 1)
#define KEY_D_2_96 (KEY_D_2_12 + 1)
#define KEY_D_2_108 (KEY_D_2_96 + 1)
#define KEY_D_2_208 (KEY_D_2_108 + 1)
#define KEY_FLICK_MSG (KEY_D_2_208 + 1)
#define KEY_FLICK_COUNTER (KEY_FLICK_MSG + 1)
#define KEY_FLICK_LOWER (KEY_FLICK_COUNTER + 1)
#define KEY_CFG_FLICK_IN (KEY_FLICK_LOWER + 1)
#define KEY_FLICK_UPPER (KEY_CFG_FLICK_IN + 1)
#define KEY_CGNOTICE_INTR (KEY_FLICK_UPPER + 1)
#define KEY_D_2_224 (KEY_CGNOTICE_INTR + 1)
#define KEY_D_2_244 (KEY_D_2_224 + 1)
#define KEY_D_2_248 (KEY_D_2_244 + 1)
#define KEY_D_2_252 (KEY_D_2_248 + 1)
#define KEY_D_GYRO_BIAS_X (KEY_D_2_252 + 1)
#define KEY_D_GYRO_BIAS_Y (KEY_D_GYRO_BIAS_X + 1)
#define KEY_D_GYRO_BIAS_Z (KEY_D_GYRO_BIAS_Y + 1)
#define KEY_D_ACC_BIAS_X (KEY_D_GYRO_BIAS_Z + 1)
#define KEY_D_ACC_BIAS_Y (KEY_D_ACC_BIAS_X + 1)
#define KEY_D_ACC_BIAS_Z (KEY_D_ACC_BIAS_Y + 1)
#define KEY_D_GYRO_ENABLE (KEY_D_ACC_BIAS_Z + 1)
#define KEY_D_ACCEL_ENABLE (KEY_D_GYRO_ENABLE + 1)
#define KEY_D_QUAT_ENABLE (KEY_D_ACCEL_ENABLE +1)
#define KEY_D_OUTPUT_ENABLE (KEY_D_QUAT_ENABLE + 1)
#define KEY_D_CR_TIME_G (KEY_D_OUTPUT_ENABLE + 1)
#define KEY_D_CR_TIME_A (KEY_D_CR_TIME_G + 1)
#define KEY_D_CR_TIME_Q (KEY_D_CR_TIME_A + 1)
#define KEY_D_CS_TAX (KEY_D_CR_TIME_Q + 1)
#define KEY_D_CS_TAY (KEY_D_CS_TAX + 1)
#define KEY_D_CS_TAZ (KEY_D_CS_TAY + 1)
#define KEY_D_CS_TGX (KEY_D_CS_TAZ + 1)
#define KEY_D_CS_TGY (KEY_D_CS_TGX + 1)
#define KEY_D_CS_TGZ (KEY_D_CS_TGY + 1)
#define KEY_D_CS_TQ0 (KEY_D_CS_TGZ + 1)
#define KEY_D_CS_TQ1 (KEY_D_CS_TQ0 + 1)
#define KEY_D_CS_TQ2 (KEY_D_CS_TQ1 + 1)
#define KEY_D_CS_TQ3 (KEY_D_CS_TQ2 + 1)
/* Compass keys */
#define KEY_CPASS_BIAS_X (KEY_D_CS_TQ3 + 1)
#define KEY_CPASS_BIAS_Y (KEY_CPASS_BIAS_X + 1)
#define KEY_CPASS_BIAS_Z (KEY_CPASS_BIAS_Y + 1)
#define KEY_CPASS_MTX_00 (KEY_CPASS_BIAS_Z + 1)
#define KEY_CPASS_MTX_01 (KEY_CPASS_MTX_00 + 1)
#define KEY_CPASS_MTX_02 (KEY_CPASS_MTX_01 + 1)
#define KEY_CPASS_MTX_10 (KEY_CPASS_MTX_02 + 1)
#define KEY_CPASS_MTX_11 (KEY_CPASS_MTX_10 + 1)
#define KEY_CPASS_MTX_12 (KEY_CPASS_MTX_11 + 1)
#define KEY_CPASS_MTX_20 (KEY_CPASS_MTX_12 + 1)
#define KEY_CPASS_MTX_21 (KEY_CPASS_MTX_20 + 1)
#define KEY_CPASS_MTX_22 (KEY_CPASS_MTX_21 + 1)
/* Gesture Keys */
#define KEY_DMP_TAPW_MIN (KEY_CPASS_MTX_22 + 1)
#define KEY_DMP_TAP_THR_X (KEY_DMP_TAPW_MIN + 1)
#define KEY_DMP_TAP_THR_Y (KEY_DMP_TAP_THR_X + 1)
#define KEY_DMP_TAP_THR_Z (KEY_DMP_TAP_THR_Y + 1)
#define KEY_DMP_SH_TH_Y (KEY_DMP_TAP_THR_Z + 1)
#define KEY_DMP_SH_TH_X (KEY_DMP_SH_TH_Y + 1)
#define KEY_DMP_SH_TH_Z (KEY_DMP_SH_TH_X + 1)
#define KEY_DMP_ORIENT (KEY_DMP_SH_TH_Z + 1)
#define KEY_D_ACT0 (KEY_DMP_ORIENT + 1)
#define KEY_D_ACSX (KEY_D_ACT0 + 1)
#define KEY_D_ACSY (KEY_D_ACSX + 1)
#define KEY_D_ACSZ (KEY_D_ACSY + 1)
#define KEY_X_GRT_Y_TMP (KEY_D_ACSZ + 1)
#define KEY_SKIP_X_GRT_Y_TMP (KEY_X_GRT_Y_TMP + 1)
#define KEY_SKIP_END_COMPARE (KEY_SKIP_X_GRT_Y_TMP + 1)
#define KEY_END_COMPARE_Y_X_TMP2 (KEY_SKIP_END_COMPARE + 1)
#define KEY_CFG_ANDROID_ORIENT_INT (KEY_END_COMPARE_Y_X_TMP2 + 1)
#define KEY_NO_ORIENT_INTERRUPT (KEY_CFG_ANDROID_ORIENT_INT + 1)
#define KEY_END_COMPARE_Y_X_TMP (KEY_NO_ORIENT_INTERRUPT + 1)
#define KEY_END_ORIENT_1 (KEY_END_COMPARE_Y_X_TMP + 1)
#define KEY_END_COMPARE_Y_X (KEY_END_ORIENT_1 + 1)
#define KEY_END_ORIENT (KEY_END_COMPARE_Y_X + 1)
#define KEY_X_GRT_Y (KEY_END_ORIENT + 1)
#define KEY_NOT_TIME_MINUS_1 (KEY_X_GRT_Y + 1)
#define KEY_END_COMPARE_Y_X_TMP3 (KEY_NOT_TIME_MINUS_1 + 1)
#define KEY_X_GRT_Y_TMP2 (KEY_END_COMPARE_Y_X_TMP3 + 1)
/* Authenticate Keys */
#define KEY_D_AUTH_OUT (KEY_X_GRT_Y_TMP2 + 1)
#define KEY_D_AUTH_IN (KEY_D_AUTH_OUT + 1)
#define KEY_D_AUTH_A (KEY_D_AUTH_IN + 1)
#define KEY_D_AUTH_B (KEY_D_AUTH_A + 1)
/* Pedometer standalone only keys */
#define KEY_D_PEDSTD_BP_B (KEY_D_AUTH_B + 1)
#define KEY_D_PEDSTD_HP_A (KEY_D_PEDSTD_BP_B + 1)
#define KEY_D_PEDSTD_HP_B (KEY_D_PEDSTD_HP_A + 1)
#define KEY_D_PEDSTD_BP_A4 (KEY_D_PEDSTD_HP_B + 1)
#define KEY_D_PEDSTD_BP_A3 (KEY_D_PEDSTD_BP_A4 + 1)
#define KEY_D_PEDSTD_BP_A2 (KEY_D_PEDSTD_BP_A3 + 1)
#define KEY_D_PEDSTD_BP_A1 (KEY_D_PEDSTD_BP_A2 + 1)
#define KEY_D_PEDSTD_INT_THRSH (KEY_D_PEDSTD_BP_A1 + 1)
#define KEY_D_PEDSTD_CLIP (KEY_D_PEDSTD_INT_THRSH + 1)
#define KEY_D_PEDSTD_SB (KEY_D_PEDSTD_CLIP + 1)
#define KEY_D_PEDSTD_SB_TIME (KEY_D_PEDSTD_SB + 1)
#define KEY_D_PEDSTD_PEAKTHRSH (KEY_D_PEDSTD_SB_TIME + 1)
#define KEY_D_PEDSTD_TIML (KEY_D_PEDSTD_PEAKTHRSH + 1)
#define KEY_D_PEDSTD_TIMH (KEY_D_PEDSTD_TIML + 1)
#define KEY_D_PEDSTD_PEAK (KEY_D_PEDSTD_TIMH + 1)
#define KEY_D_PEDSTD_TIMECTR (KEY_D_PEDSTD_PEAK + 1)
#define KEY_D_PEDSTD_STEPCTR (KEY_D_PEDSTD_TIMECTR + 1)
#define KEY_D_PEDSTD_WALKTIME (KEY_D_PEDSTD_STEPCTR + 1)
#define KEY_D_PEDSTD_DECI (KEY_D_PEDSTD_WALKTIME + 1)
/*Host Based No Motion*/
#define KEY_D_HOST_NO_MOT (KEY_D_PEDSTD_DECI + 1)
/* EIS keys */
#define KEY_P_EIS_FIFO_FOOTER (KEY_D_HOST_NO_MOT + 1)
#define KEY_P_EIS_FIFO_YSHIFT (KEY_P_EIS_FIFO_FOOTER + 1)
#define KEY_P_EIS_DATA_RATE (KEY_P_EIS_FIFO_YSHIFT + 1)
#define KEY_P_EIS_FIFO_XSHIFT (KEY_P_EIS_DATA_RATE + 1)
#define KEY_P_EIS_FIFO_SYNC (KEY_P_EIS_FIFO_XSHIFT + 1)
#define KEY_P_EIS_FIFO_ZSHIFT (KEY_P_EIS_FIFO_SYNC + 1)
#define KEY_P_EIS_FIFO_READY (KEY_P_EIS_FIFO_ZSHIFT + 1)
#define KEY_DMP_FOOTER (KEY_P_EIS_FIFO_READY + 1)
#define KEY_DMP_INTX_HC (KEY_DMP_FOOTER + 1)
#define KEY_DMP_INTX_PH (KEY_DMP_INTX_HC + 1)
#define KEY_DMP_INTX_SH (KEY_DMP_INTX_PH + 1)
#define KEY_DMP_AINV_SH (KEY_DMP_INTX_SH + 1)
#define KEY_DMP_A_INV_XH (KEY_DMP_AINV_SH + 1)
#define KEY_DMP_AINV_PH (KEY_DMP_A_INV_XH + 1)
#define KEY_DMP_CTHX_H (KEY_DMP_AINV_PH + 1)
#define KEY_DMP_CTHY_H (KEY_DMP_CTHX_H + 1)
#define KEY_DMP_CTHZ_H (KEY_DMP_CTHY_H + 1)
#define KEY_DMP_NCTHX_H (KEY_DMP_CTHZ_H + 1)
#define KEY_DMP_NCTHY_H (KEY_DMP_NCTHX_H + 1)
#define KEY_DMP_NCTHZ_H (KEY_DMP_NCTHY_H + 1)
#define KEY_DMP_CTSQ_XH (KEY_DMP_NCTHZ_H + 1)
#define KEY_DMP_CTSQ_YH (KEY_DMP_CTSQ_XH + 1)
#define KEY_DMP_CTSQ_ZH (KEY_DMP_CTSQ_YH + 1)
#define KEY_DMP_INTX_H (KEY_DMP_CTSQ_ZH + 1)
#define KEY_DMP_INTY_H (KEY_DMP_INTX_H + 1)
#define KEY_DMP_INTZ_H (KEY_DMP_INTY_H + 1)
//#define KEY_DMP_HPX_H (KEY_DMP_INTZ_H + 1)
//#define KEY_DMP_HPY_H (KEY_DMP_HPX_H + 1)
//#define KEY_DMP_HPZ_H (KEY_DMP_HPY_H + 1)
/* Stream keys */
#define KEY_STREAM_P_GYRO_Z (KEY_DMP_INTZ_H + 1)
#define KEY_STREAM_P_GYRO_Y (KEY_STREAM_P_GYRO_Z + 1)
#define KEY_STREAM_P_GYRO_X (KEY_STREAM_P_GYRO_Y + 1)
#define KEY_STREAM_P_TEMP (KEY_STREAM_P_GYRO_X + 1)
#define KEY_STREAM_P_AUX_Y (KEY_STREAM_P_TEMP + 1)
#define KEY_STREAM_P_AUX_X (KEY_STREAM_P_AUX_Y + 1)
#define KEY_STREAM_P_AUX_Z (KEY_STREAM_P_AUX_X + 1)
#define KEY_STREAM_P_ACCEL_Y (KEY_STREAM_P_AUX_Z + 1)
#define KEY_STREAM_P_ACCEL_X (KEY_STREAM_P_ACCEL_Y + 1)
#define KEY_STREAM_P_FOOTER (KEY_STREAM_P_ACCEL_X + 1)
#define KEY_STREAM_P_ACCEL_Z (KEY_STREAM_P_FOOTER + 1)
#define NUM_KEYS (KEY_STREAM_P_ACCEL_Z + 1)
typedef struct {
unsigned short key;
unsigned short addr;
} tKeyLabel;
#define DINA0A 0x0a
#define DINA22 0x22
#define DINA42 0x42
#define DINA5A 0x5a
#define DINA06 0x06
#define DINA0E 0x0e
#define DINA16 0x16
#define DINA1E 0x1e
#define DINA26 0x26
#define DINA2E 0x2e
#define DINA36 0x36
#define DINA3E 0x3e
#define DINA46 0x46
#define DINA4E 0x4e
#define DINA56 0x56
#define DINA5E 0x5e
#define DINA66 0x66
#define DINA6E 0x6e
#define DINA76 0x76
#define DINA7E 0x7e
#define DINA00 0x00
#define DINA08 0x08
#define DINA10 0x10
#define DINA18 0x18
#define DINA20 0x20
#define DINA28 0x28
#define DINA30 0x30
#define DINA38 0x38
#define DINA40 0x40
#define DINA48 0x48
#define DINA50 0x50
#define DINA58 0x58
#define DINA60 0x60
#define DINA68 0x68
#define DINA70 0x70
#define DINA78 0x78
#define DINA04 0x04
#define DINA0C 0x0c
#define DINA14 0x14
#define DINA1C 0x1C
#define DINA24 0x24
#define DINA2C 0x2c
#define DINA34 0x34
#define DINA3C 0x3c
#define DINA44 0x44
#define DINA4C 0x4c
#define DINA54 0x54
#define DINA5C 0x5c
#define DINA64 0x64
#define DINA6C 0x6c
#define DINA74 0x74
#define DINA7C 0x7c
#define DINA01 0x01
#define DINA09 0x09
#define DINA11 0x11
#define DINA19 0x19
#define DINA21 0x21
#define DINA29 0x29
#define DINA31 0x31
#define DINA39 0x39
#define DINA41 0x41
#define DINA49 0x49
#define DINA51 0x51
#define DINA59 0x59
#define DINA61 0x61
#define DINA69 0x69
#define DINA71 0x71
#define DINA79 0x79
#define DINA25 0x25
#define DINA2D 0x2d
#define DINA35 0x35
#define DINA3D 0x3d
#define DINA4D 0x4d
#define DINA55 0x55
#define DINA5D 0x5D
#define DINA6D 0x6d
#define DINA75 0x75
#define DINA7D 0x7d
#define DINADC 0xdc
#define DINAF2 0xf2
#define DINAAB 0xab
#define DINAAA 0xaa
#define DINAF1 0xf1
#define DINADF 0xdf
#define DINADA 0xda
#define DINAB1 0xb1
#define DINAB9 0xb9
#define DINAF3 0xf3
#define DINA8B 0x8b
#define DINAA3 0xa3
#define DINA91 0x91
#define DINAB6 0xb6
#define DINAB4 0xb4
#define DINC00 0x00
#define DINC01 0x01
#define DINC02 0x02
#define DINC03 0x03
#define DINC08 0x08
#define DINC09 0x09
#define DINC0A 0x0a
#define DINC0B 0x0b
#define DINC10 0x10
#define DINC11 0x11
#define DINC12 0x12
#define DINC13 0x13
#define DINC18 0x18
#define DINC19 0x19
#define DINC1A 0x1a
#define DINC1B 0x1b
#define DINC20 0x20
#define DINC21 0x21
#define DINC22 0x22
#define DINC23 0x23
#define DINC28 0x28
#define DINC29 0x29
#define DINC2A 0x2a
#define DINC2B 0x2b
#define DINC30 0x30
#define DINC31 0x31
#define DINC32 0x32
#define DINC33 0x33
#define DINC38 0x38
#define DINC39 0x39
#define DINC3A 0x3a
#define DINC3B 0x3b
#define DINC40 0x40
#define DINC41 0x41
#define DINC42 0x42
#define DINC43 0x43
#define DINC48 0x48
#define DINC49 0x49
#define DINC4A 0x4a
#define DINC4B 0x4b
#define DINC50 0x50
#define DINC51 0x51
#define DINC52 0x52
#define DINC53 0x53
#define DINC58 0x58
#define DINC59 0x59
#define DINC5A 0x5a
#define DINC5B 0x5b
#define DINC60 0x60
#define DINC61 0x61
#define DINC62 0x62
#define DINC63 0x63
#define DINC68 0x68
#define DINC69 0x69
#define DINC6A 0x6a
#define DINC6B 0x6b
#define DINC70 0x70
#define DINC71 0x71
#define DINC72 0x72
#define DINC73 0x73
#define DINC78 0x78
#define DINC79 0x79
#define DINC7A 0x7a
#define DINC7B 0x7b
#define DIND40 0x40
#define DINA80 0x80
#define DINA90 0x90
#define DINAA0 0xa0
#define DINAC9 0xc9
#define DINACB 0xcb
#define DINACD 0xcd
#define DINACF 0xcf
#define DINAC8 0xc8
#define DINACA 0xca
#define DINACC 0xcc
#define DINACE 0xce
#define DINAD8 0xd8
#define DINADD 0xdd
#define DINAF8 0xf0
#define DINAFE 0xfe
#define DINBF8 0xf8
#define DINAC0 0xb0
#define DINAC1 0xb1
#define DINAC2 0xb4
#define DINAC3 0xb5
#define DINAC4 0xb8
#define DINAC5 0xb9
#define DINBC0 0xc0
#define DINBC2 0xc2
#define DINBC4 0xc4
#define DINBC6 0xc6
#endif // DMPKEY_H__

264
Inc/mpu6050_dmpmap.h Normal file
View File

@@ -0,0 +1,264 @@
/*
$License:
Copyright (C) 2011 InvenSense Corporation, All Rights Reserved.
$
*/
#ifndef DMPMAP_H
#define DMPMAP_H
#ifdef __cplusplus
extern "C"
{
#endif
#define DMP_PTAT 0
#define DMP_XGYR 2
#define DMP_YGYR 4
#define DMP_ZGYR 6
#define DMP_XACC 8
#define DMP_YACC 10
#define DMP_ZACC 12
#define DMP_ADC1 14
#define DMP_ADC2 16
#define DMP_ADC3 18
#define DMP_BIASUNC 20
#define DMP_FIFORT 22
#define DMP_INVGSFH 24
#define DMP_INVGSFL 26
#define DMP_1H 28
#define DMP_1L 30
#define DMP_BLPFSTCH 32
#define DMP_BLPFSTCL 34
#define DMP_BLPFSXH 36
#define DMP_BLPFSXL 38
#define DMP_BLPFSYH 40
#define DMP_BLPFSYL 42
#define DMP_BLPFSZH 44
#define DMP_BLPFSZL 46
#define DMP_BLPFMTC 48
#define DMP_SMC 50
#define DMP_BLPFMXH 52
#define DMP_BLPFMXL 54
#define DMP_BLPFMYH 56
#define DMP_BLPFMYL 58
#define DMP_BLPFMZH 60
#define DMP_BLPFMZL 62
#define DMP_BLPFC 64
#define DMP_SMCTH 66
#define DMP_0H2 68
#define DMP_0L2 70
#define DMP_BERR2H 72
#define DMP_BERR2L 74
#define DMP_BERR2NH 76
#define DMP_SMCINC 78
#define DMP_ANGVBXH 80
#define DMP_ANGVBXL 82
#define DMP_ANGVBYH 84
#define DMP_ANGVBYL 86
#define DMP_ANGVBZH 88
#define DMP_ANGVBZL 90
#define DMP_BERR1H 92
#define DMP_BERR1L 94
#define DMP_ATCH 96
#define DMP_BIASUNCSF 98
#define DMP_ACT2H 100
#define DMP_ACT2L 102
#define DMP_GSFH 104
#define DMP_GSFL 106
#define DMP_GH 108
#define DMP_GL 110
#define DMP_0_5H 112
#define DMP_0_5L 114
#define DMP_0_0H 116
#define DMP_0_0L 118
#define DMP_1_0H 120
#define DMP_1_0L 122
#define DMP_1_5H 124
#define DMP_1_5L 126
#define DMP_TMP1AH 128
#define DMP_TMP1AL 130
#define DMP_TMP2AH 132
#define DMP_TMP2AL 134
#define DMP_TMP3AH 136
#define DMP_TMP3AL 138
#define DMP_TMP4AH 140
#define DMP_TMP4AL 142
#define DMP_XACCW 144
#define DMP_TMP5 146
#define DMP_XACCB 148
#define DMP_TMP8 150
#define DMP_YACCB 152
#define DMP_TMP9 154
#define DMP_ZACCB 156
#define DMP_TMP10 158
#define DMP_DZH 160
#define DMP_DZL 162
#define DMP_XGCH 164
#define DMP_XGCL 166
#define DMP_YGCH 168
#define DMP_YGCL 170
#define DMP_ZGCH 172
#define DMP_ZGCL 174
#define DMP_YACCW 176
#define DMP_TMP7 178
#define DMP_AFB1H 180
#define DMP_AFB1L 182
#define DMP_AFB2H 184
#define DMP_AFB2L 186
#define DMP_MAGFBH 188
#define DMP_MAGFBL 190
#define DMP_QT1H 192
#define DMP_QT1L 194
#define DMP_QT2H 196
#define DMP_QT2L 198
#define DMP_QT3H 200
#define DMP_QT3L 202
#define DMP_QT4H 204
#define DMP_QT4L 206
#define DMP_CTRL1H 208
#define DMP_CTRL1L 210
#define DMP_CTRL2H 212
#define DMP_CTRL2L 214
#define DMP_CTRL3H 216
#define DMP_CTRL3L 218
#define DMP_CTRL4H 220
#define DMP_CTRL4L 222
#define DMP_CTRLS1 224
#define DMP_CTRLSF1 226
#define DMP_CTRLS2 228
#define DMP_CTRLSF2 230
#define DMP_CTRLS3 232
#define DMP_CTRLSFNLL 234
#define DMP_CTRLS4 236
#define DMP_CTRLSFNL2 238
#define DMP_CTRLSFNL 240
#define DMP_TMP30 242
#define DMP_CTRLSFJT 244
#define DMP_TMP31 246
#define DMP_TMP11 248
#define DMP_CTRLSF2_2 250
#define DMP_TMP12 252
#define DMP_CTRLSF1_2 254
#define DMP_PREVPTAT 256
#define DMP_ACCZB 258
#define DMP_ACCXB 264
#define DMP_ACCYB 266
#define DMP_1HB 272
#define DMP_1LB 274
#define DMP_0H 276
#define DMP_0L 278
#define DMP_ASR22H 280
#define DMP_ASR22L 282
#define DMP_ASR6H 284
#define DMP_ASR6L 286
#define DMP_TMP13 288
#define DMP_TMP14 290
#define DMP_FINTXH 292
#define DMP_FINTXL 294
#define DMP_FINTYH 296
#define DMP_FINTYL 298
#define DMP_FINTZH 300
#define DMP_FINTZL 302
#define DMP_TMP1BH 304
#define DMP_TMP1BL 306
#define DMP_TMP2BH 308
#define DMP_TMP2BL 310
#define DMP_TMP3BH 312
#define DMP_TMP3BL 314
#define DMP_TMP4BH 316
#define DMP_TMP4BL 318
#define DMP_STXG 320
#define DMP_ZCTXG 322
#define DMP_STYG 324
#define DMP_ZCTYG 326
#define DMP_STZG 328
#define DMP_ZCTZG 330
#define DMP_CTRLSFJT2 332
#define DMP_CTRLSFJTCNT 334
#define DMP_PVXG 336
#define DMP_TMP15 338
#define DMP_PVYG 340
#define DMP_TMP16 342
#define DMP_PVZG 344
#define DMP_TMP17 346
#define DMP_MNMFLAGH 352
#define DMP_MNMFLAGL 354
#define DMP_MNMTMH 356
#define DMP_MNMTML 358
#define DMP_MNMTMTHRH 360
#define DMP_MNMTMTHRL 362
#define DMP_MNMTHRH 364
#define DMP_MNMTHRL 366
#define DMP_ACCQD4H 368
#define DMP_ACCQD4L 370
#define DMP_ACCQD5H 372
#define DMP_ACCQD5L 374
#define DMP_ACCQD6H 376
#define DMP_ACCQD6L 378
#define DMP_ACCQD7H 380
#define DMP_ACCQD7L 382
#define DMP_ACCQD0H 384
#define DMP_ACCQD0L 386
#define DMP_ACCQD1H 388
#define DMP_ACCQD1L 390
#define DMP_ACCQD2H 392
#define DMP_ACCQD2L 394
#define DMP_ACCQD3H 396
#define DMP_ACCQD3L 398
#define DMP_XN2H 400
#define DMP_XN2L 402
#define DMP_XN1H 404
#define DMP_XN1L 406
#define DMP_YN2H 408
#define DMP_YN2L 410
#define DMP_YN1H 412
#define DMP_YN1L 414
#define DMP_YH 416
#define DMP_YL 418
#define DMP_B0H 420
#define DMP_B0L 422
#define DMP_A1H 424
#define DMP_A1L 426
#define DMP_A2H 428
#define DMP_A2L 430
#define DMP_SEM1 432
#define DMP_FIFOCNT 434
#define DMP_SH_TH_X 436
#define DMP_PACKET 438
#define DMP_SH_TH_Y 440
#define DMP_FOOTER 442
#define DMP_SH_TH_Z 444
#define DMP_TEMP29 448
#define DMP_TEMP30 450
#define DMP_XACCB_PRE 452
#define DMP_XACCB_PREL 454
#define DMP_YACCB_PRE 456
#define DMP_YACCB_PREL 458
#define DMP_ZACCB_PRE 460
#define DMP_ZACCB_PREL 462
#define DMP_TMP22 464
#define DMP_TAP_TIMER 466
#define DMP_TAP_THX 468
#define DMP_TAP_THY 472
#define DMP_TAP_THZ 476
#define DMP_TAPW_MIN 478
#define DMP_TMP25 480
#define DMP_TMP26 482
#define DMP_TMP27 484
#define DMP_TMP28 486
#define DMP_ORIENT 488
#define DMP_THRSH 490
#define DMP_ENDIANH 492
#define DMP_ENDIANL 494
#define DMP_BLPFNMTCH 496
#define DMP_BLPFNMTCL 498
#define DMP_BLPFNMXH 500
#define DMP_BLPFNMXL 502
#define DMP_BLPFNMYH 504
#define DMP_BLPFNMYL 506
#define DMP_BLPFNMZH 508
#define DMP_BLPFNMZL 510
#ifdef __cplusplus
}
#endif
#endif // DMPMAP_H

370
Inc/stm32f1xx_hal_conf.h Normal file
View File

@@ -0,0 +1,370 @@
/**
******************************************************************************
* @file stm32f1xx_hal_conf.h
* @brief HAL configuration file.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2020 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F1xx_HAL_CONF_H
#define __STM32F1xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
/*#define HAL_ADC_MODULE_ENABLED */
/*#define HAL_CRYP_MODULE_ENABLED */
/*#define HAL_CAN_MODULE_ENABLED */
/*#define HAL_CEC_MODULE_ENABLED */
/*#define HAL_CORTEX_MODULE_ENABLED */
/*#define HAL_CRC_MODULE_ENABLED */
/*#define HAL_DAC_MODULE_ENABLED */
#define HAL_DMA_MODULE_ENABLED
/*#define HAL_ETH_MODULE_ENABLED */
/*#define HAL_FLASH_MODULE_ENABLED */
#define HAL_GPIO_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
/*#define HAL_I2S_MODULE_ENABLED */
/*#define HAL_IRDA_MODULE_ENABLED */
/*#define HAL_IWDG_MODULE_ENABLED */
/*#define HAL_NOR_MODULE_ENABLED */
/*#define HAL_NAND_MODULE_ENABLED */
/*#define HAL_PCCARD_MODULE_ENABLED */
/*#define HAL_PCD_MODULE_ENABLED */
/*#define HAL_HCD_MODULE_ENABLED */
/*#define HAL_PWR_MODULE_ENABLED */
/*#define HAL_RCC_MODULE_ENABLED */
/*#define HAL_RTC_MODULE_ENABLED */
/*#define HAL_SD_MODULE_ENABLED */
/*#define HAL_MMC_MODULE_ENABLED */
/*#define HAL_SDRAM_MODULE_ENABLED */
/*#define HAL_SMARTCARD_MODULE_ENABLED */
/*#define HAL_SPI_MODULE_ENABLED */
/*#define HAL_SRAM_MODULE_ENABLED */
/*#define HAL_TIM_MODULE_ENABLED */
#define HAL_UART_MODULE_ENABLED
/*#define HAL_USART_MODULE_ENABLED */
/*#define HAL_WWDG_MODULE_ENABLED */
/*#define HAL_EXTI_MODULE_ENABLED */
#define HAL_CORTEX_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
/* ########################## Oscillator Values adaptation ####################*/
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#define LSI_VALUE 40000U /*!< LSI Typical Value in Hz */
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
in voltage and temperature. */
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/* Tip: To avoid modifying this file each time you need to use different HSE,
=== you can define the HSE value in your toolchain compiler preprocessor. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)0) /*!< tick interrupt priority (lowest by default) */
#define USE_RTOS 0
#define PREFETCH_ENABLE 1
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* ################## Ethernet peripheral configuration ##################### */
/* Section 1 : Ethernet peripheral configuration */
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
#define MAC_ADDR0 2
#define MAC_ADDR1 0
#define MAC_ADDR2 0
#define MAC_ADDR3 0
#define MAC_ADDR4 0
#define MAC_ADDR5 0
/* Definition of the Ethernet driver buffers size and count */
#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
#define ETH_RXBUFNB ((uint32_t)8) /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
#define ETH_TXBUFNB ((uint32_t)4) /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
/* Section 2: PHY configuration section */
/* DP83848_PHY_ADDRESS Address*/
#define DP83848_PHY_ADDRESS 0x01U
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
#define PHY_RESET_DELAY ((uint32_t)0x000000FF)
/* PHY Configuration delay */
#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF)
#define PHY_READ_TO ((uint32_t)0x0000FFFF)
#define PHY_WRITE_TO ((uint32_t)0x0000FFFF)
/* Section 3: Common PHY Registers */
#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */
#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */
#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */
#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */
#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */
#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */
#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */
#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */
#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */
#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */
#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */
#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */
#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */
/* Section 4: Extended PHY Registers */
#define PHY_SR ((uint16_t)0x10U) /*!< PHY status register Offset */
#define PHY_SPEED_STATUS ((uint16_t)0x0002U) /*!< PHY Speed mask */
#define PHY_DUPLEX_STATUS ((uint16_t)0x0004U) /*!< PHY Duplex mask */
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32f1xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32f1xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32f1xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f1xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_ETH_MODULE_ENABLED
#include "stm32f1xx_hal_eth.h"
#endif /* HAL_ETH_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32f1xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CEC_MODULE_ENABLED
#include "stm32f1xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f1xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32f1xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32f1xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32f1xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f1xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32f1xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32f1xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32f1xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32f1xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32f1xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32f1xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32f1xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_PCCARD_MODULE_ENABLED
#include "stm32f1xx_hal_pccard.h"
#endif /* HAL_PCCARD_MODULE_ENABLED */
#ifdef HAL_SD_MODULE_ENABLED
#include "stm32f1xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */
#ifdef HAL_MMC_MODULE_ENABLED
#include "stm32f1xx_hal_mmc.h"
#endif /* HAL_MMC_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32f1xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32f1xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32f1xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32f1xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32f1xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32f1xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32f1xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32f1xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32f1xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32f1xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* __STM32F1xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

74
Inc/stm32f1xx_it.h Normal file
View File

@@ -0,0 +1,74 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f1xx_it.h
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F1xx_IT_H
#define __STM32F1xx_IT_H
#ifdef __cplusplus
extern "C" {
#endif
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
void NMI_Handler(void);
void HardFault_Handler(void);
void MemManage_Handler(void);
void BusFault_Handler(void);
void UsageFault_Handler(void);
void SVC_Handler(void);
void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void DMA1_Channel6_IRQHandler(void);
void DMA1_Channel7_IRQHandler(void);
void I2C1_EV_IRQHandler(void);
void I2C1_ER_IRQHandler(void);
void USART2_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __STM32F1xx_IT_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

58
Inc/usart.h Normal file
View File

@@ -0,0 +1,58 @@
/**
******************************************************************************
* File Name : USART.h
* Description : This file provides code for the configuration
* of the USART instances.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __usart_H
#define __usart_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
extern UART_HandleTypeDef huart2;
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
void MX_USART2_UART_Init(void);
/* USER CODE BEGIN Prototypes */
/* USER CODE END Prototypes */
#ifdef __cplusplus
}
#endif
#endif /*__ usart_H */
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

42
Inc/util.h Normal file
View File

@@ -0,0 +1,42 @@
/**
* This file is part of the hoverboard-sideboard-hack project.
*
* Copyright (C) 2020-2021 Emanuel FERU <aerdronix@gmail.com>
*
* 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/>.
*/
// Define to prevent recursive inclusion
#ifndef UTIL_H
#define UTIL_H
#include <stdint.h>
#include "defines.h"
/* general functions */
void consoleLog(char *message);
void get_tick_count_ms(unsigned long *count);
void introDemoLED(uint32_t tDelay);
/* i2c write/read functions */
int8_t i2c_writeBytes(uint8_t slaveAddr, uint8_t regAddr, uint8_t length, uint8_t *data);
int8_t i2c_writeByte (uint8_t slaveAddr, uint8_t regAddr, uint8_t data);
int8_t i2c_writeBit (uint8_t slaveAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data);
int8_t i2c_readBytes (uint8_t slaveAddr, uint8_t regAddr, uint8_t length, uint8_t *data);
int8_t i2c_readByte (uint8_t slaveAddr, uint8_t regAddr, uint8_t *data);
int8_t i2c_readBit (uint8_t slaveAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data);
#endif