Skip to content

Commit

Permalink
Merge pull request #599 from sugihara-16/PR/feature/spinal/imu/icm20948
Browse files Browse the repository at this point in the history
[Spinal][IMU] developing a interface for ICM20948
  • Loading branch information
tongtybj committed Jun 25, 2024
2 parents d0be362 + 0d95e29 commit 4b56854
Show file tree
Hide file tree
Showing 19 changed files with 951 additions and 98 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,8 @@
/* Sensors */
#if IMU_FLAG
#include "sensors/imu/imu_ros_cmd.h"
#include "sensors/imu/imu_mpu9250.h"
#include "sensors/imu/drivers/mpu9250/imu_mpu9250.h"
#include "sensors/imu/drivers/icm20948/icm_20948.h"
#endif

#if BARO_FLAG
Expand Down Expand Up @@ -98,8 +99,10 @@ bool start_processing_flag_ = false; //to prevent systick_callback starting bef

ros::NodeHandle nh_;

#if IMU_FLAG
#if IMU_MPU
IMUOnboard imu_;
#elif IMU_ICM
ICM20948 imu_;
#endif

#if BARO_FLAG
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,8 @@ void Error_Handler(void);
#define RMII_TXD1_GPIO_Port GPIOB
#define IMUCS_Pin GPIO_PIN_6
#define IMUCS_GPIO_Port GPIOB
#define SPI1_CS_Pin GPIO_PIN_7
#define SPI1_CS_GPIO_Port GPIOB
#define BAROCS_Pin GPIO_PIN_1
#define BAROCS_GPIO_Port GPIOE
/* USER CODE BEGIN Private defines */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.fpu.1560105099" name="Floating-point unit" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.fpu" useByScannerDiscovery="true" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.fpu.value.fpv5-d16" valueType="enumerated"/>
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.floatabi.451674053" name="Floating-point ABI" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.floatabi" useByScannerDiscovery="true" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.floatabi.value.hard" valueType="enumerated"/>
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.target_board.1123785686" name="Board" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.target_board" useByScannerDiscovery="false" value="genericBoard" valueType="string"/>
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.defaults.785140283" name="Defaults" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.defaults" useByScannerDiscovery="false" value="com.st.stm32cube.ide.common.services.build.inputs.revA.1.0.5 || Debug || true || Executable || com.st.stm32cube.ide.mcu.gnu.managedbuild.toolchain.base.gnu-tools-for-stm32 || STM32H743VITx || 0 || 0 || arm-none-eabi- || ${gnu_tools_for_stm32_compiler_path} || ../../Drivers/CMSIS/Include | ../../Middlewares/Third_Party/LwIP/src/include/lwip/priv | ../../Middlewares/Third_Party/LwIP/src/include/netif/ppp | ../../Middlewares/Third_Party/LwIP/src/include/lwip/apps | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/net | ../../Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS | ../../Middlewares/Third_Party/LwIP/src/include/lwip | ../../Middlewares/Third_Party/LwIP/src/include/lwip/prot | ../../Drivers/STM32H7xx_HAL_Driver/Inc | ../../Middlewares/Third_Party/LwIP/src/include/compat/stdc | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix | ../../Drivers/CMSIS/Device/ST/STM32H7xx/Include | ../../Middlewares/Third_Party/LwIP/system/arch | ../../Middlewares/Third_Party/FreeRTOS/Source/include | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/sys | ../../Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F | ../../Inc | ../../Drivers/STM32H7xx_HAL_Driver/Inc/Legacy | ../../Middlewares/Third_Party/LwIP/system | ../../Middlewares/Third_Party/LwIP/src/include | ../../Middlewares/Third_Party/LwIP/src/include/netif | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/arpa | ../../Drivers/BSP/Components/lan8742 || || || USE_HAL_DRIVER | STM32H743xx || || || || || ${workspace_loc:/${ProjName}/STM32H743VITX_FLASH.ld} || true || NonSecure || || secure_nsclib.o || || None || " valueType="string"/>
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.defaults.785140283" name="Defaults" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.defaults" useByScannerDiscovery="false" value="com.st.stm32cube.ide.common.services.build.inputs.revA.1.0.5 || Debug || true || Executable || com.st.stm32cube.ide.mcu.gnu.managedbuild.toolchain.base.gnu-tools-for-stm32 || STM32H743VITx || 0 || 0 || arm-none-eabi- || ${gnu_tools_for_stm32_compiler_path} || ../../Drivers/CMSIS/Include | ../../Middlewares/Third_Party/LwIP/src/include/lwip/priv | ../../Middlewares/Third_Party/LwIP/src/include/netif/ppp | ../../Middlewares/Third_Party/LwIP/src/include/lwip/apps | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/net | ../../Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS | ../../Middlewares/Third_Party/LwIP/src/include/lwip | ../../Middlewares/Third_Party/LwIP/src/include/lwip/prot | ../../Drivers/STM32H7xx_HAL_Driver/Inc | ../../Middlewares/Third_Party/LwIP/src/include/compat/stdc | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix | ../../Drivers/BSP/Components/lan8742 | ../../Drivers/CMSIS/Device/ST/STM32H7xx/Include | ../../Middlewares/Third_Party/LwIP/system/arch | ../../Middlewares/Third_Party/FreeRTOS/Source/include | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/sys | ../../Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F | ../../Inc | ../../Drivers/STM32H7xx_HAL_Driver/Inc/Legacy | ../../Middlewares/Third_Party/LwIP/system | ../../Middlewares/Third_Party/LwIP/src/include | ../../Middlewares/Third_Party/LwIP/src/include/netif | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/arpa || || || USE_HAL_DRIVER | STM32H743xx || || || || || ${workspace_loc:/${ProjName}/STM32H743VITX_FLASH.ld} || true || NonSecure || || secure_nsclib.o || || None || " valueType="string"/>
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.toolchain.1808345384" name="Toolchain" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.toolchain" useByScannerDiscovery="false" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.toolchain.base.gnu-tools-for-stm32.9-2020-q2-update" valueType="string"/>
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="com.st.stm32cube.ide.mcu.gnu.managedbuild.targetplatform.1732425603" isAbstract="false" osList="all" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.targetplatform"/>
<builder buildPath="${workspace_loc:/spinal}/Debug" id="com.st.stm32cube.ide.mcu.gnu.managedbuild.builder.530361035" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="Gnu Make Builder" parallelBuildOn="true" parallelizationNumber="optimal" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.builder"/>
Expand Down Expand Up @@ -209,7 +209,7 @@
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.fpu.619623993" name="Floating-point unit" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.fpu" useByScannerDiscovery="true" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.fpu.value.fpv5-d16" valueType="enumerated"/>
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.floatabi.579314840" name="Floating-point ABI" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.floatabi" useByScannerDiscovery="true" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.floatabi.value.hard" valueType="enumerated"/>
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.target_board.1946193872" name="Board" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.target_board" useByScannerDiscovery="false" value="genericBoard" valueType="string"/>
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.defaults.15398046" name="Defaults" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.defaults" useByScannerDiscovery="false" value="com.st.stm32cube.ide.common.services.build.inputs.revA.1.0.5 || Release || false || Executable || com.st.stm32cube.ide.mcu.gnu.managedbuild.toolchain.base.gnu-tools-for-stm32 || STM32H743VITx || 0 || 0 || arm-none-eabi- || ${gnu_tools_for_stm32_compiler_path} || ../../Drivers/CMSIS/Include | ../../Middlewares/Third_Party/LwIP/src/include/lwip/priv | ../../Middlewares/Third_Party/LwIP/src/include/netif/ppp | ../../Middlewares/Third_Party/LwIP/src/include/lwip/apps | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/net | ../../Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS | ../../Middlewares/Third_Party/LwIP/src/include/lwip | ../../Middlewares/Third_Party/LwIP/src/include/lwip/prot | ../../Drivers/STM32H7xx_HAL_Driver/Inc | ../../Middlewares/Third_Party/LwIP/src/include/compat/stdc | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix | ../../Drivers/CMSIS/Device/ST/STM32H7xx/Include | ../../Middlewares/Third_Party/LwIP/system/arch | ../../Middlewares/Third_Party/FreeRTOS/Source/include | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/sys | ../../Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F | ../../Inc | ../../Drivers/STM32H7xx_HAL_Driver/Inc/Legacy | ../../Middlewares/Third_Party/LwIP/system | ../../Middlewares/Third_Party/LwIP/src/include | ../../Middlewares/Third_Party/LwIP/src/include/netif | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/arpa | ../../Drivers/BSP/Components/lan8742 || || || USE_HAL_DRIVER | STM32H743xx || || || || || ${workspace_loc:/${ProjName}/STM32H743VITX_FLASH.ld} || true || NonSecure || || secure_nsclib.o || || None || " valueType="string"/>
<option id="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.defaults.15398046" name="Defaults" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.option.defaults" useByScannerDiscovery="false" value="com.st.stm32cube.ide.common.services.build.inputs.revA.1.0.5 || Release || false || Executable || com.st.stm32cube.ide.mcu.gnu.managedbuild.toolchain.base.gnu-tools-for-stm32 || STM32H743VITx || 0 || 0 || arm-none-eabi- || ${gnu_tools_for_stm32_compiler_path} || ../../Drivers/CMSIS/Include | ../../Middlewares/Third_Party/LwIP/src/include/lwip/priv | ../../Middlewares/Third_Party/LwIP/src/include/netif/ppp | ../../Middlewares/Third_Party/LwIP/src/include/lwip/apps | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/net | ../../Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS | ../../Middlewares/Third_Party/LwIP/src/include/lwip | ../../Middlewares/Third_Party/LwIP/src/include/lwip/prot | ../../Drivers/STM32H7xx_HAL_Driver/Inc | ../../Middlewares/Third_Party/LwIP/src/include/compat/stdc | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix | ../../Drivers/BSP/Components/lan8742 | ../../Drivers/CMSIS/Device/ST/STM32H7xx/Include | ../../Middlewares/Third_Party/LwIP/system/arch | ../../Middlewares/Third_Party/FreeRTOS/Source/include | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/sys | ../../Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F | ../../Inc | ../../Drivers/STM32H7xx_HAL_Driver/Inc/Legacy | ../../Middlewares/Third_Party/LwIP/system | ../../Middlewares/Third_Party/LwIP/src/include | ../../Middlewares/Third_Party/LwIP/src/include/netif | ../../Middlewares/Third_Party/LwIP/src/include/compat/posix/arpa || || || USE_HAL_DRIVER | STM32H743xx || || || || || ${workspace_loc:/${ProjName}/STM32H743VITX_FLASH.ld} || true || NonSecure || || secure_nsclib.o || || None || " valueType="string"/>
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="com.st.stm32cube.ide.mcu.gnu.managedbuild.targetplatform.2052134197" isAbstract="false" osList="all" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.targetplatform"/>
<builder buildPath="${workspace_loc:/spinal}/Release" id="com.st.stm32cube.ide.mcu.gnu.managedbuild.builder.843691260" keepEnvironmentInBuildfile="false" managedBuildOn="true" name="Gnu Make Builder" parallelBuildOn="true" parallelizationNumber="optimal" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.builder"/>
<tool id="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.assembler.1567965632" name="MCU GCC Assembler" superClass="com.st.stm32cube.ide.mcu.gnu.managedbuild.tool.assembler">
Expand Down Expand Up @@ -341,4 +341,5 @@
<autodiscovery enabled="false" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
</storageModule>
<storageModule moduleId="refreshScope"/>
</cproject>
25 changes: 18 additions & 7 deletions aerial_robot_nerve/spinal/mcu_project/boards/stm32H7/Src/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,8 @@
#include <spinal/Imu.h>

#include "flashmemory/flashmemory.h"
#include "sensors/imu/imu_mpu9250.h"
#include "sensors/imu/drivers/mpu9250/imu_mpu9250.h"
#include "sensors/imu/drivers/icm20948/icm_20948.h"
#include "sensors/imu/imu_ros_cmd.h"
#include "sensors/baro/baro_ms5611.h"
#include "sensors/gps/gps_ublox.h"
Expand Down Expand Up @@ -100,7 +101,11 @@ osMailQId canMsgMailHandle;
ros::NodeHandle nh_;

/* sensor instances */
#if IMU_MPU
IMUOnboard imu_;
#elif IMU_ICM
ICM20948 imu_;
#endif
Baro baro_;
GPS gps_;
BatteryStatus battery_status_;
Expand Down Expand Up @@ -293,7 +298,7 @@ int main(void)

/* Create the thread(s) */
/* definition and creation of coreTask */
osThreadDef(coreTask, coreTaskFunc, osPriorityRealtime, 0, 512);
osThreadDef(coreTask, coreTaskFunc, osPriorityRealtime, 0, 1024);
coreTaskHandle = osThreadCreate(osThread(coreTask), NULL);

/* definition and creation of rosSpinTask */
Expand Down Expand Up @@ -650,10 +655,10 @@ static void MX_SPI1_Init(void)
hspi1.Init.Mode = SPI_MODE_MASTER;
hspi1.Init.Direction = SPI_DIRECTION_2LINES;
hspi1.Init.DataSize = SPI_DATASIZE_8BIT;
hspi1.Init.CLKPolarity = SPI_POLARITY_LOW;
hspi1.Init.CLKPhase = SPI_PHASE_1EDGE;
hspi1.Init.CLKPolarity = SPI_POLARITY_HIGH;
hspi1.Init.CLKPhase = SPI_PHASE_2EDGE;
hspi1.Init.NSS = SPI_NSS_SOFT;
hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256;
hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_32;
hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
hspi1.Init.TIMode = SPI_TIMODE_DISABLE;
hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
Expand Down Expand Up @@ -981,7 +986,7 @@ static void MX_GPIO_Init(void)
HAL_GPIO_WritePin(GPIOE, LED0_Pin|LED1_Pin|LED2_Pin|BAROCS_Pin, GPIO_PIN_RESET);

/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(IMUCS_GPIO_Port, IMUCS_Pin, GPIO_PIN_RESET);
HAL_GPIO_WritePin(GPIOB, IMUCS_Pin|SPI1_CS_Pin, GPIO_PIN_SET);

/*Configure GPIO pins : LED0_Pin LED1_Pin LED2_Pin */
GPIO_InitStruct.Pin = LED0_Pin|LED1_Pin|LED2_Pin;
Expand All @@ -997,6 +1002,13 @@ static void MX_GPIO_Init(void)
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_MEDIUM;
HAL_GPIO_Init(IMUCS_GPIO_Port, &GPIO_InitStruct);

/*Configure GPIO pin : SPI1_CS_Pin */
GPIO_InitStruct.Pin = SPI1_CS_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
HAL_GPIO_Init(SPI1_CS_GPIO_Port, &GPIO_InitStruct);

/*Configure GPIO pin : BAROCS_Pin */
GPIO_InitStruct.Pin = BAROCS_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
Expand Down Expand Up @@ -1055,7 +1067,6 @@ void coreTaskFunc(void const * argument)
#if NERVE_COMM
Spine::send();
#endif

imu_.update();
baro_.update();
gps_.update();
Expand Down
38 changes: 24 additions & 14 deletions aerial_robot_nerve/spinal/mcu_project/boards/stm32H7/spinal.ioc
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ FREERTOS.BinarySemaphores01=coreTaskSem,Dynamic,NULL;uartTxSem,Dynamic,NULL
FREERTOS.FootprintOK=true
FREERTOS.IPParameters=Tasks01,configTOTAL_HEAP_SIZE,FootprintOK,configUSE_TIMERS,configTIMER_TASK_PRIORITY,Timers01,BinarySemaphores01,Mutexes01
FREERTOS.Mutexes01=rosPubMutex,Dynamic,NULL;flightControlMutex,Dynamic,NULL
FREERTOS.Tasks01=coreTask,3,512,coreTaskFunc,Default,NULL,Dynamic,NULL,NULL;rosSpinTask,0,256,rosSpinTaskFunc,Default,NULL,Dynamic,NULL,NULL;idleTask,-3,128,idleTaskFunc,Default,NULL,Dynamic,NULL,NULL;rosPublish,-1,128,rosPublishTask,Default,NULL,Dynamic,NULL,NULL;voltage,-2,256,voltageTask,Default,NULL,Dynamic,NULL,NULL;canRx,3,256,canRxTask,As weak,NULL,Dynamic,NULL,NULL
FREERTOS.Tasks01=coreTask,3,1024,coreTaskFunc,Default,NULL,Dynamic,NULL,NULL;rosSpinTask,0,256,rosSpinTaskFunc,Default,NULL,Dynamic,NULL,NULL;idleTask,-3,128,idleTaskFunc,Default,NULL,Dynamic,NULL,NULL;rosPublish,-1,128,rosPublishTask,Default,NULL,Dynamic,NULL,NULL;voltage,-2,256,voltageTask,Default,NULL,Dynamic,NULL,NULL;canRx,3,256,canRxTask,As weak,NULL,Dynamic,NULL,NULL
FREERTOS.Timers01=coreTaskTimer,coreTaskEvokeCb,osTimerPeriodic,Default,NULL,Dynamic,NULL
FREERTOS.configTIMER_TASK_PRIORITY=6
FREERTOS.configTOTAL_HEAP_SIZE=25600
Expand Down Expand Up @@ -211,21 +211,22 @@ Mcu.Pin35=PB3 (JTDO/TRACESWO)
Mcu.Pin36=PB4 (NJTRST)
Mcu.Pin37=PB5
Mcu.Pin38=PB6
Mcu.Pin39=PB8
Mcu.Pin39=PB7
Mcu.Pin4=PH1-OSC_OUT (PH1)
Mcu.Pin40=PB9
Mcu.Pin41=PE1
Mcu.Pin42=VP_FREERTOS_VS_CMSIS_V1
Mcu.Pin43=VP_LWIP_VS_Enabled
Mcu.Pin44=VP_SYS_VS_tim12
Mcu.Pin45=VP_TIM1_VS_ClockSourceINT
Mcu.Pin46=VP_TIM4_VS_ClockSourceINT
Mcu.Pin40=PB8
Mcu.Pin41=PB9
Mcu.Pin42=PE1
Mcu.Pin43=VP_FREERTOS_VS_CMSIS_V1
Mcu.Pin44=VP_LWIP_VS_Enabled
Mcu.Pin45=VP_SYS_VS_tim12
Mcu.Pin46=VP_TIM1_VS_ClockSourceINT
Mcu.Pin47=VP_TIM4_VS_ClockSourceINT
Mcu.Pin5=PC1
Mcu.Pin6=PA1
Mcu.Pin7=PA2
Mcu.Pin8=PA3
Mcu.Pin9=PA4
Mcu.PinsNb=47
Mcu.PinsNb=48
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32H743VITx
Expand Down Expand Up @@ -322,12 +323,19 @@ PB5.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
PB5.Locked=true
PB5.Mode=Full_Duplex_Master
PB5.Signal=SPI1_MOSI
PB6.GPIOParameters=GPIO_Speed,GPIO_FM6,GPIO_Label
PB6.GPIOParameters=GPIO_Speed,GPIO_FM6,PinState,GPIO_Label
PB6.GPIO_FM6=__NULL
PB6.GPIO_Label=IMUCS
PB6.GPIO_Speed=GPIO_SPEED_FREQ_MEDIUM
PB6.Locked=true
PB6.PinState=GPIO_PIN_SET
PB6.Signal=GPIO_Output
PB7.GPIOParameters=GPIO_Speed,PinState,GPIO_Label
PB7.GPIO_Label=SPI1_CS
PB7.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PB7.Locked=true
PB7.PinState=GPIO_PIN_SET
PB7.Signal=GPIO_Output
PB8.Locked=true
PB8.Mode=I2C
PB8.Signal=I2C1_SCL
Expand Down Expand Up @@ -536,11 +544,13 @@ SH.S_TIM4_CH3.0=TIM4_CH3,PWM Generation3 CH3
SH.S_TIM4_CH3.ConfNb=1
SH.S_TIM4_CH4.0=TIM4_CH4,PWM Generation4 CH4
SH.S_TIM4_CH4.ConfNb=1
SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_256
SPI1.CalculateBaudRate=781.25 KBits/s
SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_32
SPI1.CLKPhase=SPI_PHASE_2EDGE
SPI1.CLKPolarity=SPI_POLARITY_HIGH
SPI1.CalculateBaudRate=6.25 MBits/s
SPI1.DataSize=SPI_DATASIZE_8BIT
SPI1.Direction=SPI_DIRECTION_2LINES
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler,DataSize
SPI1.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler,DataSize,CLKPolarity,CLKPhase
SPI1.Mode=SPI_MODE_MASTER
SPI1.VirtualType=VM_MASTER
TIM1.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
Expand Down
2 changes: 2 additions & 0 deletions aerial_robot_nerve/spinal/mcu_project/lib/Jsk_Lib/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@
//2.1 Sensors
//2.1.1 IMU Sensor
#define IMU_FLAG 1
#define IMU_MPU 0
#define IMU_ICM 1
//2.1.2 Barometer Sensor
#define BARO_FLAG 1
//2.1.3 GPS Sensor
Expand Down
Loading

0 comments on commit 4b56854

Please sign in to comment.