Skip to content

Commit

Permalink
3.14
Browse files Browse the repository at this point in the history
  • Loading branch information
Luo25177 committed Mar 14, 2024
1 parent b1e5cf9 commit 20a7539
Show file tree
Hide file tree
Showing 20 changed files with 506 additions and 413 deletions.
2 changes: 1 addition & 1 deletion Chassis/inc/leg.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ typedef struct {
DataStruct theta;
DataStruct L0;
DataStruct dis;
u32 timer;
vu32 timer;
// 五连杆坐标系下的坐标,原点在五连杆的中垂线上
float angle0, angle1, angle2, angle3, angle4; // 角度计算值和读取到的真实值,是和图中的一一对应
float angle1set, angle4set; // 角度设定值,是在初始角度之上的设定值
Expand Down
4 changes: 2 additions & 2 deletions Chassis/src/leg.c
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ void Zjie(Leg* leg, float pitch) {
cor_XY_then[1] = sin(pitch) * leg->xc + cos(pitch) * leg->yc;
leg->theta.now = atan2f(cor_XY_then[0], cor_XY_then[1]);

float dt = 1000 / (float) (GlobalTimer - leg->timer);
float dt = 10000 / (float) (GlobalTimer - leg->timer);
leg->timer = GlobalTimer;

if (dt > 0) {
Expand Down Expand Up @@ -143,5 +143,5 @@ void INVMC(Leg* leg) {
float trans[2][2] = { cos(leg->angle0 - leg->angle2) * A, -cos(leg->angle0 - leg->angle3) * B, -leg->L0.now * sin(leg->angle0 - leg->angle2) * A, leg->L0.now * sin(leg->angle0 - leg->angle3) * B };

leg->Fnow = trans[0][0] * leg->TFnow + trans[0][1] * leg->TBnow;
leg->Tpnow = trans[1][0] * leg->TFnow + trans[1][1] * leg->TBnow;
leg->Tpnow = -trans[1][0] * leg->TFnow - trans[1][1] * leg->TBnow;
}
55 changes: 28 additions & 27 deletions Chassis/src/robot.c
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ void RobotInit() {
robot.mode = ROBOTNORMAL;

// TODO: 参数暂定 调节
PidInit(&robot.yawpid, 1, 0, 0, 0, 1000, PIDPOS);
PidInit(&robot.yawpid, 3, 0, 3, 0, 1000, PIDPOS);
PidInit(&robot.rollpid, 1, 1, 1, 0, 1000, PIDPOS);
PidInit(&robot.splitpid, 120, 0, 1000, 0, 1000, PIDPOS);

Expand Down Expand Up @@ -67,24 +67,24 @@ void BalanceMode() {
float L02 = L01 * L01;
float L03 = L02 * L01;

if (robot.flyflag) {
for (int row = 0; row < 2; row++) {
for (int col = 0; col < 6; col++) {
int num = (row * 6) + col;
if (row == 1 && (col == 0 || col == 1))
robot.legVir.K[row][col] = Kcoeff[num][0] * L03 + Kcoeff[num][1] * L02 + Kcoeff[num][2] * L01 + Kcoeff[num][3];
else
robot.legVir.K[row][col] = 0;
}
}
if (robot.flyflag) {
for (int row = 0; row < 2; row++) {
for (int col = 0; col < 6; col++) {
int num = (row * 6) + col;
if (row == 1 && (col == 0 || col == 1))
robot.legVir.K[row][col] = Kcoeff[num][0] * L03 + Kcoeff[num][1] * L02 + Kcoeff[num][2] * L01 + Kcoeff[num][3];
else
robot.legVir.K[row][col] = 0;
}
}
} else {
for (int row = 0; row < 2; row++) {
for (int col = 0; col < 6; col++) {
int num = (row * 6) + col;
robot.legVir.K[row][col] = Kcoeff[num][0] * L03 + Kcoeff[num][1] * L02 + Kcoeff[num][2] * L01 + Kcoeff[num][3];
for (int row = 0; row < 2; row++) {
for (int col = 0; col < 6; col++) {
int num = (row * 6) + col;
robot.legVir.K[row][col] = Kcoeff[num][0] * L03 + Kcoeff[num][1] * L02 + Kcoeff[num][2] * L01 + Kcoeff[num][3];
}
}
}
}
robot.legVir.X.theta = robot.legVir.theta.now;
robot.legVir.X.thetadot = robot.legVir.theta.dot;
robot.legVir.X.x = robot.legVir.dis.now;
Expand All @@ -94,7 +94,7 @@ void BalanceMode() {

robot.legVir.Xd.theta = 0;
robot.legVir.Xd.thetadot = 0;
robot.legVir.Xd.x = 0;
robot.legVir.Xd.x = expectx;
robot.legVir.Xd.v = 0;
robot.legVir.Xd.pitch = 0;
robot.legVir.Xd.pitchdot = 0;
Expand Down Expand Up @@ -127,9 +127,9 @@ void BalanceMode() {
robot.legL.Fset += lfCompensate;
robot.legR.Fset += rfCompensate;
// 旋转补偿
// float yawCompensate = 0; // robot.yawpid->compute(robot.yawpid, robot.yesense.yaw.now);
// robot.legL.TWheelset -= yawCompensate;
// robot.legR.TWheelset += yawCompensate;
float yawCompensate = robot.yawpid.compute(&robot.yawpid, robot.yesense.yaw.now);
robot.legL.TWheelset -= yawCompensate;
robot.legR.TWheelset += yawCompensate;
// 劈腿补偿
float splitCompensate = robot.splitpid.compute(&robot.splitpid, robot.legL.theta.now - robot.legR.theta.now);
robot.legL.Tpset += splitCompensate;
Expand Down Expand Up @@ -213,16 +213,17 @@ void HaltMode() {
//----
void FlyCheck() {
// 要计算轮子所受的地面的支持力,也就是Fn,且Fn=F+Gw 其中F应当时轮子给机体的支持力,其实就是地面给的支持力用于轮子的重力和上层机构的支持力,而对于lp是机体对轮子的力,所以要反向
float lp = robot.legL.Fnow * cos(robot.legL.theta.now) + robot.legL.Tpnow * sin(robot.legL.theta.now) / robot.legL.L0.now;
float rp = robot.legR.Fnow * cos(robot.legR.theta.now) + robot.legR.Tpnow * sin(robot.legR.theta.now) / robot.legR.L0.now;
float lpw = robot.legL.Fnow * cos(robot.legL.theta.now) - robot.legL.Tpnow * sin(robot.legL.theta.now) / robot.legL.L0.now;
float rpw = robot.legR.Fnow * cos(robot.legR.theta.now) - robot.legR.Tpnow * sin(robot.legR.theta.now) / robot.legR.L0.now;

float zbdd = (robot.yesense.accelz * cos(robot.yesense.pitch.now) - robot.yesense.accelx * sin(robot.yesense.pitch.now)) * cos(robot.yesense.roll.now) + robot.yesense.accely * sin(robot.yesense.roll.now);

float zmdd = robot.yesense.accelz * cos(robot.yesense.pitch.now) - robot.yesense.accelx * sin(robot.yesense.pitch.now);
float lzwdd = zbdd - robot.legL.L0.ddot * cos(robot.legL.theta.now) + 2 * robot.legL.L0.dot + robot.legL.theta.dot * sin(robot.legL.theta.now) + robot.legL.L0.now * robot.legL.theta.ddot * sin(robot.legL.theta.now) + robot.legL.L0.now * robot.legL.theta.dot * robot.legL.theta.dot * cos(robot.legL.theta.now);
float rzwdd = zbdd - robot.legR.L0.ddot * cos(robot.legR.theta.now) + 2 * robot.legR.L0.dot + robot.legR.theta.dot * sin(robot.legR.theta.now) + robot.legR.L0.now * robot.legR.theta.ddot * sin(robot.legR.theta.now) + robot.legR.L0.now * robot.legR.theta.dot * robot.legR.theta.dot * cos(robot.legR.theta.now);

float lzwdd = zmdd - robot.legL.L0.ddot * cos(robot.legL.theta.now) + 2 * robot.legL.L0.dot + robot.legL.theta.dot * sin(robot.legL.theta.now) + robot.legL.L0.now * robot.legL.theta.ddot * sin(robot.legL.theta.now) + robot.legL.L0.now * robot.legL.theta.dot * robot.legL.theta.dot * cos(robot.legL.theta.now);
float rzwdd = zmdd - robot.legR.L0.ddot * cos(robot.legR.theta.now) + 2 * robot.legR.L0.dot + robot.legR.theta.dot * sin(robot.legR.theta.now) + robot.legR.L0.now * robot.legR.theta.ddot * sin(robot.legR.theta.now) + robot.legR.L0.now * robot.legR.theta.dot * robot.legR.theta.dot * cos(robot.legR.theta.now);
robot.legR.normalforce = rpw + MASSWHEEL * (GRAVITY + rzwdd);
robot.legL.normalforce = lpw + MASSWHEEL * (GRAVITY + lzwdd);

robot.legR.normalforce = rp + MASSWHEEL * (GRAVITY + rzwdd);
robot.legL.normalforce = lp + MASSWHEEL * (GRAVITY + lzwdd);
float force = (robot.legL.normalforce + robot.legR.normalforce) / 2;

if (force < FORCETHRESHOLD)
Expand Down
14 changes: 8 additions & 6 deletions Chassis/src/robotmonitor.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,26 +23,28 @@ void LegRPidMonitor() {
}

void RobotLqrMonitor() {
float data[8];
float data[12];
data[0] = robot.legVir.X.theta;
data[1] = robot.legVir.X.thetadot;
data[2] = robot.legVir.X.x;
data[3] = robot.legVir.X.v;
data[4] = robot.legVir.X.pitch;
data[5] = robot.legVir.X.pitchdot;
data[6] = robot.legVir.U.Tp;
data[7] = robot.legVir.U.Twheel;
Oscilloscope(data, 8);
data[6] = robot.legL.wheel->set.torque;
data[7] = robot.legR.wheel->set.torque;
data[8] = robot.legL.wheel->real.torque;
data[9] = robot.legR.wheel->real.torque;
Oscilloscope(data, 10);
}

void RobotTorqueMonitor() {
float data[6];
data[0] = robot.legL.front->set.torque;
data[1] = robot.legL.behind->set.torque;
data[2] = robot.legL.wheel->set.torque;
data[2] = robot.legL.wheel->real.torque;
data[3] = robot.legR.front->set.torque;
data[4] = robot.legR.behind->set.torque;
data[5] = robot.legR.wheel->set.torque;
data[5] = robot.legR.wheel->real.torque;
Oscilloscope(data, 6);
}

Expand Down
24 changes: 12 additions & 12 deletions Chassis/src/robotparam.c
Original file line number Diff line number Diff line change
Expand Up @@ -15,16 +15,16 @@ void OutputInit(Output* output) {
}

float Kcoeff[12][4] = {
-20.7421 , 44.5431 , -71.0665 , -12.5062 ,
24.2688 , -29.8395 , -2.5740 , -2.0772 ,
-4.0292 , 6.0080 , -3.1864 , -5.6813 ,
14.2085 , -11.6371 , 0.1024 , -7.8522 ,
30.7127 , -21.6507 , 1.2630 , 1.0754 ,
2.8987 , 1.0732 , -3.4447 , 1.3749 ,
104.1655 , -91.9755 , 18.8838 , 6.5726 ,
8.4960 , -8.7746 , 3.2443 , 1.0115 ,
3.7080 , 10.4070 , -14.0617 , 5.6284 ,
-0.7846 , 17.0350 , -18.0747 , 7.0663 ,
-4.0049 , 0.7336 , 1.3283 , 18.5794 ,
3.5933 , -5.5874 , 3.0038 , 5.9042
-12.1894, 36.8978, -70.9040, -12.3114,
25.5786, -31.1195, -2.7708, -1.9304,
-2.0806, 4.1396, -2.6215, -6.4716,
18.1504, -15.3280, 0.8718, -8.1811,
36.0834, -27.8536, 3.7670, 0.6970,
4.4404, -0.7541, -2.6918, 1.2634,
110.3385, -104.1633, 26.4006, 5.1440,
9.2475, -10.6837, 4.6153, 0.7215,
12.3829, 1.9497, -11.6976, 5.6937,
10.4316, 4.3038, -13.0799, 6.4611,
-5.8336, 2.7725, 0.5557, 18.6829,
1.9086, -3.8031, 2.3602, 5.9845
};
2 changes: 1 addition & 1 deletion Hardware/inc/tim.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include "stm32f4xx_rcc.h"
#include "stm32f4xx_tim.h"

extern unsigned int GlobalTimer;
extern vu32 GlobalTimer;

void Tim2Init();
void Tim3Init();
2 changes: 1 addition & 1 deletion Hardware/src/can.c
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ void Can2Init() {

/* CAN cell init */
CAN_InitStructure.CAN_TTCM = DISABLE; // 非时间触发通道模式
CAN_InitStructure.CAN_ABOM = ENABLE; // 软件对CAN_MCR寄存器的INRQ位置1,随后清0,一旦监测到128次连续11位的隐性位,就退出离线状态
CAN_InitStructure.CAN_ABOM = ENABLE; // 软件对CAN_MCR寄存器的INRQ位置1,随后清0,一旦监测到128次连续11位的隐性位,就退出离线状态
CAN_InitStructure.CAN_AWUM = DISABLE; // 睡眠模式由软件唤醒
CAN_InitStructure.CAN_NART = DISABLE; // 禁止报文自动发送,即只发送一次,无论结果如何
CAN_InitStructure.CAN_RFLM = DISABLE; // 报文不锁定,新的覆盖旧的
Expand Down
28 changes: 14 additions & 14 deletions Hardware/src/delay.c
Original file line number Diff line number Diff line change
@@ -1,22 +1,22 @@
#include "delay.h"

void delay_ms(const unsigned int t) {
unsigned int i;
for (i = 0; i < t; ++i) {
int a = 42000;
while (a--)
;
}
unsigned int i;
for (i = 0; i < t; ++i) {
int a = 42000;
while (a--)
;
}
}
void delay_us(const unsigned int t) {
unsigned int i;
for (i = 0; i < t; ++i) {
int a = 40;
while (a--)
;
}
unsigned int i;
for (i = 0; i < t; ++i) {
int a = 40;
while (a--)
;
}
}
void delay(u16 t) {
while (t--)
;
while (t--)
;
}
4 changes: 2 additions & 2 deletions Hardware/src/tim.c
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "tim.h"

unsigned int GlobalTimer = 0;
vu32 GlobalTimer = 0;

// 时钟计算公式 时钟频率 / TIM_Prescaler / TIM_Period

Expand All @@ -17,7 +17,7 @@ void Tim2Init() {
NVIC_Init(&NVIC_InitStructure);

TIM_TimeBaseStructure.TIM_Prescaler = 84 - 1;
TIM_TimeBaseStructure.TIM_Period = 1000 - 1; // 1ms
TIM_TimeBaseStructure.TIM_Period = 100 - 1; // 100 us
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
Expand Down
1 change: 0 additions & 1 deletion Main/inc/main.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
//----
#pragma once

// TODO: 还差一些限制条件没写完
#include "beep.h"
#include "bluetooth.h"
#include "can.h"
Expand Down
13 changes: 9 additions & 4 deletions Main/src/irqhandler.c
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,16 @@ void USART2_IRQHandler(void) {
}
}

// 1ms
int canCnt = 0;
// 0.1 ms
void TIM2_IRQHandler(void) {
if (TIM_GetITStatus(TIM2, TIM_IT_Update) == SET) {
GlobalTimer++; // 全局计时器 代码的全局时间可都靠这个
CanSend(0x3);
++GlobalTimer; // 全局计时器 代码的全局时间可都靠这个
++canCnt;
if (canCnt == 10) {
CanSend(0x3);
canCnt = 0;
}
}
TIM_ClearITPendingBit(TIM2, TIM_IT_Update); // 清除中断标志位
}
Expand All @@ -54,7 +59,7 @@ void TIM3_IRQHandler(void) {
if (TIM_GetITStatus(TIM3, TIM_IT_Update) == SET) {
for (int i = 0; i < 4; ++i) TmotorMonitor(&tmotor[i]);
for (int i = 0; i < 2; ++i) ZdriveMonitor(&zdrive[i]);
RobotStateUpdate(&robotstate);
// RobotStateUpdate(&robotstate);
// robot 状态检测
RobotLqrMonitor();
}
Expand Down
31 changes: 1 addition & 30 deletions Main/src/masterparam.c
Original file line number Diff line number Diff line change
Expand Up @@ -40,34 +40,5 @@ void RobotStateInit(RobotState* robotstate) {
}

void RobotStateUpdate(RobotState* robotstate) {
robotstate->height = robot.legVir.L0.now;
robotstate->pitch = robot.yesense.pitch.now;
robotstate->yaw = robot.yesense.yaw.now;
robotstate->roll = robot.yesense.roll.now;
robotstate->v = robot.legVir.dis.dot;
// 这一段写的有点傻鸟,但是没想到更好的办法
if (tmotor[0].monitor.timeOut)
robotstate->deviceState &= 0b11111110;
else
robotstate->deviceState |= 0b00000001;
if (tmotor[1].monitor.timeOut)
robotstate->deviceState &= 0b11111101;
else
robotstate->deviceState |= 0b00000010;
if (zdrive[0].monitor.timeOut)
robotstate->deviceState &= 0b11111011;
else
robotstate->deviceState |= 0b00000100;
if (tmotor[2].monitor.timeOut)
robotstate->deviceState &= 0b11110111;
else
robotstate->deviceState |= 0b00001000;
if (tmotor[3].monitor.timeOut)
robotstate->deviceState &= 0b11101111;
else
robotstate->deviceState |= 0b00010000;
if (zdrive[1].monitor.timeOut)
robotstate->deviceState &= 0b11011111;
else
robotstate->deviceState |= 0b00100000;
// TODO:
}
45 changes: 45 additions & 0 deletions Motor/inc/cybergear.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
#pragma once

#include "motorparam.h"

typedef enum {
OK = 0, // 无故障
BAT_LOW_ERR = 1, // 欠压故障
OVER_CURRENT_ERR = 2, // 过流
OVER_TEMP_ERR = 3, // 过温
MAGNETIC_ERR = 4, // 磁编码故障
HALL_ERR_ERR = 5, // HALL编码故障
NO_CALIBRATION_ERR = 6 // 未标定
} CyberGearState; // 电机状态(故障信息)

typedef enum {
RESET_MODE = 0, // Reset[模式]
CALI_MODE = 1, // Cali 模式[标定]
RUN_MODE = 2, // Motor模式[运行]
} CyberGearContorlMode; // 电机运行模式

typedef struct {
uint32_t id : 8; // 只占8位
uint32_t data : 16;
uint32_t mode : 5;
uint32_t res : 3;
} EXTID;

typedef struct CyberGear {
bool init;
u8 id;
MotorValue(float) real;
MotorValue(float) set;
MotorMonitor monitor;
float kp, kd;
float lastAngleDeg;
float initReadAngle;
float initSetAngle;
} CyberGear;

void CyberGearInit(CyberGear* motor, u8 id);
void CyberGearStatueControl(u8 controlword, u8 id);
void CyberGearreceiveHandle(CyberGear* motor, CanRxMsg msg);
void CyberGearCommunicate(CyberGear* motor, float _pos, float _speed, float _torque, float _kp, float _kd);
void CyberGearRun(CyberGear* motor);
void CyberGearMonitor(CyberGear* motor);
Loading

0 comments on commit 20a7539

Please sign in to comment.