大更新

This commit is contained in:
Robofish 2025-09-06 13:04:19 +08:00
parent d626e4e656
commit f1c6b085a4
22 changed files with 277 additions and 206 deletions

View File

@ -11,6 +11,12 @@
"device.h": "c",
"gpio.h": "c",
"uart.h": "c",
"motor_rm.h": "c"
"motor_rm.h": "c",
"mm.h": "c",
"capacity.h": "c",
"error_detect.h": "c",
"bmi088.h": "c",
"time.h": "c",
"motor.h": "c"
}
}

BIN
assets/.DS_Store vendored

Binary file not shown.

View File

@ -1,12 +0,0 @@
/*
*/
#include "ballistics.h"
void Ballistics_Init(Ballistics_t *b) { (void)b; }
void Ballistics_Apply(Ballistics_t *b, float bullet_speed) {
(void)b;
(void)bullet_speed;
}
void Ballistics_Reset(Ballistics_t *b) { (void)b; }

View File

@ -1,23 +0,0 @@
/*
*/
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include "ahrs.h"
typedef struct {
AHRS_Eulr_t *eulr;
} Ballistics_t;
void Ballistics_Init(Ballistics_t *b);
void Ballistics_Apply(Ballistics_t *b, float bullet_speed);
void Ballistics_Reset(Ballistics_t *b);
#ifdef __cplusplus
}
#endif

View File

@ -1,6 +1,5 @@
/*
*/

View File

@ -11,7 +11,7 @@ extern "C" {
#include <stdbool.h>
#include <stdint.h>
#include "ahrs.h"
#include "component/ahrs.h"
#define CMD_REFEREE_MAX_NUM (3) /* 发送命令限定的最大数量 */

View File

@ -1,3 +1,8 @@
ahrs,component/user_math.h
capacity,component/user_math.h
cmd,component/ahrs
error_detect,bsp/mm
pid,component/filter
ahrs,component/filter
filter,component/ahrs
filter,component/ahrs
mixer,component/user_math.h
ui,component/user_math.h
1 pid ahrs component/filter component/user_math.h
1 ahrs component/user_math.h
2 capacity component/user_math.h
3 cmd component/ahrs
4 error_detect bsp/mm
5 pid pid component/filter component/filter
6 ahrs filter component/filter component/ahrs
7 filter mixer component/ahrs component/user_math.h
8 ui component/user_math.h

View File

@ -1,2 +1,14 @@
pid,好用的
ahrs,开源的
ahrs,开源的AHRS算法MadgwickAHRS
capacity,电池容量计算
cmd,通用控制命令
crc8,CRC8校验rm
crc16,CRC16校验rm
error_detect,错误检测
filter,各类滤波器
FreeRTOS_CLI,FreeRTOS命令行接口
limiter,限幅器
mixer,混控器
ui,用户交互
user_math,用户自定义数学函数
pid,PID控制器
1 pid 好用的
2 ahrs 开源的 开源的AHRS算法,MadgwickAHRS
3 capacity 电池容量计算
4 cmd 通用控制命令
5 crc8 CRC8校验rm
6 crc16 CRC16校验rm
7 error_detect 错误检测
8 filter 各类滤波器
9 FreeRTOS_CLI FreeRTOS命令行接口
10 limiter 限幅器
11 mixer 混控器
12 ui 用户交互
13 user_math 用户自定义数学函数
14 pid PID控制器

View File

@ -1,4 +1,4 @@
bsp,can,dwt,gpio,i2c,mm,spi,uart,pwm,time
component,ahrs,ballistics,capacity,cmd,crc8,crc16,error_detect,filter,FreeRTOS_CLI,limiter,mixer,pid,ui,user_math
component,ahrs,capacity,cmd,crc8,crc16,error_detect,filter,FreeRTOS_CLI,limiter,mixer,pid,ui,user_math
device,dr16,bmi088,ist8310,motor,motor_rm,motor_vesc,motor_lk,motor_lz,motor_odrive,dm_imu,servo,buzzer,led,ws2812
module,
1 bsp,can,dwt,gpio,i2c,mm,spi,uart,pwm,time
2 component,ahrs,ballistics,capacity,cmd,crc8,crc16,error_detect,filter,FreeRTOS_CLI,limiter,mixer,pid,ui,user_math component,ahrs,capacity,cmd,crc8,crc16,error_detect,filter,FreeRTOS_CLI,limiter,mixer,pid,ui,user_math
3 device,dr16,bmi088,ist8310,motor,motor_rm,motor_vesc,motor_lk,motor_lz,motor_odrive,dm_imu,servo,buzzer,led,ws2812
4 module,

Binary file not shown.

View File

@ -1,6 +1,5 @@
/*
BMI088 +
BMI088 +
*/
/* Includes ----------------------------------------------------------------- */

View File

@ -79,7 +79,10 @@ devices:
name: "VESC 电调"
description: "VESC 电调驱动"
dependencies:
bsp: ["can", "time"]
bsp: ["can", "time", "mm"]
component: ["user_math"]
thread_signals:
- name: "SIGNAL_VESC_DATA_REDY"
files:
header: "motor_vesc.h"
source: "motor_vesc.c"
@ -88,7 +91,10 @@ devices:
name: "ODrive 电机"
description: "ODrive 电机驱动"
dependencies:
bsp: ["can", "time"]
bsp: ["can", "time", "mm"]
component: ["user_math"]
thread_signals:
- name: "SIGNAL_ODRIVE_DATA_REDY"
files:
header: "motor_odrive.h"
source: "motor_odrive.c"
@ -97,7 +103,10 @@ devices:
name: "RM 电机"
description: "RM 电机驱动"
dependencies:
bsp: ["can", "time"]
bsp: ["can", "time", "mm"]
component: ["user_math"]
thread_signals:
- name: "SIGNAL_RM_MOTOR_DATA_REDY"
files:
header: "motor_rm.h"
source: "motor_rm.c"
@ -105,6 +114,11 @@ devices:
motor:
name: "通用电机"
description: "通用电机驱动"
dependencies:
bsp: []
component: []
bsp_requirements: []
thread_signals: []
files:
header: "motor.h"
source: "motor.c"
@ -115,11 +129,91 @@ devices:
dependencies:
bsp: ["pwm", "time"]
component: []
bsp_requirements:
- type: "pwm"
var_name: "BSP_PWM_WS2812"
description: "用于WS2812数据传输的PWM通道"
thread_signals: []
files:
header: "ws2812.h"
source: "ws2812.c"
source: "ws2812.c"
buzzer:
name: "蜂鸣器"
description: "蜂鸣器驱动"
dependencies:
bsp: ["pwm"]
component: []
bsp_requirements:
- type: "pwm"
var_name: "BSP_PWM_BUZZER"
description: "用于蜂鸣器的PWM通道"
thread_signals: []
files:
header: "buzzer.h"
source: "buzzer.c"
dm_imu:
name: "DM IMU"
description: "DM IMU 传感器"
dependencies:
bsp: ["can", "time"]
component: ["user_math"]
thread_signals:
- name: "SIGNAL_DM_IMU_DATA_REDY"
files:
header: "dm_imu.h"
source: "dm_imu.c"
led:
name: "LED 灯"
description: "LED 灯驱动"
dependencies:
bsp: ["gpio", "pwm"]
component: []
thread_signals: []
files:
header: "led.h"
source: "led.c"
motor_lk:
name: "LK 电机"
description: "LK 电机驱动"
dependencies:
bsp: ["can", "time", "mm"]
component: ["user_math"]
thread_signals:
- name: "SIGNAL_LK_MOTOR_DATA_REDY"
files:
header: "motor_lk.h"
source: "motor_lk.c"
motor_lz:
name: "LZ 电机"
description: "LZ 电机驱动"
dependencies:
bsp: ["can", "time", "mm"]
component: ["user_math"]
thread_signals:
- name: "SIGNAL_LZ_MOTOR_DATA_REDY"
files:
header: "motor_lz.h"
source: "motor_lz.c"
servo:
name: "舵机"
description: "舵机驱动"
dependencies:
bsp: ["pwm"]
component: []
thread_signals: []
files:
header: "servo.h"
source: "servo.c"
vofa:
name: "VOFA"
description: "VOFA 数据传输协议"
dependencies:
bsp: ["uart"]
component: []
thread_signals: []
files:
header: "vofa.h"
source: "vofa.c"

View File

@ -1,5 +1,5 @@
/*
DM_IMU数据获取
DM_IMU数据获取CAN
*/
/* Includes ----------------------------------------------------------------- */

View File

@ -1,5 +1,5 @@
/*
DR16接收机
DR16接收机
*/
/* Includes ----------------------------------------------------------------- */

View File

@ -1,6 +1,5 @@
/*
IST8310
IST8310
*/
/* Includes ----------------------------------------------------------------- */

View File

@ -1,5 +1,5 @@
/*
DR16接收机
*/
/* Includes ----------------------------------------------------------------- */
@ -18,29 +18,17 @@
/* Exported functions ------------------------------------------------------- */
float MOTOR_GetRotorAbsAngle(const MOTOR_t *motor) {
if (motor == NULL) return DEVICE_ERR_NULL;
if (motor->reverse) {
return -motor->feedback.rotor_abs_angle;
}else{
return motor->feedback.rotor_abs_angle;
}
motor->feedback.rotor_abs_angle;
}
float MOTOR_GetRotorSpeed(const MOTOR_t *motor) {
if (motor == NULL) return DEVICE_ERR_NULL;
if (motor->reverse) {
return -motor->feedback.rotor_speed;
}else{
return motor->feedback.rotor_speed;
}
return motor->feedback.rotor_speed;
}
float MOTOR_GetTorqueCurrent(const MOTOR_t *motor) {
if (motor == NULL) return DEVICE_ERR_NULL;
if (motor->reverse) {
return -motor->feedback.torque_current;
}else{
return motor->feedback.torque_current;
}
return motor->feedback.torque_current;
}
float MOTOR_GetTemp(const MOTOR_t *motor) {

View File

@ -1,10 +1,5 @@
/*
- CAN 2.01Mbps
- (29ID)
- ID格式Bit28~24() + Bit23~8(2) + Bit7~0()
*/
/* Includes ----------------------------------------------------------------- */
#include "motor_lz.h"

View File

@ -1,6 +1,5 @@
/*
CAN总线上的设备
CAN总线上挂载的设备抽象成一个设备进行配置和控制
Odrive电机驱动
*/
/* Includes ----------------------------------------------------------------- */
#include "motor_odrive.h"

View File

@ -1,6 +1,5 @@
/*
CAN总线上的设备
CAN总线上挂载的设备抽象成一个设备进行配置和控制
RM电机驱动
*/
/* Includes ----------------------------------------------------------------- */
#include "motor_rm.h"

View File

@ -1,6 +1,5 @@
/*
CAN总线上的设备
CAN总线上挂载的设备抽象成一个设备进行配置和控制
VESC电机驱动
*/
/* Includes ----------------------------------------------------------------- */
#include "motor_vesc.h"

View File

@ -20,125 +20,125 @@ extern "C"
// VESC数量根据实际情况调整
#define VESC_MAX_MOTORS 4
/* Exported constants ------------------------------------------------------- */
/* Exported constants ------------------------------------------------------- */
/* Exported macro ----------------------------------------------------------- */
/* Exported types ----------------------------------------------------------- */
/* Exported macro ----------------------------------------------------------- */
/* Exported types ----------------------------------------------------------- */
typedef enum
{
VESC_1 = 1,
VESC_2 = 2,
VESC_3 = 3,
VESC_4 = 4,
CAN_VESC5065_M1_MSG1 = 0x901, // vesc的数据回传使用了扩展id[0:7]为驱动器id[8:15]为帧类型
CAN_VESC5065_M2_MSG1 = 0x902,
CAN_VESC5065_M3_MSG1 = 0x903,
CAN_VESC5065_M4_MSG1 = 0x904,
}VESC_ID;
typedef enum
{
VESC_1 = 1,
VESC_2 = 2,
VESC_3 = 3,
VESC_4 = 4,
CAN_VESC5065_M1_MSG1 = 0x901, // vesc的数据回传使用了扩展id[0:7]为驱动器id[8:15]为帧类型
CAN_VESC5065_M2_MSG1 = 0x902,
CAN_VESC5065_M3_MSG1 = 0x903,
CAN_VESC5065_M4_MSG1 = 0x904,
}VESC_ID;
typedef enum
{
CAN_PACKET_SET_DUTY = 0,
CAN_PACKET_SET_CURRENT = 1,
CAN_PACKET_SET_CURRENT_BRAKE = 2,
CAN_PACKET_SET_RPM = 3,
CAN_PACKET_SET_POS = 4,
CAN_PACKET_FILL_RX_BUFFER = 5,
CAN_PACKET_FILL_RX_BUFFER_LONG = 6,
CAN_PACKET_PROCESS_RX_BUFFER = 7,
CAN_PACKET_PROCESS_SHORT_BUFFER = 8,
CAN_PACKET_STATUS = 9,
CAN_PACKET_SET_CURRENT_REL = 10,
CAN_PACKET_SET_CURRENT_BRAKE_REL = 11,
CAN_PACKET_SET_CURRENT_HANDBRAKE = 12,
CAN_PACKET_SET_CURRENT_HANDBRAKE_REL = 13
} CAN_PACKET_ID;
typedef enum
{
CAN_PACKET_SET_DUTY = 0,
CAN_PACKET_SET_CURRENT = 1,
CAN_PACKET_SET_CURRENT_BRAKE = 2,
CAN_PACKET_SET_RPM = 3,
CAN_PACKET_SET_POS = 4,
CAN_PACKET_FILL_RX_BUFFER = 5,
CAN_PACKET_FILL_RX_BUFFER_LONG = 6,
CAN_PACKET_PROCESS_RX_BUFFER = 7,
CAN_PACKET_PROCESS_SHORT_BUFFER = 8,
CAN_PACKET_STATUS = 9,
CAN_PACKET_SET_CURRENT_REL = 10,
CAN_PACKET_SET_CURRENT_BRAKE_REL = 11,
CAN_PACKET_SET_CURRENT_HANDBRAKE = 12,
CAN_PACKET_SET_CURRENT_HANDBRAKE_REL = 13
} CAN_PACKET_ID;
// Control Modes
typedef enum
{
DUTY_CONTROL = 0x0,
RPM_CONTROL = 0x1,
CURRENT_CONTROL = 0x2,
POSITION_CONTROL = 0x3
} Control_Mode;
// Control Modes
typedef enum
{
DUTY_CONTROL = 0x0,
RPM_CONTROL = 0x1,
CURRENT_CONTROL = 0x2,
POSITION_CONTROL = 0x3
} Control_Mode;
/*每个电机需要的参数*/
typedef struct
{
BSP_CAN_t can;
uint16_t id;
uint16_t mode;
bool reverse;
} VESC_Param_t;
/*每个电机需要的参数*/
typedef struct
{
BSP_CAN_t can;
uint16_t id;
uint16_t mode;
bool reverse;
} VESC_Param_t;
/*电机实例*/
typedef struct ODrive_t
{
VESC_Param_t param;
MOTOR_t motor;
} VESC_t;
/*电机实例*/
typedef struct ODrive_t
{
VESC_Param_t param;
MOTOR_t motor;
} VESC_t;
/*CAN管理器管理一个CAN总线上所有的电机*/
typedef struct
{
BSP_CAN_t can;
VESC_t *motors[VESC_MAX_MOTORS];
uint8_t motor_count;
} VESC_CANManager_t;
/*CAN管理器管理一个CAN总线上所有的电机*/
typedef struct
{
BSP_CAN_t can;
VESC_t *motors[VESC_MAX_MOTORS];
uint8_t motor_count;
} VESC_CANManager_t;
/* Exported functions prototypes -------------------------------------------- */
/* Exported functions prototypes -------------------------------------------- */
/**
* @brief vesc电机
* @param param
* @return
*/
int8_t VESC_Register(VESC_Param_t *param);
/**
* @brief vesc电机
* @param param
* @return
*/
int8_t VESC_Register(VESC_Param_t *param);
/**
* @brief
* @param param
* @return
*/
int8_t VESC_Update(VESC_Param_t *param);
/**
* @brief
* @param param
* @return
*/
int8_t VESC_Update(VESC_Param_t *param);
/**
* @brief
* @return
*/
int8_t VESC_UpdateAll(void);
/**
* @brief
* @param param
* @param value
* @return
*/
/**
* @brief
* @return
*/
int8_t VESC_UpdateAll(void);
int8_t VESC_SetOutput(VESC_Param_t *param, float value);
/**
* @brief
* @param param
* @param value
* @return
*/
/**
* @brief
* @param param
* @return
*/
int8_t VESC_SetOutput(VESC_Param_t *param, float value);
VESC_t* VESC_GetMotor(VESC_Param_t *param);
/**
* @brief
* @param param
* @return
*/
/**
* @brief 使0
* @param param
* @return
*/
int8_t VESC_Relax(VESC_Param_t *param);
/**
* @brief 使线线false
* @param param
* @return
*/
int8_t VESC_Offine(VESC_Param_t *param);
VESC_t* VESC_GetMotor(VESC_Param_t *param);
/**
* @brief 使0
* @param param
* @return
*/
int8_t VESC_Relax(VESC_Param_t *param);
/**
* @brief 使线线false
* @param param
* @return
*/
int8_t VESC_Offine(VESC_Param_t *param);
#ifdef __cplusplus

View File

@ -1,14 +1,10 @@
/* Includes ----------------------------------------------------------------- */
#include <stdio.h>
#include <string.h>
#include "vofa.h"
#include "device/vofa.h"
#include "bsp/uart.h"
/* Private define ----------------------------------------------------------- */
//#define PROTOCOL_RAWDATA
#define PROTOCOL_FIREWATER
//#define PROTOCOL_JUSTFLOAT
#define MAX_CHANNEL 64u // 根据实际最大通道数调整
#define JUSTFLOAT_TAIL 0x7F800000
@ -16,6 +12,7 @@
/* Private typedef ---------------------------------------------------------- */
/* Private variables -------------------------------------------------------- */
static uint8_t vofa_tx_buf[sizeof(float) * MAX_CHANNEL + sizeof(uint32_t)];
static VOFA_Protocol_t current_protocol = VOFA_PROTOCOL_FIREWATER; // ĬÈÏЭÒé
/* Private function -------------------------------------------------------- */
@ -59,19 +56,34 @@ void VOFA_JustFloat_Send(float *channels, uint8_t channel_count, bool dma)
}
/* Exported functions ------------------------------------------------------- */
init8_t VOFA_Send(float* channels, uint8_t channel_count, bool dma) {
#ifdef PROTOCOL_RAWDATA
sprintf(vofa_tx_buf, "Channel1:%.2f,Channel2:%.2f\n", channels[0],channels[1]);
VOFA_RawData_Send(vofa_tx_buf, dma);
#elif defined(PROTOCOL_FIREWATER)
VOFA_FireWater_Send(channels, channel_count, dma);
#elif defined(PROTOCOL_JUSTFLOAT)
VOFA_JustFloat_Send(channels, channel_count, dma);
#else
// ĬÈÏʹÓÃRawDataЭÒé
char data[256];
sprintf(data, "Channel1: %.2f, Channel2: %.2f\n", channels[0], channels[1]);
VOFA_RawData_Send(data, dma);
#endif
int8_t VOFA_init(VOFA_Protocol_t protocol) {
current_protocol = protocol;
return DEVICE_OK;
}
int8_t VOFA_Send(float* channels, uint8_t channel_count, bool dma) {
switch (current_protocol) {
case VOFA_PROTOCOL_RAWDATA:
{
char data[256];
if (channel_count >= 1) {
sprintf(data, "Channel1: %.2f", channels[0]);
if (channel_count >= 2) {
sprintf(data + strlen(data), ", Channel2: %.2f", channels[1]);
}
strcat(data, "\n");
VOFA_RawData_Send(data, dma);
}
}
break;
case VOFA_PROTOCOL_FIREWATER:
VOFA_FireWater_Send(channels, channel_count, dma);
break;
case VOFA_PROTOCOL_JUSTFLOAT:
VOFA_JustFloat_Send(channels, channel_count, dma);
break;
default:
return DEVICE_ERR;
}
return DEVICE_OK;
}