增加了遥控器控制,待测试

This commit is contained in:
NeoZng 2022-12-07 21:56:34 +08:00
parent 3eba5b1c07
commit 2dd39f9815
6 changed files with 95 additions and 40 deletions

View File

@ -38,7 +38,7 @@
"typeinfo": "c",
"general_def.h": "c",
"super_cap.h": "c",
"motor_def.h": "c"
"motor_def.h": "c",
},
"C_Cpp.default.configurationProvider": "ms-vscode.makefile-tools",
}

View File

@ -81,17 +81,58 @@ static void CalcOffsetAngle()
* @brief ()
*
*/
static void RemoteControlSetMode()
static void RemoteControlSet()
{
// 控制底盘和云台运行模式,云台待添加,云台是否始终使用IMU数据?
if (switch_is_down(remote_control_data[0].rc.s[1])) // 右侧开关状态[下],底盘跟随云台
chassis_cmd_send.chassis_mode = CHASSIS_FOLLOW_GIMBAL_YAW;
if (switch_is_mid(remote_control_data[0].rc.s[1])) // 右侧开关状态[中],底盘和云台分离,底盘保持不转动
chassis_cmd_send.chassis_mode = CHASSIS_NO_FOLLOW;
// 云台参数,确定云台控制数据
if (switch_is_mid(remote_control_data[0].rc.s[0])) // 左侧开关状态为[中],视觉模式
{
// 待添加
// ...
}
// 侧开关状态为[下],或视觉未识别到目标,纯遥控器拨杆控制
if (switch_is_down(remote_control_data[0].rc.s[0]) || vision_recv_data->target_state == NO_TARGET)
{ // 按照摇杆的输出大小进行角度增量,增益系数需调整
gimbal_cmd_send.yaw += 0.04f * (float)remote_control_data[0].rc.joystick[2];
gimbal_cmd_send.pitch = 0.5f * (float)remote_control_data[0].rc.joystick[3];
gimbal_cmd_send.gimbal_mode = GIMBAL_GYRO_MODE;
}
// 底盘参数,目前没有加入小陀螺(调试似乎没有必要),系数需要调整
chassis_cmd_send.vx = 1.0f * (float)remote_control_data[0].rc.joystick[0];
chassis_cmd_send.vy = 1.0f * (float)remote_control_data[0].rc.joystick[1];
// 发射参数
if (switch_is_up(remote_control_data[0].rc.s[1])) //右侧开关状态[上],弹舱打开
; //弹舱舵机控制,待添加servo_motor模块,开启
else
;//弹舱舵机控制,待添加servo_motor模块,关闭
// 摩擦轮控制,后续可以根据左侧拨轮的值大小切换射频
if(remote_control_data[0].rc.joystick[4]>100)
shoot_cmd_send.shoot_mode=FRICTION_ON;
else
shoot_cmd_send.shoot_mode=FRICTION_OFF;
// 拨弹控制,目前固定为连发
if(remote_control_data[0].rc.joystick[4]>500)
shoot_cmd_send.load_mode=LOAD_BURSTFIRE;
else
shoot_cmd_send.load_mode=LOAD_STOP;
}
/**
* @brief
*
*/
static void MouseKeySetMode()
static void MouseKeySet()
{
}
@ -102,7 +143,8 @@ static void MouseKeySetMode()
*/
static void EmergencyHandler()
{
if(remote_control_data[0].joy_stick.ch[4]<-300)//还需添加重要应用和模块离线的判断
// 拨轮的向下拨超过一半
if (remote_control_data[0].rc.joystick[4] < -300) // 还需添加重要应用和模块离线的判断
{
robot_state = ROBOT_STOP; // 遥控器左上侧拨轮打满,进入紧急停止模式
gimbal_cmd_send.gimbal_mode == GIMBAL_ZERO_FORCE;
@ -110,7 +152,7 @@ static void EmergencyHandler()
shoot_cmd_send.shoot_mode == SHOOT_STOP;
return;
}
// if(remote_control_data[0].joy_stick.ch[4]>300 && 各个模块正常)
// if(remote_control_data[0].rc.joystick[4]>300 && 各个模块正常)
// {
// //恢复运行
// //...
@ -127,14 +169,14 @@ void GimbalCMDTask()
// 根据gimbal的反馈值计算云台和底盘正方向的夹角,不需要传参,通过私有变量完成
CalcOffsetAngle();
if (1) // 遥控器控制
RemoteControlSetMode();
else if (0) // 键盘控制
MouseKeySetMode();
if (switch_is_down(remote_control_data[0].rc.s[0])) // 遥控器左侧开关状态为[下],遥控器控制
RemoteControlSet();
else if (switch_is_up(remote_control_data[0].rc.s[0])) // 遥控器左侧开关状态为[上],键盘控制
MouseKeySet();
EmergencyHandler(); // 处理模块离线和遥控器急停等紧急情况
// 设置视觉发送数据,work_mode在前一部分设置
// 设置视觉发送数据
vision_send_data.bullet_speed = chassis_fetch_data.bullet_speed;
vision_send_data.enemy_color = chassis_fetch_data.enemy_color;
vision_send_data.pitch = gimbal_fetch_data.gimbal_imu_data.Pitch;

View File

@ -85,7 +85,7 @@ typedef enum
typedef enum
{
GIMBAL_ZERO_FORCE, // 电流零输入
GIMBAL_FREE_MODE, // 云台自由运动模式,即与底盘分离(底盘此时应为NO_FOLLOW)反馈值为电机total_angle
GIMBAL_FREE_MODE, // 云台自由运动模式,即与底盘分离(底盘此时应为NO_FOLLOW)反馈值为电机total_angle;似乎可以改为全部用IMU数据?
GIMBAL_GYRO_MODE, // 云台陀螺仪反馈模式,反馈值为陀螺仪pitch,total_yaw_angle,底盘可以为小陀螺和跟随模式
} gimbal_mode_e;

View File

@ -68,3 +68,17 @@ remote_control
* Bit15:B键 *
**************************************************************/
```
拨轮向下打到底进入紧急停止模式;拨轮向上打开启摩擦轮,超过一半开始发射(速度环,连发)
左侧开关:
- 上:键鼠控制
- 中:视觉控制(没有识别到目标的时候仍然可以使用遥控器控制云台)
- 下:遥控器控制
右侧开关:
- 上:弹舱开
- 中:底盘云台分离(底盘不旋转,全向移动)
- 下:底盘跟随云台

View File

@ -19,14 +19,14 @@ static void sbus_to_rc(volatile const uint8_t *sbus_buf)
{
memcpy(&rc_ctrl[1], &rc_ctrl[0], sizeof(RC_ctrl_t)); // 保存上一次的数据
// 摇杆
rc_ctrl[0].joy_stick.ch[0] = (sbus_buf[0] | (sbus_buf[1] << 8)) & 0x07ff; //!< Channel 0
rc_ctrl[0].joy_stick.ch[1] = ((sbus_buf[1] >> 3) | (sbus_buf[2] << 5)) & 0x07ff; //!< Channel 1
rc_ctrl[0].joy_stick.ch[2] = ((sbus_buf[2] >> 6) | (sbus_buf[3] << 2) | (sbus_buf[4] << 10)) & 0x07ff; //!< Channel 2
rc_ctrl[0].joy_stick.ch[3] = ((sbus_buf[4] >> 1) | (sbus_buf[5] << 7)) & 0x07ff; //!< Channel 3
rc_ctrl[0].joy_stick.ch[4] = sbus_buf[16] | (sbus_buf[17] << 8); // 拨轮
rc_ctrl[0].rc.joystick[0] = (sbus_buf[0] | (sbus_buf[1] << 8)) & 0x07ff; //!< Channel 0
rc_ctrl[0].rc.joystick[1] = ((sbus_buf[1] >> 3) | (sbus_buf[2] << 5)) & 0x07ff; //!< Channel 1
rc_ctrl[0].rc.joystick[2] = ((sbus_buf[2] >> 6) | (sbus_buf[3] << 2) | (sbus_buf[4] << 10)) & 0x07ff; //!< Channel 2
rc_ctrl[0].rc.joystick[3] = ((sbus_buf[4] >> 1) | (sbus_buf[5] << 7)) & 0x07ff; //!< Channel 3
rc_ctrl[0].rc.joystick[4] = sbus_buf[16] | (sbus_buf[17] << 8); // 拨轮
// 开关,0左1右
rc_ctrl[0].joy_stick.s[0] = ((sbus_buf[5] >> 4) & 0x0003); //!< Switch left
rc_ctrl[0].joy_stick.s[1] = ((sbus_buf[5] >> 4) & 0x000C) >> 2; //!< Switch right
rc_ctrl[0].rc.s[0] = ((sbus_buf[5] >> 4) & 0x0003); //!< Switch left
rc_ctrl[0].rc.s[1] = ((sbus_buf[5] >> 4) & 0x000C) >> 2; //!< Switch right
// 鼠标解析
rc_ctrl[0].mouse.x = sbus_buf[6] | (sbus_buf[7] << 8); //!< Mouse X axis
@ -62,13 +62,12 @@ static void sbus_to_rc(volatile const uint8_t *sbus_buf)
if (rc_ctrl[0].key_test[KEY_PRESS].shift)
rc_ctrl[0].key_test[Key_Shift] = rc_ctrl[0].key_test[KEY_PRESS];
// 减去偏置值
rc_ctrl[0].joy_stick.ch[0] -= RC_CH_VALUE_OFFSET;
rc_ctrl[0].joy_stick.ch[1] -= RC_CH_VALUE_OFFSET;
rc_ctrl[0].joy_stick.ch[2] -= RC_CH_VALUE_OFFSET;
rc_ctrl[0].joy_stick.ch[3] -= RC_CH_VALUE_OFFSET;
rc_ctrl[0].joy_stick.ch[4] -= RC_CH_VALUE_OFFSET;
rc_ctrl[0].rc.joystick[0] -= RC_CH_VALUE_OFFSET;
rc_ctrl[0].rc.joystick[1] -= RC_CH_VALUE_OFFSET;
rc_ctrl[0].rc.joystick[2] -= RC_CH_VALUE_OFFSET;
rc_ctrl[0].rc.joystick[3] -= RC_CH_VALUE_OFFSET;
rc_ctrl[0].rc.joystick[4] -= RC_CH_VALUE_OFFSET;
}
/**

View File

@ -80,9 +80,9 @@ typedef struct
{
struct
{
int16_t ch[5]; // 右|0 ,右-1 ,左-2 ,左|3 ,拨轮4
int16_t joystick[5]; // 右|0 ,右-1 ,左-2 ,左|3 ,拨轮4
uint8_t s[2]; //[0]:left [1]:right
} joy_stick;
} rc;
struct
{
int16_t x;