RobotHardware-UESTC/Hardware/银星机器人底盘/PiRobot-YH_Firmware v1.0/STM32/Lib/DataHolder/data_holder.h

112 lines
3.1 KiB
C
Raw Normal View History

2024-01-20 13:19:09 +08:00
#ifndef DATA_HOLDER_H_
#define DATA_HOLDER_H_
#include <string.h>
// 1字节对齐
#pragma pack(1)
struct Robot_firmware
{
char version[16]; //固件版本
char time[16]; //构建时间
};
enum IMU_TYPE
{
IMU_TYPE_GY65 = 49,
IMU_TYPE_GY85 = 69,
IMU_TYPE_GY87 = 71
};
#define MOTOR_ENCODER_1_FLAG 0x01
#define MOTOR_ENCODER_2_FLAG 0x02
#define MOTOR_ENCODER_3_FLAG 0x04
#define MOTOR_ENCODER_4_FLAG 0x08
struct Params
{
unsigned short wheel_diameter; //轮子直径 mm
unsigned short wheel_track; //差分:轮距, 三全向轮:直径,四全向:前后轮距+左右轮距 mm
unsigned short encoder_resolution; //编码器分辨率
unsigned char do_pid_interval; //pid间隔 (ms)
unsigned short kp;
unsigned short ki;
unsigned short kd;
unsigned short ko; //pid参数比例
unsigned short cmd_last_time; //命令持久时间ms 超过该时间会自动停止运动
unsigned short max_v_liner_x; // 最大x线速度
unsigned short max_v_liner_y; // 最大y线速度
unsigned short max_v_angular_z; // 最大角速度
unsigned char imu_type; // imu类型 参见IMU_TYPE
unsigned short motor_ratio; // 电机减速比
unsigned char model_type; // 运动模型类型 参见MODEL_TYPE
unsigned char motor_nonexchange_flag; // 电机标志参数 1 正接 0 反接(相当于电机线交换)
unsigned char encoder_nonexchange_flag; // 编码器标志参数 1 正接 0 反接(相当于编码器ab相交换)
};
struct Robot_parameter
{
union
{
char buff[64];
struct Params params;
};
};
struct Robot_velocity
{
short v_liner_x; //线速度 前>0 cm/s
short v_liner_y; //差分轮 为0 cm/s
short v_angular_z; //角速度 左>0 0.01rad/s 100 means 1 rad/s
};
struct Robot_odom
{
short v_liner_x; //线速度 前>0 后<0 cm/s
short v_liner_y; //差分轮 为0 cm/s
short v_angular_z; //角速度 左>0 右<0 0.01rad/s 100 means 1 rad/s
long x; //里程计坐标x cm (这里long为4字节下同)
long y; //里程计坐标y cm
short yaw; //里程计航角 0.01rad 100 means 1 rad
};
struct Robot_pid_data
{
long input[4]; //各轮子驱动输入值
long output[4]; //个轮子输出值
};
struct Robot_pwm_value
{
short value[4];
};
class Data_holder
{
public:
static Data_holder* get() {
static Data_holder dh;
return &dh;
}
void load_parameter();
void save_parameter();
private:
Data_holder();
public:
struct Robot_firmware firmware_info;//版本信息
struct Robot_parameter parameter; //参数
struct Robot_velocity velocity; // 速度
struct Robot_odom odom; //里程
struct Robot_pid_data pid_data; //pid输入输出
float imu_data[9]; //imu的值 9axis
float encoder_count[4]; // 编码器计数
struct Robot_pwm_value pwm; // 控制的pwm
};
#endif