修修平移
This commit is contained in:
parent
a8d01e7f74
commit
a195d14e00
@ -1,6 +1,6 @@
|
|||||||
/*
|
/*
|
||||||
* 配置相关
|
* 配置相关
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* Includes ----------------------------------------------------------------- */
|
/* Includes ----------------------------------------------------------------- */
|
||||||
#include "module/config.h"
|
#include "module/config.h"
|
||||||
@ -15,488 +15,494 @@
|
|||||||
/* Exported variables ------------------------------------------------------- */
|
/* Exported variables ------------------------------------------------------- */
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 机器人参数配置
|
* @brief 机器人参数配置
|
||||||
* @note 在此配置机器人参数
|
* @note 在此配置机器人参数
|
||||||
*/
|
*/
|
||||||
Config_RobotParam_t robot_config = {
|
Config_RobotParam_t robot_config = {
|
||||||
/* USER CODE BEGIN robot_config */
|
/* USER CODE BEGIN robot_config */
|
||||||
.ref_screen={
|
.ref_screen={
|
||||||
.width=1920,
|
.width=1920,
|
||||||
.height=1080,
|
.height=1080,
|
||||||
},
|
},
|
||||||
.gimbal_param = {
|
.gimbal_param = {
|
||||||
.pid = {
|
.pid = {
|
||||||
.yaw_omega = {
|
.yaw_omega = {
|
||||||
.k = 0.25f,
|
.k = 0.25f,
|
||||||
.p = 1.0f,
|
.p = 1.0f,
|
||||||
.i = 0.0f,
|
.i = 0.0f,
|
||||||
.d = 0.0f,
|
.d = 0.0f,
|
||||||
.i_limit = 1.0f,
|
.i_limit = 1.0f,
|
||||||
.out_limit = 1.0f,
|
.out_limit = 1.0f,
|
||||||
.d_cutoff_freq = -1.0f,
|
.d_cutoff_freq = -1.0f,
|
||||||
.range = -1.0f,
|
.range = -1.0f,
|
||||||
},
|
},
|
||||||
.yaw_angle = {
|
.yaw_angle = {
|
||||||
.k = 7.0f,
|
.k = 7.0f,
|
||||||
.p = 3.5f,
|
.p = 3.5f,
|
||||||
.i = 0.0f,
|
.i = 0.0f,
|
||||||
.d = 0.0f,
|
.d = 0.0f,
|
||||||
.i_limit = 0.0f,
|
.i_limit = 0.0f,
|
||||||
.out_limit = 10.0f,
|
.out_limit = 10.0f,
|
||||||
.d_cutoff_freq = -1.0f,
|
.d_cutoff_freq = -1.0f,
|
||||||
.range = M_2PI,
|
.range = M_2PI,
|
||||||
},
|
},
|
||||||
.pit_omega = {
|
.pit_omega = {
|
||||||
.k = 0.25f,
|
.k = 0.25f,
|
||||||
.p = 1.0f,
|
.p = 1.0f,
|
||||||
.i = 0.0f,
|
.i = 0.0f,
|
||||||
.d = 0.0f,
|
.d = 0.0f,
|
||||||
.i_limit = 1.0f,
|
.i_limit = 1.0f,
|
||||||
.out_limit = 1.0f,
|
.out_limit = 1.0f,
|
||||||
.d_cutoff_freq = -1.0f,
|
.d_cutoff_freq = -1.0f,
|
||||||
.range = -1.0f,
|
.range = -1.0f,
|
||||||
},
|
},
|
||||||
.pit_angle = {
|
.pit_angle = {
|
||||||
.k = 2.5f,
|
.k = 2.5f,
|
||||||
.p = 5.0f,
|
.p = 5.0f,
|
||||||
.i = 0.2f,
|
.i = 0.2f,
|
||||||
.d = 0.01f,
|
.d = 0.01f,
|
||||||
.i_limit = 0.0f,
|
.i_limit = 0.0f,
|
||||||
.out_limit = 10.0f,
|
.out_limit = 10.0f,
|
||||||
.d_cutoff_freq = -1.0f,
|
.d_cutoff_freq = -1.0f,
|
||||||
.range = M_2PI,
|
.range = M_2PI,
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
.mech_zero = {
|
.mech_zero = {
|
||||||
.yaw = 0.0f,
|
.yaw = 0.0f,
|
||||||
.pit = 3.23056364f,
|
.pit = 3.23056364f,
|
||||||
},
|
},
|
||||||
.travel = {
|
.travel = {
|
||||||
.yaw = -1.0f,
|
.yaw = -1.0f,
|
||||||
.pit = 0.85f,
|
.pit = 0.85f,
|
||||||
},
|
},
|
||||||
.low_pass_cutoff_freq = {
|
.low_pass_cutoff_freq = {
|
||||||
.out = -1.0f,
|
.out = -1.0f,
|
||||||
.gyro = 1000.0f,
|
.gyro = 1000.0f,
|
||||||
},
|
},
|
||||||
.pit_motor ={
|
.pit_motor ={
|
||||||
.can = BSP_CAN_1,
|
.can = BSP_CAN_1,
|
||||||
.id = 0x206,
|
.id = 0x206,
|
||||||
.gear = false,
|
.gear = false,
|
||||||
.module = MOTOR_GM6020,
|
.module = MOTOR_GM6020,
|
||||||
.reverse = true,
|
.reverse = true,
|
||||||
},
|
},
|
||||||
.yaw_motor = {
|
.yaw_motor = {
|
||||||
.can = BSP_CAN_1,
|
.can = BSP_CAN_1,
|
||||||
.can_id = 0x1,
|
.can_id = 0x1,
|
||||||
.master_id = 0x11,
|
.master_id = 0x11,
|
||||||
.module = MOTOR_DM_J4310,
|
.module = MOTOR_DM_J4310,
|
||||||
.reverse = false,
|
.reverse = false,
|
||||||
},
|
},
|
||||||
.imu = {
|
.imu = {
|
||||||
.can = BSP_CAN_2,
|
.can = BSP_CAN_2,
|
||||||
.accl_id = 0x100, // 加速度计 (十进制256)
|
.accl_id = 0x100, // 加速度计 (十进制256)
|
||||||
.gyro_id = 0x101, // 陀螺仪 (十进制257)
|
.gyro_id = 0x101, // 陀螺仪 (十进制257)
|
||||||
.eulr_id = 0x102, // 欧拉角 (十进制258)
|
.eulr_id = 0x102, // 欧拉角 (十进制258)
|
||||||
.quat_id = 0x103 // 四元数 (十进制259)
|
.quat_id = 0x103 // 四元数 (十进制259)
|
||||||
},
|
},
|
||||||
|
|
||||||
},
|
},
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
.shoot_param = {
|
.shoot_param = {
|
||||||
.basic={
|
.basic={
|
||||||
.projectileType=SHOOT_PROJECTILE_17MM,
|
.projectileType=SHOOT_PROJECTILE_17MM,
|
||||||
.fric_num=2,
|
.fric_num=2,
|
||||||
.extra_deceleration_ratio=1.0f,
|
.extra_deceleration_ratio=1.0f,
|
||||||
.num_trig_tooth=8,
|
.num_trig_tooth=8,
|
||||||
.shot_freq=1.0f,
|
.shot_freq=1.0f,
|
||||||
.shot_burst_num=3,
|
.shot_burst_num=3,
|
||||||
.ratio_multilevel = {1.0f},
|
.ratio_multilevel = {1.0f},
|
||||||
},
|
},
|
||||||
.jamDetection={
|
.jamDetection={
|
||||||
.enable=true,
|
.enable=true,
|
||||||
.threshold=200.0f,
|
.threshold=200.0f,
|
||||||
.suspectedTime=0.5f,
|
.suspectedTime=0.5f,
|
||||||
},
|
},
|
||||||
.heatControl={
|
.heatControl={
|
||||||
.enable=true,
|
.enable=true,
|
||||||
.nmax=18.0f, // 最大射频 Hz
|
.nmax=18.0f, // 最大射频 Hz
|
||||||
.Hwarn=200.0f, // 热量预警值
|
.Hwarn=200.0f, // 热量预警值
|
||||||
.Hsatu=100.0f, // 热量饱和值
|
.Hsatu=100.0f, // 热量饱和值
|
||||||
.Hthres=50.0f, // 热量阈值
|
.Hthres=50.0f, // 热量阈值
|
||||||
},
|
},
|
||||||
.motor={
|
.motor={
|
||||||
.fric = {
|
.fric = {
|
||||||
{
|
{
|
||||||
.param = {
|
.param = {
|
||||||
.can = BSP_CAN_1,
|
.can = BSP_CAN_1,
|
||||||
.id = 0x201,
|
.id = 0x201,
|
||||||
.module = MOTOR_M3508,
|
.module = MOTOR_M3508,
|
||||||
.reverse = false,
|
.reverse = false,
|
||||||
.gear=false,
|
.gear=false,
|
||||||
},
|
},
|
||||||
.level=1,
|
.level=1,
|
||||||
},
|
},
|
||||||
{
|
{
|
||||||
.param = {
|
.param = {
|
||||||
.can = BSP_CAN_1,
|
.can = BSP_CAN_1,
|
||||||
.id = 0x202,
|
.id = 0x202,
|
||||||
.module = MOTOR_M3508,
|
.module = MOTOR_M3508,
|
||||||
.reverse = true,
|
.reverse = true,
|
||||||
.gear=false,
|
.gear=false,
|
||||||
},
|
},
|
||||||
.level=1,
|
.level=1,
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
.trig = {
|
.trig = {
|
||||||
.can = BSP_CAN_1,
|
.can = BSP_CAN_1,
|
||||||
.id = 0x203,
|
.id = 0x203,
|
||||||
.module = MOTOR_M2006,
|
.module = MOTOR_M2006,
|
||||||
.reverse = true,
|
.reverse = true,
|
||||||
.gear=true,
|
.gear=true,
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
.pid={
|
.pid={
|
||||||
.fric_follow = {
|
.fric_follow = {
|
||||||
.k=1.0f,
|
.k=1.0f,
|
||||||
.p=1.5f,
|
.p=1.5f,
|
||||||
.i=0.0f,
|
.i=0.0f,
|
||||||
.d=0.0f,
|
.d=0.0f,
|
||||||
.i_limit=0.0f,
|
.i_limit=0.0f,
|
||||||
.out_limit=0.9f,
|
.out_limit=0.9f,
|
||||||
.d_cutoff_freq=30.0f,
|
.d_cutoff_freq=30.0f,
|
||||||
.range=-1.0f,
|
.range=-1.0f,
|
||||||
},
|
},
|
||||||
.fric_err = {
|
.fric_err = {
|
||||||
.k=0.0f,
|
.k=0.0f,
|
||||||
.p=0.0f,
|
.p=0.0f,
|
||||||
.i=0.0f,
|
.i=0.0f,
|
||||||
.d=0.0f,
|
.d=0.0f,
|
||||||
.i_limit=0.0f,
|
.i_limit=0.0f,
|
||||||
.out_limit=0.0f,
|
.out_limit=0.0f,
|
||||||
.d_cutoff_freq=0.0f,
|
.d_cutoff_freq=0.0f,
|
||||||
.range=-1.0f,
|
.range=-1.0f,
|
||||||
},
|
},
|
||||||
.trig_2006 = {
|
.trig_2006 = {
|
||||||
.k=1.0f,
|
.k=1.0f,
|
||||||
.p=1.0f,
|
.p=1.0f,
|
||||||
.i=0.1f,
|
.i=0.1f,
|
||||||
.d=0.05f,
|
.d=0.05f,
|
||||||
.i_limit=0.8f,
|
.i_limit=0.8f,
|
||||||
.out_limit=0.5f,
|
.out_limit=0.5f,
|
||||||
.d_cutoff_freq=-1.0f,
|
.d_cutoff_freq=-1.0f,
|
||||||
.range=M_2PI,
|
.range=M_2PI,
|
||||||
},
|
},
|
||||||
.trig_omg_2006 = {
|
.trig_omg_2006 = {
|
||||||
.k=1.0f,
|
.k=1.0f,
|
||||||
.p=1.5f,
|
.p=1.5f,
|
||||||
.i=0.3f,
|
.i=0.3f,
|
||||||
.d=0.5f,
|
.d=0.5f,
|
||||||
.i_limit=0.2f,
|
.i_limit=0.2f,
|
||||||
.out_limit=0.9f,
|
.out_limit=0.9f,
|
||||||
.d_cutoff_freq=-1.0f,
|
.d_cutoff_freq=-1.0f,
|
||||||
.range=-1.0f,
|
.range=-1.0f,
|
||||||
},
|
},
|
||||||
.trig_3508 = {
|
.trig_3508 = {
|
||||||
.k=0.5f,
|
.k=0.5f,
|
||||||
.p=1.8f,
|
.p=1.8f,
|
||||||
.i=0.3f,
|
.i=0.3f,
|
||||||
.d=0.1f,
|
.d=0.1f,
|
||||||
.i_limit=0.15f,
|
.i_limit=0.15f,
|
||||||
.out_limit=1.0f,
|
.out_limit=1.0f,
|
||||||
.d_cutoff_freq=-1.0f,
|
.d_cutoff_freq=-1.0f,
|
||||||
.range=M_2PI,
|
.range=M_2PI,
|
||||||
},
|
},
|
||||||
.trig_omg_3508 = {
|
.trig_omg_3508 = {
|
||||||
.k=1.0f,
|
.k=1.0f,
|
||||||
.p=1.0f,
|
.p=1.0f,
|
||||||
.i=0.0f,
|
.i=0.0f,
|
||||||
.d=0.0f,
|
.d=0.0f,
|
||||||
.i_limit=0.0f,
|
.i_limit=0.0f,
|
||||||
.out_limit=1.0f,
|
.out_limit=1.0f,
|
||||||
.d_cutoff_freq=-1.0f,
|
.d_cutoff_freq=-1.0f,
|
||||||
.range=-1.0f,
|
.range=-1.0f,
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
.filter={
|
.filter={
|
||||||
.fric = {
|
.fric = {
|
||||||
.in = 30.0f,
|
.in = 30.0f,
|
||||||
.out = 30.0f,
|
.out = 30.0f,
|
||||||
},
|
},
|
||||||
.trig = {
|
.trig = {
|
||||||
.in = 30.0f,
|
.in = 30.0f,
|
||||||
.out = 30.0f,
|
.out = 30.0f,
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
.chassis_param = {
|
.chassis_param = {
|
||||||
.yaw={
|
.yaw={
|
||||||
.k=1.0f,
|
.k=1.0f,
|
||||||
.p=1.0f,
|
.p=1.0f,
|
||||||
.i=0.0f,
|
.i=0.0f,
|
||||||
.d=0.3f,
|
.d=0.3f,
|
||||||
.i_limit=0.0f,
|
.i_limit=0.0f,
|
||||||
.out_limit=1.0f,
|
.out_limit=1.0f,
|
||||||
.d_cutoff_freq=30.0f,
|
.d_cutoff_freq=30.0f,
|
||||||
.range=M_2PI, /* 2*PI,用于处理角度循环误差 */
|
.range=M_2PI, /* 2*PI,用于处理角度循环误差 */
|
||||||
},
|
},
|
||||||
|
|
||||||
.rotor={
|
.rotor={
|
||||||
.k=1.0f,
|
.k=1.0f,
|
||||||
.p=0.5f,
|
.p=0.5f,
|
||||||
.i=0.0f,
|
.i=0.0f,
|
||||||
.d=0.01f,
|
.d=0.01f,
|
||||||
.i_limit=0.0f,
|
.i_limit=0.0f,
|
||||||
.out_limit=1.0f,
|
.out_limit=1.0f,
|
||||||
.d_cutoff_freq=30.0f,
|
.d_cutoff_freq=30.0f,
|
||||||
.range=-1.0f, /* 角速度不需要循环误差处理 */
|
.range=-1.0f, /* 角速度不需要循环误差处理 */
|
||||||
},
|
},
|
||||||
|
|
||||||
.roll={
|
.roll={
|
||||||
.k=0.15f,
|
.k=0.15f,
|
||||||
.p=0.3f, /* 横滚角腿长补偿比例系数 (降低避免抖动) */
|
.p=0.3f, /* 横滚角腿长补偿比例系数 (降低避免抖动) */
|
||||||
.i=0.0f, /* 横滚角腿长补偿积分系数 (关闭避免震荡) */
|
.i=0.0f, /* 横滚角腿长补偿积分系数 (关闭避免震荡) */
|
||||||
.d=0.01f, /* 横滚角腿长补偿微分系数 (关闭避免噪声放大) */
|
.d=0.01f, /* 横滚角腿长补偿微分系数 (关闭避免噪声放大) */
|
||||||
.i_limit=0.0f, /* 积分限幅 */
|
.i_limit=0.0f, /* 积分限幅 */
|
||||||
.out_limit=0.03f, /* 输出限幅,腿长差值限制(m) 降低避免过度补偿 */
|
.out_limit=0.03f, /* 输出限幅,腿长差值限制(m) 降低避免过度补偿 */
|
||||||
.d_cutoff_freq=30.0f, /* 微分截止频率 */
|
.d_cutoff_freq=30.0f, /* 微分截止频率 */
|
||||||
.range=-1.0f, /* 不使用循环误差处理 */
|
.range=-1.0f, /* 不使用循环误差处理 */
|
||||||
},
|
},
|
||||||
|
|
||||||
.roll_force={
|
.roll_force={
|
||||||
.k=5.0f,
|
.k=5.0f,
|
||||||
.p=10.0f, /* 横滚角力补偿比例系数 (大幅降低避免抖动) */
|
.p=10.0f, /* 横滚角力补偿比例系数 (大幅降低避免抖动) */
|
||||||
.i=0.0f, /* 横滚角力补偿积分系数 */
|
.i=0.0f, /* 横滚角力补偿积分系数 */
|
||||||
.d=5.0f, /* 横滚角力补偿微分系数 (降低避免高频抖动) */
|
.d=5.0f, /* 横滚角力补偿微分系数 (降低避免高频抖动) */
|
||||||
.i_limit=0.0f, /* 积分限幅 */
|
.i_limit=0.0f, /* 积分限幅 */
|
||||||
.out_limit=20.0f, /* 输出限幅,力补偿限制(N) 降低避免过度补偿 */
|
.out_limit=20.0f, /* 输出限幅,力补偿限制(N) 降低避免过度补偿 */
|
||||||
.d_cutoff_freq=30.0f, /* 微分截止频率 */
|
.d_cutoff_freq=30.0f, /* 微分截止频率 */
|
||||||
.range=-1.0f, /* 不使用循环误差处理 */
|
.range=-1.0f, /* 不使用循环误差处理 */
|
||||||
},
|
},
|
||||||
|
|
||||||
.leg_length={
|
.leg_length={
|
||||||
.k = 40.0f,
|
.k = 40.0f,
|
||||||
.p = 50.0f,
|
.p = 50.0f,
|
||||||
.i = 0.01f,
|
.i = 0.01f,
|
||||||
.d = 2.0f,
|
.d = 2.0f,
|
||||||
.i_limit = 0.0f,
|
.i_limit = 0.0f,
|
||||||
.out_limit = 500.0f,
|
.out_limit = 500.0f,
|
||||||
.d_cutoff_freq = -1.0f,
|
.d_cutoff_freq = -1.0f,
|
||||||
.range = -1.0f,
|
.range = -1.0f,
|
||||||
},
|
},
|
||||||
|
|
||||||
.leg_theta={
|
.leg_theta={
|
||||||
.k=5.0f,
|
.k=5.0f,
|
||||||
.p=2.0f, /* 摆角比例系数 */
|
.p=2.0f, /* 摆角比例系数 */
|
||||||
.i=0.0f, /* 摆角积分系数 */
|
.i=0.0f, /* 摆角积分系数 */
|
||||||
.d=0.0f, /* 摆角微分系数 */
|
.d=0.0f, /* 摆角微分系数 */
|
||||||
.i_limit=0.0f, /* 积分限幅 */
|
.i_limit=0.0f, /* 积分限幅 */
|
||||||
.out_limit=0.05f, /* 输出限幅,腿长差值限制 */
|
.out_limit=0.05f, /* 输出限幅,腿长差值限制 */
|
||||||
.d_cutoff_freq=30.0f, /* 微分截止频率 */
|
.d_cutoff_freq=30.0f, /* 微分截止频率 */
|
||||||
.range=-1.0f, /* 不使用循环误差处理 */
|
.range=-1.0f, /* 不使用循环误差处理 */
|
||||||
},
|
},
|
||||||
|
|
||||||
.tp={
|
.tp={
|
||||||
.k=4.0f,
|
.k=4.0f,
|
||||||
.p=3.0f, /* 俯仰角比例系数 */
|
.p=3.0f, /* 俯仰角比例系数 */
|
||||||
.i=0.0f, /* 俯仰角积分系数 */
|
.i=0.0f, /* 俯仰角积分系数 */
|
||||||
.d=0.0f, /* 俯仰角微分系数 */
|
.d=0.0f, /* 俯仰角微分系数 */
|
||||||
.i_limit=0.0f, /* 积分限幅 */
|
.i_limit=0.0f, /* 积分限幅 */
|
||||||
.out_limit=10.0f, /* 输出限幅,腿长差值限制 */
|
.out_limit=10.0f, /* 输出限幅,腿长差值限制 */
|
||||||
.d_cutoff_freq=30.0f, /* 微分截止频率 */
|
.d_cutoff_freq=30.0f, /* 微分截止频率 */
|
||||||
.range=-1.0f, /* 不使用循环误差处理 */
|
.range=-1.0f, /* 不使用循环误差处理 */
|
||||||
},
|
},
|
||||||
|
|
||||||
.low_pass_cutoff_freq = {
|
.low_pass_cutoff_freq = {
|
||||||
.in = 30.0f,
|
.in = 30.0f,
|
||||||
.out = 30.0f,
|
.out = 30.0f,
|
||||||
},
|
},
|
||||||
|
|
||||||
.yaw_motor = { // 云台Yaw轴电机
|
.yaw_motor = { // 云台Yaw轴电机
|
||||||
.can = BSP_CAN_1,
|
.can = BSP_CAN_1,
|
||||||
.can_id = 0x1,
|
.can_id = 0x1,
|
||||||
.master_id = 0x11,
|
.master_id = 0x11,
|
||||||
.module = MOTOR_DM_J4310,
|
.module = MOTOR_DM_J4310,
|
||||||
.reverse = false,
|
.reverse = false,
|
||||||
},
|
},
|
||||||
|
|
||||||
.joint_param = {
|
.joint_param = {
|
||||||
{ // 左髋关节
|
{ // 左髋关节
|
||||||
.can = BSP_CAN_3,
|
.can = BSP_CAN_3,
|
||||||
.motor_id = 124,
|
.motor_id = 124,
|
||||||
.host_id = 0xFF,
|
.host_id = 0xFF,
|
||||||
.module = MOTOR_LZ_RSO3,
|
.module = MOTOR_LZ_RSO3,
|
||||||
.reverse = false,
|
.reverse = false,
|
||||||
.mode = MOTOR_LZ_MODE_MOTION,
|
.mode = MOTOR_LZ_MODE_MOTION,
|
||||||
},
|
},
|
||||||
{ // 右髋关节
|
{ // 右髋关节
|
||||||
.can = BSP_CAN_3,
|
.can = BSP_CAN_3,
|
||||||
.motor_id = 125,
|
.motor_id = 125,
|
||||||
.host_id = 0xFF,
|
.host_id = 0xFF,
|
||||||
.module = MOTOR_LZ_RSO3,
|
.module = MOTOR_LZ_RSO3,
|
||||||
.reverse = false,
|
.reverse = false,
|
||||||
.mode = MOTOR_LZ_MODE_MOTION,
|
.mode = MOTOR_LZ_MODE_MOTION,
|
||||||
},
|
},
|
||||||
{ // 左膝关节
|
{ // 左膝关节
|
||||||
.can = BSP_CAN_3,
|
.can = BSP_CAN_3,
|
||||||
.motor_id = 126,
|
.motor_id = 126,
|
||||||
.host_id = 0xFF,
|
.host_id = 0xFF,
|
||||||
.module = MOTOR_LZ_RSO3,
|
.module = MOTOR_LZ_RSO3,
|
||||||
.reverse = true,
|
.reverse = true,
|
||||||
.mode = MOTOR_LZ_MODE_MOTION,
|
.mode = MOTOR_LZ_MODE_MOTION,
|
||||||
},
|
},
|
||||||
{ // 右膝关节
|
{ // 右膝关节
|
||||||
.can = BSP_CAN_3,
|
.can = BSP_CAN_3,
|
||||||
.motor_id = 127,
|
.motor_id = 127,
|
||||||
.host_id = 0xFF,
|
.host_id = 0xFF,
|
||||||
.module = MOTOR_LZ_RSO3,
|
.module = MOTOR_LZ_RSO3,
|
||||||
.reverse = true,
|
.reverse = true,
|
||||||
.mode = MOTOR_LZ_MODE_MOTION,
|
.mode = MOTOR_LZ_MODE_MOTION,
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
|
|
||||||
.wheel_param = {
|
.wheel_param = {
|
||||||
{ // 左轮电机
|
{ // 左轮电机
|
||||||
.can = BSP_CAN_3,
|
.can = BSP_CAN_3,
|
||||||
.id = 0x142,
|
.id = 0x142,
|
||||||
.module = MOTOR_LK_MF9025,
|
.module = MOTOR_LK_MF9025,
|
||||||
.reverse = false,
|
.reverse = false,
|
||||||
},
|
},
|
||||||
{ // 右轮电机
|
{ // 右轮电机
|
||||||
.can = BSP_CAN_3,
|
.can = BSP_CAN_3,
|
||||||
.id = 0x141,
|
.id = 0x141,
|
||||||
.module = MOTOR_LK_MF9025,
|
.module = MOTOR_LK_MF9025,
|
||||||
.reverse = true,
|
.reverse = true,
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
|
|
||||||
.mech = {
|
.mech = {
|
||||||
.wheel_radius = 0.068f,
|
.wheel_radius = 0.068f,
|
||||||
.wheel_gear_ratio = 4.5f,
|
.wheel_gear_ratio = 4.5f,
|
||||||
.hip_width = 0.423f, /* 髋宽,即两腿间距 (m),用于Roll几何补偿 */
|
.hip_width = 0.423f, /* 髋宽,即两腿间距 (m),用于Roll几何补偿 */
|
||||||
.joint_zero = {0.0f, 0.0f, 1.33022018f, 1.13195965f}, /* 关节电机零点偏移 */
|
.joint_zero = {0.0f, 0.0f, 1.33022018f, 1.13195965f}, /* 关节电机零点偏移 */
|
||||||
.mech_zero_yaw = 2.96925735f, /* 机械零点 */
|
.mech_zero_yaw = 2.96925735f, /* 机械零点 */
|
||||||
},
|
},
|
||||||
|
|
||||||
.leg = {
|
.leg = {
|
||||||
.base_length = 0.16f, /* 基础腿长 (m) */
|
.base_length = 0.16f, /* 基础腿长 (m) */
|
||||||
.length_range = 0.20f, /* 腿长调节范围 (m) */
|
.length_range = 0.20f, /* 腿长调节范围 (m) */
|
||||||
.min_length = 0.14f, /* 最小腿长 (m) */
|
.min_length = 0.14f, /* 最小腿长 (m) */
|
||||||
.max_length = 0.36f, /* 最大腿长 (m) */
|
.max_length = 0.36f, /* 最大腿长 (m) */
|
||||||
.left_base_force = 65.0f, /* 左腿基础支撑力 (N) */
|
.left_base_force = 65.0f, /* 左腿基础支撑力 (N) */
|
||||||
.right_base_force = 65.0f, /* 右腿基础支撑力 (N) */
|
.right_base_force = 65.0f, /* 右腿基础支撑力 (N) */
|
||||||
},
|
},
|
||||||
|
|
||||||
.motion = {
|
.motion = {
|
||||||
.max_acceleration = 5.0f, /* 最大加速度 (m/s^2) */
|
.max_acceleration = 5.0f, /* 最大加速度 (m/s^2) */
|
||||||
.non_contact_theta = -0.01f, /* 离地摆角目标 (rad) */
|
.non_contact_theta = -0.01f, /* 离地摆角目标 (rad) */
|
||||||
},
|
},
|
||||||
|
|
||||||
.rotor_ctrl = {
|
.rotor_ctrl = {
|
||||||
.max_spin_speed = 0.05236f, /* 最大旋转角速度 (rad/s),0.5rpm */
|
.max_spin_speed = 5.0236f, /* 最大旋转角速度 (rad/s),0.5rpm */
|
||||||
.max_trans_speed = 1.5f, /* 小陀螺时最大平移速度 (m/s) */
|
.max_trans_speed = 1.5f, /* 小陀螺时最大平移速度 (m/s) */
|
||||||
.spin_accel = 5.0f, /* 旋转加速度 (rad/s²) */
|
.spin_accel = 5.0f,
|
||||||
.spin_decel = 8.0f, /* 退出减速度 (rad/s²),比加速更快 */
|
|
||||||
.align_threshold = 0.15f, /* 退出对齐阈值 (rad),约8.6° */
|
|
||||||
},
|
|
||||||
|
|
||||||
|
|
||||||
|
/* 旋转加速度 (rad/s²) */
|
||||||
|
.spin_decel = 8.0f, /* 退出减速度 (rad/s²),比加速更快 */
|
||||||
|
.align_threshold = 0.15f, /* 退出对齐阈值 (rad),约8.6° */
|
||||||
|
},
|
||||||
|
|
||||||
.vmc_param = {
|
.vmc_param = {
|
||||||
{ // 左腿
|
{ // 左腿
|
||||||
.leg_1 = 0.215f, // 后髋连杆长度 (L1) (m)
|
.leg_1 = 0.215f, // 后髋连杆长度 (L1) (m)
|
||||||
.leg_2 = 0.258f, // 后膝连杆长度 (L2) (m)
|
.leg_2 = 0.258f, // 后膝连杆长度 (L2) (m)
|
||||||
.leg_3 = 0.258f, // 前膝连杆长度 (L3) (m)
|
.leg_3 = 0.258f, // 前膝连杆长度 (L3) (m)
|
||||||
.leg_4 = 0.215f, // 前髋连杆长度 (L4) (m)
|
.leg_4 = 0.215f, // 前髋连杆长度 (L4) (m)
|
||||||
.hip_length = 0.0f // 髋宽 (L5) (m)
|
.hip_length = 0.0f // 髋宽 (L5) (m)
|
||||||
},
|
},
|
||||||
{ // 右腿
|
{ // 右腿
|
||||||
.leg_1 = 0.215f, // 后髋连杆长度 (L1) (m)
|
.leg_1 = 0.215f, // 后髋连杆长度 (L1) (m)
|
||||||
.leg_2 = 0.258f, // 后膝连杆长度 (L2) (m)
|
.leg_2 = 0.258f, // 后膝连杆长度 (L2) (m)
|
||||||
.leg_3 = 0.258f, // 前膝连杆长度 (L3) (m)
|
.leg_3 = 0.258f, // 前膝连杆长度 (L3) (m)
|
||||||
.leg_4 = 0.215f, // 前髋连杆长度 (L4) (m)
|
.leg_4 = 0.215f, // 前髋连杆长度 (L4) (m)
|
||||||
.hip_length = 0.0f // 髋宽 (L5) (m)
|
.hip_length = 0.0f // 髋宽 (L5) (m)
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
.lqr_gains = {
|
.lqr_gains = {
|
||||||
.k11_coeff = { -1.997928012118380e+02f, 2.358970856133577e+02f, -1.221432656066952e+02f, -3.660884265594530e+00f }, // theta
|
.k11_coeff = { -1.997928012118380e+02f, 2.358970856133577e+02f, -1.221432656066952e+02f, -3.660884265594530e+00f }, // theta
|
||||||
.k12_coeff = { 1.144642140244768e+00f, -6.781143989723293e-01f, -8.286867905694857e+00f, -3.233743818654922e-01f }, // d_theta
|
.k12_coeff = { 1.144642140244768e+00f, -6.781143989723293e-01f, -8.286867905694857e+00f, -3.233743818654922e-01f }, // d_theta
|
||||||
.k13_coeff = { -2.920908857554099e+01f, 3.294053235814564e+01f, -1.331127106026891e+01f, -2.036633181450379e+00f }, // x
|
.k13_coeff = { -2.920908857554099e+01f, 3.294053235814564e+01f, -1.331127106026891e+01f, -2.036633181450379e+00f }, // x
|
||||||
.k14_coeff = { -2.202395151966686e+01f, 2.624258394298977e+01f, -1.238392622003398e+01f, -2.516594294742349e+00f }, // d_x
|
.k14_coeff = { -2.202395151966686e+01f, 2.624258394298977e+01f, -1.238392622003398e+01f, -2.516594294742349e+00f }, // d_x
|
||||||
.k15_coeff = { -5.531234648285231e+01f, 7.666196018790744e+01f, -4.254301644877548e+01f, 1.191958597928930e+01f }, // phi
|
.k15_coeff = { -5.531234648285231e+01f, 7.666196018790744e+01f, -4.254301644877548e+01f, 1.191958597928930e+01f }, // phi
|
||||||
.k16_coeff = { -8.603393557876432e+00f, 1.181868681749069e+01f, -6.519358011847959e+00f, 2.002836931783026e+00f }, // d_phi
|
.k16_coeff = { -8.603393557876432e+00f, 1.181868681749069e+01f, -6.519358011847959e+00f, 2.002836931783026e+00f }, // d_phi
|
||||||
.k21_coeff = { 3.121841964126664e+02f, -2.644789946321499e+02f, 5.653973783920610e+01f, 1.306067415926613e+01f }, // theta
|
.k21_coeff = { 3.121841964126664e+02f, -2.644789946321499e+02f, 5.653973783920610e+01f, 1.306067415926613e+01f }, // theta
|
||||||
.k22_coeff = { 9.751578045310433e+00f, -8.174866581419979e+00f, 1.060040492386880e+00f, 1.945460420856203e+00f }, // d_theta
|
.k22_coeff = { 9.751578045310433e+00f, -8.174866581419979e+00f, 1.060040492386880e+00f, 1.945460420856203e+00f }, // d_theta
|
||||||
.k23_coeff = { -1.589159892148102e+01f, 3.771040781828523e+01f, -2.789168930865428e+01f, 8.354369470743295e+00f }, // x
|
.k23_coeff = { -1.589159892148102e+01f, 3.771040781828523e+01f, -2.789168930865428e+01f, 8.354369470743295e+00f }, // x
|
||||||
.k24_coeff = { -3.304075197263637e+01f, 5.411818719230526e+01f, -3.342861600971858e+01f, 9.256855471266778e+00f }, // d_x
|
.k24_coeff = { -3.304075197263637e+01f, 5.411818719230526e+01f, -3.342861600971858e+01f, 9.256855471266778e+00f }, // d_x
|
||||||
.k25_coeff = { 2.574491871362636e+02f, -2.771545105998671e+02f, 1.074894289176479e+02f, 3.130550754680395e+00f }, // phi
|
.k25_coeff = { 2.574491871362636e+02f, -2.771545105998671e+02f, 1.074894289176479e+02f, 3.130550754680395e+00f }, // phi
|
||||||
.k26_coeff = { 4.162978395880715e+01f, -4.533986766238992e+01f, 1.794589550749570e+01f, 2.032213740678163e-01f }, // d_phi
|
.k26_coeff = { 4.162978395880715e+01f, -4.533986766238992e+01f, 1.794589550749570e+01f, 2.032213740678163e-01f }, // d_phi
|
||||||
},
|
},
|
||||||
|
|
||||||
|
|
||||||
.jump = {
|
.jump = {
|
||||||
.crouch_time_ms = 500,
|
.crouch_time_ms = 500,
|
||||||
.launch_time_ms = 300,
|
.launch_time_ms = 300,
|
||||||
.retract_time_ms = 500,
|
.retract_time_ms = 500,
|
||||||
.land_time_ms = 500,
|
.land_time_ms = 500,
|
||||||
.crouch_leg_length = 0.13f, /* 不用蹲太低 */
|
.crouch_leg_length = 0.13f, /* 不用蹲太低 */
|
||||||
.launch_force = 20.0f, /* 起跳力减小 */
|
.launch_force = 20.0f, /* 起跳力减小 */
|
||||||
.retract_leg_length = 0.12f, /* 收腿目标 */
|
.retract_leg_length = 0.12f, /* 收腿目标 */
|
||||||
.retract_force = -20.0f, /* 收腿前馈力减小 */
|
.retract_force = -20.0f, /* 收腿前馈力减小 */
|
||||||
},
|
},
|
||||||
|
|
||||||
.lqr_offset = {
|
.lqr_offset = {
|
||||||
.theta = 0.0f,
|
.theta = 0.0f,
|
||||||
.x = 0.0f,
|
.x = 0.0f,
|
||||||
.phi = 0.0f,
|
.phi = 0.0f,
|
||||||
},
|
},
|
||||||
|
|
||||||
},
|
},
|
||||||
|
|
||||||
.ai_param = {
|
.ai_param = {
|
||||||
.can = BSP_FDCAN_2,
|
.can = BSP_FDCAN_2,
|
||||||
.vision_id = 0x104,
|
.vision_id = 0x104,
|
||||||
},
|
},
|
||||||
|
|
||||||
.cmd_param = {
|
.cmd_param = {
|
||||||
.source_priority = {
|
.source_priority = {
|
||||||
#if CMD_ENABLE_SRC_RC
|
#if CMD_ENABLE_SRC_RC
|
||||||
[0] = CMD_SRC_RC,
|
[0] = CMD_SRC_RC,
|
||||||
#endif
|
#endif
|
||||||
#if CMD_ENABLE_SRC_PC
|
#if CMD_ENABLE_SRC_PC
|
||||||
[1] = CMD_SRC_PC,
|
[1] = CMD_SRC_PC,
|
||||||
#endif
|
#endif
|
||||||
},
|
},
|
||||||
.sensitivity = {
|
.sensitivity = {
|
||||||
.mouse_sens = 60.0f,
|
.mouse_sens = 60.0f,
|
||||||
.move_sens = 1.0f,
|
.move_sens = 1.0f,
|
||||||
.move_fast_mult = 2.0f,
|
.move_fast_mult = 2.0f,
|
||||||
.move_slow_mult = 0.4f,
|
.move_slow_mult = 0.4f,
|
||||||
},
|
},
|
||||||
.rc_mode_map = {
|
.rc_mode_map = {
|
||||||
#if CMD_ENABLE_MODULE_GIMBAL
|
#if CMD_ENABLE_MODULE_GIMBAL
|
||||||
.gimbal_sw_up = GIMBAL_MODE_RELAX,
|
.gimbal_sw_up = GIMBAL_MODE_RELAX,
|
||||||
.gimbal_sw_mid = GIMBAL_MODE_RELATIVE,
|
.gimbal_sw_mid = GIMBAL_MODE_RELATIVE,
|
||||||
.gimbal_sw_down = GIMBAL_MODE_RELATIVE,
|
.gimbal_sw_down = GIMBAL_MODE_RELATIVE,
|
||||||
#endif
|
#endif
|
||||||
#if CMD_ENABLE_MODULE_BALANCE_CHASSIS
|
#if CMD_ENABLE_MODULE_BALANCE_CHASSIS
|
||||||
.balance_sw_up = CHASSIS_MODE_RELAX,
|
.balance_sw_up = CHASSIS_MODE_RELAX,
|
||||||
.balance_sw_mid = CHASSIS_MODE_WHELL_LEG_BALANCE,
|
.balance_sw_mid = CHASSIS_MODE_WHELL_LEG_BALANCE,
|
||||||
.balance_sw_down = CHASSIS_MODE_BALANCE_ROTOR,
|
.balance_sw_down = CHASSIS_MODE_BALANCE_ROTOR,
|
||||||
#endif
|
#endif
|
||||||
},
|
},
|
||||||
},
|
},
|
||||||
|
|
||||||
/* USER CODE END robot_config */
|
/* USER CODE END robot_config */
|
||||||
};
|
};
|
||||||
|
|
||||||
/* Private function prototypes ---------------------------------------------- */
|
/* Private function prototypes ---------------------------------------------- */
|
||||||
/* Exported functions ------------------------------------------------------- */
|
/* Exported functions ------------------------------------------------------- */
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 获取机器人配置参数
|
* @brief 获取机器人配置参数
|
||||||
* @return 机器人配置参数指针
|
* @return 机器人配置参数指针
|
||||||
*/
|
*/
|
||||||
Config_RobotParam_t* Config_GetRobotParam(void) {
|
Config_RobotParam_t* Config_GetRobotParam(void) {
|
||||||
return &robot_config;
|
return &robot_config;
|
||||||
}
|
}
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user