底盘跟随,5V激光,拨弹轮
This commit is contained in:
parent
c2388e74e5
commit
7fc13a67e6
|
@ -103,6 +103,13 @@ void MX_GPIO_Init(void)
|
|||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||
HAL_GPIO_Init(CS1_GYRO_GPIO_Port, &GPIO_InitStruct);
|
||||
|
||||
/*Configure GPIO pin : PtPin */
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_8;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP;
|
||||
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
|
||||
HAL_GPIO_WritePin(GPIOC,GPIO_PIN_8,GPIO_PIN_SET);
|
||||
|
||||
/* EXTI interrupt init*/
|
||||
HAL_NVIC_SetPriority(EXTI3_IRQn, 5, 0);
|
||||
HAL_NVIC_EnableIRQ(EXTI3_IRQn);
|
||||
|
|
|
@ -214,7 +214,7 @@ void ChassisTask()
|
|||
chassis_cmd_recv.wz = 0;
|
||||
break;
|
||||
case CHASSIS_FOLLOW_GIMBAL_YAW: // 跟随云台,不单独设置pid,以误差角度平方为速度输出
|
||||
chassis_cmd_recv.wz = 1.5f * chassis_cmd_recv.offset_angle * abs(chassis_cmd_recv.offset_angle);
|
||||
chassis_cmd_recv.wz = 2.0f * chassis_cmd_recv.offset_angle * abs(chassis_cmd_recv.offset_angle);
|
||||
break;
|
||||
case CHASSIS_ROTATE: // 自旋,同时保持全向机动;当前wz维持定值,后续增加不规则的变速策略
|
||||
chassis_cmd_recv.wz = 1600;
|
||||
|
|
|
@ -101,8 +101,15 @@ static void CalcOffsetAngle()
|
|||
else
|
||||
chassis_cmd_send.offset_angle = angle - YAW_ALIGN_ANGLE + 360.0f;
|
||||
#endif
|
||||
// if(chassis_cmd_send.offset_angle > 340.0f)
|
||||
// chassis_cmd_send.offset_angle = chassis_cmd_send.offset_angle - 360.0f;
|
||||
// else if(chassis_cmd_send.offset_angle < -340.0f)
|
||||
// chassis_cmd_send.offset_angle = chassis_cmd_send.offset_angle + 360.0f;
|
||||
// else
|
||||
// chassis_cmd_send.offset_angle = chassis_cmd_send.offset_angle;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief 控制输入为遥控器(调试时)的模式和控制量设置
|
||||
*
|
||||
|
@ -117,7 +124,7 @@ static void RemoteControlSet()
|
|||
}
|
||||
else if (switch_is_mid(rc_data[TEMP].rc.switch_right)) // 右侧开关状态[中],底盘和云台分离,底盘保持不转动
|
||||
{
|
||||
chassis_cmd_send.chassis_mode = CHASSIS_NO_FOLLOW;
|
||||
chassis_cmd_send.chassis_mode = CHASSIS_FOLLOW_GIMBAL_YAW;
|
||||
gimbal_cmd_send.gimbal_mode = GIMBAL_FREE_MODE;
|
||||
}
|
||||
|
||||
|
@ -130,8 +137,8 @@ static void RemoteControlSet()
|
|||
// 左侧开关状态为[下],或视觉未识别到目标,纯遥控器拨杆控制
|
||||
if (switch_is_down(rc_data[TEMP].rc.switch_left) || vision_recv_data->target_state == NO_TARGET)
|
||||
{ // 按照摇杆的输出大小进行角度增量,增益系数需调整
|
||||
gimbal_cmd_send.yaw += 0.005f * (float)rc_data[TEMP].rc.rocker_l_;
|
||||
gimbal_cmd_send.pitch += 0.001f * (float)rc_data[TEMP].rc.rocker_l1;
|
||||
gimbal_cmd_send.yaw += 0.003f * (float)rc_data[TEMP].rc.rocker_l_;
|
||||
gimbal_cmd_send.pitch += 0.0007f * (float)rc_data[TEMP].rc.rocker_l1;
|
||||
if(gimbal_cmd_send.pitch>=18.0) gimbal_cmd_send.pitch=18.0f;
|
||||
if(gimbal_cmd_send.pitch<=-40.0) gimbal_cmd_send.pitch=-40.0f;
|
||||
|
||||
|
@ -139,8 +146,8 @@ static void RemoteControlSet()
|
|||
// 云台软件限位
|
||||
|
||||
// 底盘参数,目前没有加入小陀螺(调试似乎暂时没有必要),系数需要调整
|
||||
chassis_cmd_send.vx = 10.1f * (float)rc_data[TEMP].rc.rocker_r_; // _水平方向
|
||||
chassis_cmd_send.vy = 10.1f * (float)rc_data[TEMP].rc.rocker_r1; // 1数值方向
|
||||
chassis_cmd_send.vx = 13.1f * (float)rc_data[TEMP].rc.rocker_r_; // _水平方向
|
||||
chassis_cmd_send.vy = 13.1f * (float)rc_data[TEMP].rc.rocker_r1; // 1数值方向
|
||||
|
||||
// 发射参数
|
||||
if (switch_is_up(rc_data[TEMP].rc.switch_right)) // 右侧开关状态[上],弹舱打开
|
||||
|
|
|
@ -27,7 +27,7 @@
|
|||
/* 机器人重要参数定义,注意根据不同机器人进行修改,浮点数需要以.0或f结尾,无符号以u结尾 */
|
||||
// 云台参数
|
||||
#define YAW_CHASSIS_ALIGN_ECD 891 // 云台和底盘对齐指向相同方向时的电机编码器值,若对云台有机械改动需要修改
|
||||
#define YAW_ECD_GREATER_THAN_4096 0 // ALIGN_ECD值是否大于4096,是为1,否为0;用于计算云台偏转角度
|
||||
#define YAW_ECD_GREATER_THAN_4096 1 // ALIGN_ECD值是否大于4096,是为1,否为0;用于计算云台偏转角度
|
||||
#define PITCH_HORIZON_ECD 3412 // 云台处于水平位置时编码器值,若对云台有机械改动需要修改
|
||||
#define PITCH_MAX_ANGLE 0 // 云台竖直方向最大角度 (注意反馈如果是陀螺仪,则填写陀螺仪的角度)
|
||||
#define PITCH_MIN_ANGLE 0 // 云台竖直方向最小角度 (注意反馈如果是陀螺仪,则填写陀螺仪的角度)
|
||||
|
@ -204,6 +204,7 @@ typedef struct
|
|||
{
|
||||
// code to go here
|
||||
// ...
|
||||
uint8_t stalled_flag; //堵转标志
|
||||
} Shoot_Upload_Data_s;
|
||||
|
||||
#pragma pack() // 开启字节对齐,结束前面的#pragma pack(1)
|
||||
|
|
|
@ -19,6 +19,8 @@ static Shoot_Upload_Data_s shoot_feedback_data; // 来自cmd的发射控制信
|
|||
// dwt定时,计算冷却用
|
||||
static float hibernate_time = 0, dead_time = 0;
|
||||
|
||||
static uint16_t locked_time;
|
||||
|
||||
void ShootInit()
|
||||
{
|
||||
// 左摩擦轮
|
||||
|
@ -69,10 +71,10 @@ void ShootInit()
|
|||
.controller_param_init_config = {
|
||||
.angle_PID = {
|
||||
// 如果启用位置环来控制发弹,需要较大的I值保证输出力矩的线性度否则出现接近拨出的力矩大幅下降
|
||||
.Kp = 10, // 10
|
||||
.Ki = 0.1f,
|
||||
.Kp = 130, // 10
|
||||
.Ki = 0,
|
||||
.Kd = 0,
|
||||
.MaxOut = 4500,
|
||||
.MaxOut = 15000,
|
||||
},
|
||||
.speed_PID = {
|
||||
.Kp = 10, // 10
|
||||
|
@ -83,8 +85,8 @@ void ShootInit()
|
|||
.MaxOut = 10000,
|
||||
},
|
||||
.current_PID = {
|
||||
.Kp = 0.3f, // 0.7
|
||||
.Ki = 0.1f, // 0.1
|
||||
.Kp = 0.7f, // 0.7
|
||||
.Ki = 0, // 0.1
|
||||
.Kd = 0,
|
||||
.Improve = PID_Integral_Limit,
|
||||
.IntegralLimit = 5000,
|
||||
|
@ -125,7 +127,6 @@ void ShootTask()
|
|||
DJIMotorEnable(friction_r);
|
||||
DJIMotorEnable(loader);
|
||||
}
|
||||
|
||||
// 如果上一次触发单发或3发指令的时间加上不应期仍然大于当前时间(尚未休眠完毕),直接返回即可
|
||||
// 单发模式主要提供给能量机关激活使用(以及英雄的射击大部分处于单发)
|
||||
if (hibernate_time + dead_time > DWT_GetTimeline_ms())
|
||||
|
@ -162,12 +163,11 @@ void ShootTask()
|
|||
// 拨盘反转,对速度闭环,后续增加卡弹检测(通过裁判系统剩余热量反馈和电机电流)
|
||||
// 也有可能需要从switch-case中独立出来
|
||||
case LOAD_REVERSE:
|
||||
DJIMotorOuterLoop(loader, SPEED_LOOP);
|
||||
// ...
|
||||
break;
|
||||
default:
|
||||
while (1)
|
||||
; // 未知模式,停止运行,检查指针越界,内存溢出等问题
|
||||
|
||||
}
|
||||
|
||||
// 确定是否开启摩擦轮,后续可能修改为键鼠模式下始终开启摩擦轮(上场时建议一直开启)
|
||||
|
@ -212,6 +212,7 @@ void ShootTask()
|
|||
|
||||
// 反馈数据,目前暂时没有要设定的反馈数据,后续可能增加应用离线监测以及卡弹反馈
|
||||
|
||||
//推送消息
|
||||
PubPushMessage(shoot_pub, (void *)&shoot_feedback_data);
|
||||
|
||||
}
|
|
@ -1,6 +1,7 @@
|
|||
#ifndef SHOOT_H
|
||||
#define SHOOT_H
|
||||
|
||||
|
||||
/**
|
||||
* @brief 发射初始化,会被RobotInit()调用
|
||||
*
|
||||
|
|
Loading…
Reference in New Issue