Merge pull request '日常更新 2312161132' (#4) from define/firmware_violet_zf:master into master

Reviewed-on: http://git.isthmus.tk:441/btl143/firmware_violet_zf/pulls/4
This commit is contained in:
2023-12-16 11:40:14 +08:00
7 changed files with 400 additions and 356 deletions

View File

@@ -1,24 +1,24 @@
# fireware_violet # fireware_violet
## 使用 VSCode + EIDE + GCC + OpenOCD 开发 ## 1 使用 VSCode + EIDE + GCC + OpenOCD 开发
* 确保 VSCode 安装了 `EIDE` 插件 ### 1.1 前提要求
* 将文件 `firmware_violet.code-workspace_eg` 重命名为 `firmware_violet.code-workspace` 1. VSCode 安装了 `EIDE` 插件
2. 有 Python3 环境
3. 已有沁恒 risc-v 工具链 (MRS 集成开发环境自带)
* 双击 `firmware_violet.code-workspace` 从工作区开启 VSCode ### 1.2 在工作区目录下运行配置脚本
* 工作区设置中修改 EIDE 插件设置,将 `EIDE.RISCV.InstallDirectory``EIDE.OpenOCD.ExePath` 两项设置更改为自己 MRS 下 ToolChains 中 GCC 和 OpenOCD 的路径 ```bash
pyhton ./set_eide_env.py
```
### eg. 根据提示配置两个路径 (OpenOCD 和 riscv-gcc) 即可
`EIDE.RISCV.InstallDirectory` - `D:\Program_Files_nospace\MounRiver\MounRiver_Studio\toolchain\RISC-V Embedded GCC` 配置完成后请先关闭 VSCode再重新双击 `violet_firmware_zf.code-workspace` 文件开启工作区 (否则当前工作区的 OpenOCD 路径配置不会马上生效)
`EIDE.OpenOCD.ExePath` - `D:\Program_Files_nospace\MounRiver\MounRiver_Studio\toolchain\OpenOCD\bin\openocd.exe` ## 2 常用快捷键
然后就可以愉快的使用 VSCode 进行开发和下载了
## 常用快捷键:
* 编译:`F7` * 编译:`F7`

17
app/cw_servo.c Normal file
View File

@@ -0,0 +1,17 @@
#include "zf_common_headfile.h"
#include "cw_servo.h"
void cw_servo_init(void)
{
pwm_init(SERVO_L_PWM_CHANNEL, 50, 1000);
pwm_init(SERVO_R_PWM_CHANNEL, 50, 1000);
}
void cw_servo_set_angle(float servo_l_angle, float servo_r_angle)
{
uint32_t servo_l_duty_s = (uint32_t)(servo_l_angle * SERVO_L_DUTY_PER_ANGLE);
uint32_t servo_r_duty_s = (uint32_t)(servo_r_angle * SERVO_R_DUTY_PER_ANGLE);
pwm_set_duty(SERVO_L_PWM_CHANNEL, servo_l_duty_s);
pwm_set_duty(SERVO_R_PWM_CHANNEL, servo_r_duty_s);
}

20
app/cw_servo.h Normal file
View File

@@ -0,0 +1,20 @@
#ifndef _CW_SERVO_H__
#define _CW_SERVO_H__
#include "zf_common_headfile.h"
#define SERVO_L_PWM_CHANNEL TIM2_PWM_MAP0_CH1_A0
#define SERVO_R_PWM_CHANNEL TIM2_PWM_MAP0_CH2_A1
#define SERVO_MAX_ANGLE_RANGE (90.0F)
#define SERVO_L_DUTY_MAX (1100.0F)
#define SERVO_L_DUTY_MIN (900.0F)
#define SERVO_R_DUTY_MAX (1100.0F)
#define SERVO_R_DUTY_MIN (900.0F)
#define SERVO_L_DUTY_PER_ANGLE ((SERVO_L_DUTY_MAX - SERVO_L_DUTY_MIN) / SERVO_MAX_ANGLE_RANGE)
#define SERVO_R_DUTY_PER_ANGLE ((SERVO_R_DUTY_MAX - SERVO_R_DUTY_MIN) / SERVO_MAX_ANGLE_RANGE)
extern void cw_servo_init(void);
extern void cw_servo_set_angle(float servo_l_angle, float servo_r_angle);
#endif

View File

@@ -33,29 +33,32 @@
* 2022-09-15 <20><>W first version * 2022-09-15 <20><>W first version
********************************************************************************************************************/ ********************************************************************************************************************/
#include "zf_common_headfile.h" #include "zf_common_headfile.h"
#include "cw_servo.h"
#include "by_pt_button.h" #include "by_pt_button.h"
#include "by_fan_control.h" #include "by_fan_control.h"
uint8 mt9v03x_image_cp[MT9V03X_H][MT9V03X_W];
uint16_t pwm_cnt = 0;
int main(void) int main(void)
{ {
clock_init(SYSTEM_CLOCK_120M); // <20><>ʼ<EFBFBD><CABC>оƬʱ<C6AC><CAB1> <20><><EFBFBD><EFBFBD>Ƶ<EFBFBD><C6B5>Ϊ 120MHz clock_init(SYSTEM_CLOCK_120M); // <20><>ʼ<EFBFBD><CABC>оƬʱ<C6AC><CAB1> <20><><EFBFBD><EFBFBD>Ƶ<EFBFBD><C6B5>Ϊ 120MHz
debug_init(); // <20><><EFBFBD>ر<EFBFBD><D8B1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڳ<EFBFBD>ʼ<EFBFBD><CABC>MPU ʱ<><CAB1> <20><><EFBFBD>Դ<EFBFBD><D4B4><EFBFBD> debug_init(); // <20><><EFBFBD>ر<EFBFBD><D8B1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ڳ<EFBFBD>ʼ<EFBFBD><CABC>MPU ʱ<><CAB1> <20><><EFBFBD>Դ<EFBFBD><D4B4><EFBFBD>
// <20>˴<EFBFBD><CBB4><EFBFBD>д<EFBFBD>û<EFBFBD><C3BB><EFBFBD><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
ips114_init(); ips114_init();
by_gpio_init(); by_gpio_init();
by_exit_init(); by_exit_init();
by_pwm_init(); by_pwm_init();
cw_servo_init();
// mt9v03x_init(); // mt9v03x_init();
// <20>˴<EFBFBD><CBB4><EFBFBD>д<EFBFBD>û<EFBFBD><C3BB><EFBFBD><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> // <20>˴<EFBFBD><CBB4><EFBFBD>д<EFBFBD>û<EFBFBD><C3BB><EFBFBD><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
while(1)
{
while (1) {
// <20>˴<EFBFBD><CBB4><EFBFBD>д<EFBFBD><D0B4>Ҫѭ<D2AA><D1AD>ִ<EFBFBD>еĴ<D0B5><C4B4><EFBFBD> // <20>˴<EFBFBD><CBB4><EFBFBD>д<EFBFBD><D0B4>Ҫѭ<D2AA><D1AD>ִ<EFBFBD>еĴ<D0B5><C4B4><EFBFBD>
// <20>˴<EFBFBD><CBB4><EFBFBD>д<EFBFBD><D0B4>Ҫѭ<D2AA><D1AD>ִ<EFBFBD>еĴ<D0B5><C4B4><EFBFBD> // <20>˴<EFBFBD><CBB4><EFBFBD>д<EFBFBD><D0B4>Ҫѭ<D2AA><D1AD>ִ<EFBFBD>еĴ<D0B5><C4B4><EFBFBD>
} }
} }

View File

@@ -50,14 +50,20 @@
#if USE_ZF_TYPEDEF #if USE_ZF_TYPEDEF
// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> // <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
// <20><><EFBFBD><EFBFBD>ʹ<EFBFBD><CAB9> stdint.h <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͻ <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Բü<D4B2> // <20><><EFBFBD><EFBFBD>ʹ<EFBFBD><CAB9> stdint.h <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͻ <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Բü<D4B2>
// <20><><EFBFBD>滰˵<E6BBB0><CBB5>ͦ<EFBFBD>ã<EFBFBD>uint32(aka unsigned int) <20><> uint32_t(aka unsigned long) <20><>һ<EFBFBD><D2BB>
// <20><>Ȼ<EFBFBD><C8BB> 32 λ<><CEBB><EFBFBD>϶<EFBFBD><CFB6><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ֽڣ<D6BD><DAA3><EFBFBD><EFBFBD>Ǿ<EFBFBD>̬<EFBFBD><CCAC><EFBFBD><EFBFBD><EFBFBD>ܻ<EFBFBD><DCBB><EFBFBD><EFBFBD><EFBFBD>ʾ<EFBFBD><CABE><EFBFBD>ܲ<EFBFBD>ˬ<EFBFBD><CBAC><EFBFBD><EFBFBD><EFBFBD>¸ĵ<C2B8>
// typedef unsigned int uint32; // <20>޷<EFBFBD><DEB7><EFBFBD> 32 bits
typedef unsigned char uint8; // <20>޷<EFBFBD><DEB7><EFBFBD> 8 bits typedef unsigned char uint8; // <20>޷<EFBFBD><DEB7><EFBFBD> 8 bits
typedef unsigned short int uint16; // <20>޷<EFBFBD><DEB7><EFBFBD> 16 bits typedef unsigned short uint16; // <20>޷<EFBFBD><DEB7><EFBFBD> 16 bits
typedef unsigned int uint32; // <20>޷<EFBFBD><DEB7><EFBFBD> 32 bits
typedef unsigned long uint32; // <20>޷<EFBFBD><DEB7><EFBFBD> 32 bits
typedef unsigned long long uint64; // <20>޷<EFBFBD><DEB7><EFBFBD> 64 bits typedef unsigned long long uint64; // <20>޷<EFBFBD><DEB7><EFBFBD> 64 bits
typedef signed char int8; // <20>з<EFBFBD><D0B7><EFBFBD> 8 bits typedef signed char int8; // <20>з<EFBFBD><D0B7><EFBFBD> 8 bits
typedef signed short int int16; // <20>з<EFBFBD><D0B7><EFBFBD> 16 bits typedef signed short int16; // <20>з<EFBFBD><D0B7><EFBFBD> 16 bits
typedef signed int int32; // <20>з<EFBFBD><D0B7><EFBFBD> 32 bits typedef signed long int32; // <20>з<EFBFBD><D0B7><EFBFBD> 32 bits
typedef signed long long int64; // <20>з<EFBFBD><D0B7><EFBFBD> 64 bits typedef signed long long int64; // <20>з<EFBFBD><D0B7><EFBFBD> 64 bits
typedef volatile uint8 vuint8; // <20>ױ<EFBFBD><D7B1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> <20>޷<EFBFBD><DEB7><EFBFBD> 8 bits typedef volatile uint8 vuint8; // <20>ױ<EFBFBD><D7B1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> <20>޷<EFBFBD><DEB7><EFBFBD> 8 bits

View File

@@ -63,9 +63,14 @@
#include "zf_device_imu660ra.h" #include "zf_device_imu660ra.h"
int16 imu660ra_gyro_x = 0, imu660ra_gyro_y = 0, imu660ra_gyro_z = 0; // 三轴陀螺仪数据 gyro (陀螺仪) int16 imu660ra_gyro_x = 0;
int16 imu660ra_acc_x = 0, imu660ra_acc_y = 0, imu660ra_acc_z = 0; // 三轴加速度计数据 acc (accelerometer 加速度计) int16 imu660ra_gyro_y = 0;
float imu660ra_transition_factor[2] = {4096, 16.4}; int16 imu660ra_gyro_z = 0; // 三轴陀螺仪数据 gyro (陀螺仪)
int16 imu660ra_acc_x = 0;
int16 imu660ra_acc_y = 0;
int16 imu660ra_acc_z = 0; // 三轴加速度计数据 acc (accelerometer 加速度计)
float imu660ra_temperature = 0;
float imu660ra_transition_factor[2] = {4096, 16.4f};
#if IMU660RA_USE_SOFT_IIC #if IMU660RA_USE_SOFT_IIC
static soft_iic_info_struct imu660ra_iic_struct; static soft_iic_info_struct imu660ra_iic_struct;
@@ -136,8 +141,7 @@ static void imu660ra_read_registers(uint8 reg, uint8 *data, uint32 len)
IMU660RA_CS(0); IMU660RA_CS(0);
spi_read_8bit_registers(IMU660RA_SPI, reg | IMU660RA_SPI_R, temp_data, len + 1); spi_read_8bit_registers(IMU660RA_SPI, reg | IMU660RA_SPI_R, temp_data, len + 1);
IMU660RA_CS(1); IMU660RA_CS(1);
for(int i = 0; i < len; i ++) for (int i = 0; i < len; i++) {
{
*(data++) = temp_data[i + 1]; *(data++) = temp_data[i + 1];
} }
} }
@@ -152,12 +156,11 @@ static void imu660ra_read_registers(uint8 reg, uint8 *data, uint32 len)
//------------------------------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------------------------------
static uint8 imu660ra_self_check(void) static uint8 imu660ra_self_check(void)
{ {
uint8 dat = 0, return_state = 0; uint8 dat = 0;
uint8 return_state = 0;
uint16 timeout_count = 0; uint16 timeout_count = 0;
do do {
{ if (timeout_count++ > IMU660RA_TIMEOUT_COUNT) {
if(timeout_count ++ > IMU660RA_TIMEOUT_COUNT)
{
return_state = 1; return_state = 1;
break; break;
} }
@@ -202,6 +205,14 @@ void imu660ra_get_gyro (void)
imu660ra_gyro_z = (int16)(((uint16)dat[5] << 8 | dat[4])); imu660ra_gyro_z = (int16)(((uint16)dat[5] << 8 | dat[4]));
} }
void imu660ra_get_temperature(void)
{
uint8_t dat[2];
imu660ra_read_registers(IMU660RA_TEMP_ADDRESS, dat, 2);
imu660ra_temperature = (int16_t)((uint16_t)dat[1] << 8 | dat[0]);
imu660ra_temperature = imu660ra_temperature / 512.0f + 23.0f;
}
//------------------------------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------------------------------
// 函数简介 初始化 IMU660RA // 函数简介 初始化 IMU660RA
// 参数说明 void // 参数说明 void
@@ -255,36 +266,29 @@ uint8 imu660ra_init (void)
// 设置为 0x01 加速度计量程为 ±4 g 获取到的加速度计数据除以 8192 可以转化为带物理单位的数据 单位 g(m/s^2) // 设置为 0x01 加速度计量程为 ±4 g 获取到的加速度计数据除以 8192 可以转化为带物理单位的数据 单位 g(m/s^2)
// 设置为 0x02 加速度计量程为 ±8 g 获取到的加速度计数据除以 4096 可以转化为带物理单位的数据 单位 g(m/s^2) // 设置为 0x02 加速度计量程为 ±8 g 获取到的加速度计数据除以 4096 可以转化为带物理单位的数据 单位 g(m/s^2)
// 设置为 0x03 加速度计量程为 ±16 g 获取到的加速度计数据除以 2048 可以转化为带物理单位的数据 单位 g(m/s^2) // 设置为 0x03 加速度计量程为 ±16 g 获取到的加速度计数据除以 2048 可以转化为带物理单位的数据 单位 g(m/s^2)
switch(IMU660RA_ACC_SAMPLE_DEFAULT) switch (IMU660RA_ACC_SAMPLE_DEFAULT) {
{ default: {
default:
{
zf_log(0, "IMU660RA_ACC_SAMPLE_DEFAULT set error."); zf_log(0, "IMU660RA_ACC_SAMPLE_DEFAULT set error.");
return_state = 1; return_state = 1;
} break; } break;
case IMU660RA_ACC_SAMPLE_SGN_2G: case IMU660RA_ACC_SAMPLE_SGN_2G: {
{
imu660ra_write_register(IMU660RA_ACC_RANGE, 0x00); imu660ra_write_register(IMU660RA_ACC_RANGE, 0x00);
imu660ra_transition_factor[0] = 16384; imu660ra_transition_factor[0] = 16384;
} break; } break;
case IMU660RA_ACC_SAMPLE_SGN_4G: case IMU660RA_ACC_SAMPLE_SGN_4G: {
{
imu660ra_write_register(IMU660RA_ACC_RANGE, 0x01); imu660ra_write_register(IMU660RA_ACC_RANGE, 0x01);
imu660ra_transition_factor[0] = 8192; imu660ra_transition_factor[0] = 8192;
} break; } break;
case IMU660RA_ACC_SAMPLE_SGN_8G: case IMU660RA_ACC_SAMPLE_SGN_8G: {
{
imu660ra_write_register(IMU660RA_ACC_RANGE, 0x02); imu660ra_write_register(IMU660RA_ACC_RANGE, 0x02);
imu660ra_transition_factor[0] = 4096; imu660ra_transition_factor[0] = 4096;
} break; } break;
case IMU660RA_ACC_SAMPLE_SGN_16G: case IMU660RA_ACC_SAMPLE_SGN_16G: {
{
imu660ra_write_register(IMU660RA_ACC_RANGE, 0x03); imu660ra_write_register(IMU660RA_ACC_RANGE, 0x03);
imu660ra_transition_factor[0] = 2048; imu660ra_transition_factor[0] = 2048;
} break; } break;
} }
if(1 == return_state) if (1 == return_state) {
{
break; break;
} }
@@ -294,45 +298,35 @@ uint8 imu660ra_init (void)
// 设置为 0x02 陀螺仪量程为 ±500 dps 获取到的陀螺仪数据除以 65.6 可以转化为带物理单位的数据 单位为 °/s // 设置为 0x02 陀螺仪量程为 ±500 dps 获取到的陀螺仪数据除以 65.6 可以转化为带物理单位的数据 单位为 °/s
// 设置为 0x01 陀螺仪量程为 ±1000 dps 获取到的陀螺仪数据除以 32.8 可以转化为带物理单位的数据 单位为 °/s // 设置为 0x01 陀螺仪量程为 ±1000 dps 获取到的陀螺仪数据除以 32.8 可以转化为带物理单位的数据 单位为 °/s
// 设置为 0x00 陀螺仪量程为 ±2000 dps 获取到的陀螺仪数据除以 16.4 可以转化为带物理单位的数据 单位为 °/s // 设置为 0x00 陀螺仪量程为 ±2000 dps 获取到的陀螺仪数据除以 16.4 可以转化为带物理单位的数据 单位为 °/s
switch(IMU660RA_GYRO_SAMPLE_DEFAULT) switch (IMU660RA_GYRO_SAMPLE_DEFAULT) {
{ default: {
default:
{
zf_log(0, "IMU660RA_GYRO_SAMPLE_DEFAULT set error."); zf_log(0, "IMU660RA_GYRO_SAMPLE_DEFAULT set error.");
return_state = 1; return_state = 1;
} break; } break;
case IMU660RA_GYRO_SAMPLE_SGN_125DPS: case IMU660RA_GYRO_SAMPLE_SGN_125DPS: {
{
imu660ra_write_register(IMU660RA_GYR_RANGE, 0x04); imu660ra_write_register(IMU660RA_GYR_RANGE, 0x04);
imu660ra_transition_factor[1] = 262.4; imu660ra_transition_factor[1] = 262.4;
} break; } break;
case IMU660RA_GYRO_SAMPLE_SGN_250DPS: case IMU660RA_GYRO_SAMPLE_SGN_250DPS: {
{
imu660ra_write_register(IMU660RA_GYR_RANGE, 0x03); imu660ra_write_register(IMU660RA_GYR_RANGE, 0x03);
imu660ra_transition_factor[1] = 131.2; imu660ra_transition_factor[1] = 131.2;
} break; } break;
case IMU660RA_GYRO_SAMPLE_SGN_500DPS: case IMU660RA_GYRO_SAMPLE_SGN_500DPS: {
{
imu660ra_write_register(IMU660RA_GYR_RANGE, 0x02); imu660ra_write_register(IMU660RA_GYR_RANGE, 0x02);
imu660ra_transition_factor[1] = 65.6; imu660ra_transition_factor[1] = 65.6;
} break; } break;
case IMU660RA_GYRO_SAMPLE_SGN_1000DPS: case IMU660RA_GYRO_SAMPLE_SGN_1000DPS: {
{
imu660ra_write_register(IMU660RA_GYR_RANGE, 0x01); imu660ra_write_register(IMU660RA_GYR_RANGE, 0x01);
imu660ra_transition_factor[1] = 32.8; imu660ra_transition_factor[1] = 32.8;
} break; } break;
case IMU660RA_GYRO_SAMPLE_SGN_2000DPS: case IMU660RA_GYRO_SAMPLE_SGN_2000DPS: {
{
imu660ra_write_register(IMU660RA_GYR_RANGE, 0x00); imu660ra_write_register(IMU660RA_GYR_RANGE, 0x00);
imu660ra_transition_factor[1] = 16.4; imu660ra_transition_factor[1] = 16.4;
} break; } break;
} }
if(1 == return_state) if (1 == return_state) {
{
break; break;
} }
} while (0); } while (0);
return return_state; return return_state;
} }

View File

@@ -58,12 +58,12 @@
#include "zf_common_typedef.h" #include "zf_common_typedef.h"
#define IMU660RA_USE_SOFT_IIC (0) // 默认使用硬件 SPI 方式驱动 #define IMU660RA_USE_SOFT_IIC (1) // 默认使用硬件 SPI 方式驱动
#if IMU660RA_USE_SOFT_IIC // 这两段 颜色正常的才是正确的 颜色灰的就是没有用的 #if IMU660RA_USE_SOFT_IIC // 这两段 颜色正常的才是正确的 颜色灰的就是没有用的
//====================================================软件 IIC 驱动==================================================== //====================================================软件 IIC 驱动====================================================
#define IMU660RA_SOFT_IIC_DELAY (10) // 软件 IIC 的时钟延时周期 数值越小 IIC 通信速率越快 #define IMU660RA_SOFT_IIC_DELAY (10) // 软件 IIC 的时钟延时周期 数值越小 IIC 通信速率越快
#define IMU660RA_SCL_PIN (B13) // 软件 IIC SCL 引脚 连接 IMU660RA 的 SCL 引脚 #define IMU660RA_SCL_PIN (B3) // 软件 IIC SCL 引脚 连接 IMU660RA 的 SCL 引脚
#define IMU660RA_SDA_PIN (B15) // 软件 IIC SDA 引脚 连接 IMU660RA 的 SDA 引脚 #define IMU660RA_SDA_PIN (B5) // 软件 IIC SDA 引脚 连接 IMU660RA 的 SDA 引脚
//====================================================软件 IIC 驱动==================================================== //====================================================软件 IIC 驱动====================================================
#else #else
@@ -79,16 +79,14 @@
#define IMU660RA_CS_PIN (C10) // CS 片选引脚 #define IMU660RA_CS_PIN (C10) // CS 片选引脚
#define IMU660RA_CS(x) ((x) ? (gpio_high(IMU660RA_CS_PIN)) : (gpio_low(IMU660RA_CS_PIN))) #define IMU660RA_CS(x) ((x) ? (gpio_high(IMU660RA_CS_PIN)) : (gpio_low(IMU660RA_CS_PIN)))
typedef enum typedef enum {
{
IMU660RA_ACC_SAMPLE_SGN_2G, // 加速度计量程 ±2G (ACC = Accelerometer 加速度计) (SGN = signum 带符号数 表示正负范围) (G = g 重力加速度 g≈9.80 m/s^2) IMU660RA_ACC_SAMPLE_SGN_2G, // 加速度计量程 ±2G (ACC = Accelerometer 加速度计) (SGN = signum 带符号数 表示正负范围) (G = g 重力加速度 g≈9.80 m/s^2)
IMU660RA_ACC_SAMPLE_SGN_4G, // 加速度计量程 ±4G (ACC = Accelerometer 加速度计) (SGN = signum 带符号数 表示正负范围) (G = g 重力加速度 g≈9.80 m/s^2) IMU660RA_ACC_SAMPLE_SGN_4G, // 加速度计量程 ±4G (ACC = Accelerometer 加速度计) (SGN = signum 带符号数 表示正负范围) (G = g 重力加速度 g≈9.80 m/s^2)
IMU660RA_ACC_SAMPLE_SGN_8G, // 加速度计量程 ±8G (ACC = Accelerometer 加速度计) (SGN = signum 带符号数 表示正负范围) (G = g 重力加速度 g≈9.80 m/s^2) IMU660RA_ACC_SAMPLE_SGN_8G, // 加速度计量程 ±8G (ACC = Accelerometer 加速度计) (SGN = signum 带符号数 表示正负范围) (G = g 重力加速度 g≈9.80 m/s^2)
IMU660RA_ACC_SAMPLE_SGN_16G, // 加速度计量程 ±16G (ACC = Accelerometer 加速度计) (SGN = signum 带符号数 表示正负范围) (G = g 重力加速度 g≈9.80 m/s^2) IMU660RA_ACC_SAMPLE_SGN_16G, // 加速度计量程 ±16G (ACC = Accelerometer 加速度计) (SGN = signum 带符号数 表示正负范围) (G = g 重力加速度 g≈9.80 m/s^2)
} imu660ra_acc_sample_config; } imu660ra_acc_sample_config;
typedef enum typedef enum {
{
IMU660RA_GYRO_SAMPLE_SGN_125DPS, // 陀螺仪量程 ±125DPS (GYRO = Gyroscope 陀螺仪) (SGN = signum 带符号数 表示正负范围) (DPS = Degree Per Second 角速度单位 °/S) IMU660RA_GYRO_SAMPLE_SGN_125DPS, // 陀螺仪量程 ±125DPS (GYRO = Gyroscope 陀螺仪) (SGN = signum 带符号数 表示正负范围) (DPS = Degree Per Second 角速度单位 °/S)
IMU660RA_GYRO_SAMPLE_SGN_250DPS, // 陀螺仪量程 ±250DPS (GYRO = Gyroscope 陀螺仪) (SGN = signum 带符号数 表示正负范围) (DPS = Degree Per Second 角速度单位 °/S) IMU660RA_GYRO_SAMPLE_SGN_250DPS, // 陀螺仪量程 ±250DPS (GYRO = Gyroscope 陀螺仪) (SGN = signum 带符号数 表示正负范围) (DPS = Degree Per Second 角速度单位 °/S)
IMU660RA_GYRO_SAMPLE_SGN_500DPS, // 陀螺仪量程 ±500DPS (GYRO = Gyroscope 陀螺仪) (SGN = signum 带符号数 表示正负范围) (DPS = Degree Per Second 角速度单位 °/S) IMU660RA_GYRO_SAMPLE_SGN_500DPS, // 陀螺仪量程 ±500DPS (GYRO = Gyroscope 陀螺仪) (SGN = signum 带符号数 表示正负范围) (DPS = Degree Per Second 角速度单位 °/S)
@@ -112,6 +110,7 @@ typedef enum
#define IMU660RA_INIT_CTRL (0x59) #define IMU660RA_INIT_CTRL (0x59)
#define IMU660RA_INIT_DATA (0x5E) #define IMU660RA_INIT_DATA (0x5E)
#define IMU660RA_INT_STA (0x21) #define IMU660RA_INT_STA (0x21)
#define IMU660RA_TEMP_ADDRESS (0x22)
#define IMU660RA_ACC_ADDRESS (0x0C) #define IMU660RA_ACC_ADDRESS (0x0C)
#define IMU660RA_GYRO_ADDRESS (0x12) #define IMU660RA_GYRO_ADDRESS (0x12)
#define IMU660RA_ACC_CONF (0x40) #define IMU660RA_ACC_CONF (0x40)
@@ -120,12 +119,18 @@ typedef enum
#define IMU660RA_GYR_RANGE (0x43) #define IMU660RA_GYR_RANGE (0x43)
//================================================定义 IMU660RA 内部地址================================================ //================================================定义 IMU660RA 内部地址================================================
extern int16 imu660ra_gyro_x, imu660ra_gyro_y, imu660ra_gyro_z; // 三轴陀螺仪数据 gyro (陀螺仪) extern int16 imu660ra_gyro_x;
extern int16 imu660ra_acc_x, imu660ra_acc_y, imu660ra_acc_z; // 三轴加速度计数据 acc (accelerometer 加速度计) extern int16 imu660ra_gyro_y;
extern int16 imu660ra_gyro_z; // 三轴陀螺仪数据 gyro (陀螺仪)
extern int16 imu660ra_acc_x;
extern int16 imu660ra_acc_y;
extern int16 imu660ra_acc_z; // 三轴加速度计数据 acc (accelerometer 加速度计)
extern float imu660ra_temperature;
extern float imu660ra_transition_factor[2]; extern float imu660ra_transition_factor[2];
void imu660ra_get_acc(void); // 获取 IMU660RA 加速度计数据 void imu660ra_get_acc(void); // 获取 IMU660RA 加速度计数据
void imu660ra_get_gyro(void); // 获取 IMU660RA 陀螺仪数据 void imu660ra_get_gyro(void); // 获取 IMU660RA 陀螺仪数据
void imu660ra_get_temperature(void);
//------------------------------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------------------------------
// 函数简介 将 IMU660RA 加速度计数据转换为实际物理数据 // 函数简介 将 IMU660RA 加速度计数据转换为实际物理数据
@@ -148,4 +153,3 @@ void imu660ra_get_gyro (void);
uint8 imu660ra_init(void); // 初始化 IMU660RA uint8 imu660ra_init(void); // 初始化 IMU660RA
#endif #endif