sensor_2026/USER/main.c

600 lines
18 KiB
C
Raw Normal View History

2026-02-08 17:48:22 +08:00
#include "sys.h"
#include "delay.h"
#include "usart.h"
#include "led.h"
#include "beep.h"
#include "key.h"
#include "motor_driver.h"
2026-02-08 17:48:22 +08:00
//ALIENTEK ̽<><CCBD><EFBFBD><EFBFBD>STM32F407<30><37><EFBFBD><EFBFBD><EFBFBD><EFBFBD> ʵ<><CAB5>4
//<2F><><EFBFBD><EFBFBD>ͨ<EFBFBD><CDA8>ʵ<EFBFBD><CAB5> -<2D><EFBFBD><E2BAAF><EFBFBD>
//<2F><><EFBFBD><EFBFBD>֧<EFBFBD>֣<EFBFBD>www.openedv.com
//<2F>Ա<EFBFBD><D4B1><EFBFBD><EFBFBD>̣<EFBFBD>http://eboard.taobao.com
//<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ӿƼ<D3BF><C6BC><EFBFBD><EFBFBD>޹<EFBFBD>˾
//<2F><><EFBFBD>ߣ<EFBFBD><DFA3><EFBFBD><EFBFBD><EFBFBD>ԭ<EFBFBD><D4AD> @ALIENTEK
2026-02-09 17:29:30 +08:00
void MX_TIM2_Init(void);
//void PWM_SetPulseWidth(uint16_t pulseWidth);
//void PWM_SetSpeed(int16_t speed);
void Error_Handler(void);
typedef uint32_t u32;
typedef uint16_t u16;
typedef uint8_t u8;
// <20><><EFBFBD><EFBFBD>TMC2240<34>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD>ַ
#define REG_MICROSTEPS 0x03
#define REG_CURRENT 0x05
#define EG_STATUS 0x0F
extern volatile u16 rx_len; // <20><><EFBFBD>ռ<EFBFBD><D5BC><EFBFBD>
extern volatile u8 rx_flag; // <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ɱ<EFBFBD>־
#define GCONF 0x00
#define IHOLD_IRUN 0x10
#define TPOWERDOWN 0x11
#define TPWMTHRS 0x13
#define TCOOLTHRS 0x14
#define CHOPCONF 0x6C
#define COOLCONF 0x6D
#define DRV_CONF 0x0A
#define DRV_STATUS 0x6F
#define PWMCONF 0x70
#define SOFT_SPI_DR_PORT GPIOD
#define SOFT_SPI_DR_PIN GPIO_Pin_3
//forward and reverse
#define D3_DR_forward() GPIO_SetBits(SOFT_SPI_DR_PORT, SOFT_SPI_DR_PIN)
#define D3_DR_reverse() GPIO_ResetBits(SOFT_SPI_DR_PORT, SOFT_SPI_DR_PIN)
void TMC2240_Init_rotating() {
// <20><><EFBFBD>õ<EFBFBD>ѹ<EFBFBD><D1B9><EFBFBD><EFBFBD><EFBFBD><EFBFBD>PWMģʽ
TMC2240_WriteReg(GCONF, 0x000000C4);
// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ã<EFBFBD>IHOLD=0.5A, IRUN=1.2A
TMC2240_WriteReg(IHOLD_IRUN, 0x00180C10);
// 16΢<36><CEA2><EFBFBD><EFBFBD>MRES=4<><34><EFBFBD><EFBFBD>TOFF=3
TMC2240_WriteReg(CHOPCONF, 0x030000C3);
// <20><><EFBFBD><EFBFBD><EFBFBD>ٶ<EFBFBD><D9B6><EFBFBD>ֵ500Hz<48><7A><EFBFBD><EFBFBD><EFBFBD>ڴ<EFBFBD>ֵ<EFBFBD><D6B5>StealthChop2<70><32>
TMC2240_WriteReg(TPWMTHRS, 200);
// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ã<EFBFBD><C3A3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
TMC2240_WriteReg(DRV_CONF, 0x00000001);
// ͣ<><CDA3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʱ
TMC2240_WriteReg(TPOWERDOWN, 10);
}
void TMC2240_Init() {
// <20><><EFBFBD><EFBFBD>StealthChop2<70>Զ<EFBFBD><D4B6><EFBFBD>г + SpreadCycle<6C><65>̬<EFBFBD>л<EFBFBD>
TMC2240_WriteReg(GCONF, 0x000000C4 | (1 << 7)); // bit7=1
// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ã<EFBFBD>IRUN=1.2A, IHOLD=0.8A<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʽ<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ֵ<EFBFBD><EFBFBD>
//TMC2240_WriteReg(IHOLD_IRUN, 0x00190C10);
TMC2240_WriteReg(IHOLD_IRUN, 0x04090101); //<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>е<EFBFBD><D0B5><EFBFBD>̫<EFBFBD>󣬷<EFBFBD><F3A3ACB7>ȣ<EFBFBD><C8A3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>С<EFBFBD><D0A1><EFBFBD><EFBFBD>
// <20><><EFBFBD><EFBFBD>΢<EFBFBD><CEA2><EFBFBD>ֱ<EFBFBD><D6B1>ʣ<EFBFBD><CAA3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>256΢<36><CEA2><EFBFBD><EFBFBD>Ϊ16΢<36><CEA2><EFBFBD><EFBFBD>
TMC2240_WriteReg(CHOPCONF, 0x070080C3 ); // MRES=4<><34>16΢<36><CEA2><EFBFBD><EFBFBD>
// <20><><EFBFBD><EFBFBD><EFBFBD>ٶ<EFBFBD><D9B6><EFBFBD>ֵ500Hz<48><7A><EFBFBD><EFBFBD><EFBFBD>ڴ<EFBFBD>ֵ<EFBFBD><D6B5>StealthChop2<70><32>
TMC2240_WriteReg(TPWMTHRS, 50);
// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ñ<EFBFBD><C3B1>ֲ<EFBFBD><D6B2><EFBFBD>
TMC2240_WriteReg(DRV_CONF, 0x00000001);
TMC2240_WriteReg(TPOWERDOWN, 10);
}
// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>״̬
void CheckDriverStatus() {
uint32_t status = TMC2240_ReadReg(DRV_STATUS);//
if (status & (1 << 26)) { // <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>·<EFBFBD><C2B7><EFBFBD><EFBFBD>
printf("Short to ground detected\n");
}
if (status & (1 << 25)) { // <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
printf("Overtemperature detected\n");
}
if (status & (1 << 24)) { // <20><><EFBFBD><EFBFBD>ʧ<EFBFBD><CAA7>
printf("Motor stall detected\n");
}
}
void motor_steps(uint8_t num, uint8_t dir, uint16_t steps)
{
GPIO_SetBits(GPIOD, GPIO_Pin_4); //TMS2240 - 2ʹ<32><CAB9><EFBFBD>ź<EFBFBD>
delay_us(steps);
GPIO_ResetBits(GPIOD, GPIO_Pin_4); //TMS2240 - 1ʹ<31><CAB9><EFBFBD>ź<EFBFBD>
}
void motor_stop(uint8_t num)
{
}
uint8_t crc8_calculate(const uint8_t *data, uint32_t length, uint8_t poly, uint8_t init_val, uint8_t ref_out)
{
// 1. <20><>ʼ<EFBFBD><CABC> CRC <20>Ĵ<EFBFBD><C4B4><EFBFBD>
uint8_t crc = init_val;
// 2. <20><><EFBFBD><EFBFBD>ÿ<EFBFBD><C3BF><EFBFBD>ֽ<EFBFBD>
for (uint32_t i = 0; i < length; i++)
{
// 3. <20><><EFBFBD><EFBFBD>ǰ<EFBFBD>ֽ<EFBFBD><D6BD><EFBFBD> CRC <20>Ĵ<EFBFBD><C4B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD>򣨺<EFBFBD><F2A3A8BA>IJ<EFBFBD><C4B2>
crc ^= data[i];
// 4. <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ǰ<EFBFBD>ֽڵ<D6BD>ÿһλ<D2BB><CEBB>8 λ<><CEBB>
for (uint8_t j = 0; j < 8; j++)
{
// 5. <20>ж<EFBFBD><D0B6><EFBFBD><EFBFBD><EFBFBD>λ<EFBFBD>Ƿ<EFBFBD>Ϊ 1<><31><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ƿ<EFBFBD><C7B7><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʽ
if (crc & 0x80)
{
// <20><><EFBFBD><EFBFBD> 1 λ<><CEBB><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʽ<EFBFBD><CABD><EFBFBD>ȼ<EFBFBD><C8BC>ڶ<EFBFBD><DAB6><EFBFBD>ʽ<EFBFBD><CABD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
crc = (crc << 1) ^ poly;
}
else
{
// <20><><EFBFBD><EFBFBD>λΪ 0<><30><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> 1 λ
crc <<= 1;
}
}
}
// 6. <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ת<EFBFBD><D7AA><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ҫ<EFBFBD><D2AA>
if (ref_out)
{
// <20><>λ<EFBFBD><CEBB>ת CRC <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> 0x12 <20><> 0x48<34><38>
uint8_t reversed = 0;
for (uint8_t i = 0; i < 8; i++)
{
reversed |= ((crc >> i) & 0x01) << (7 - i);
}
crc = reversed;
}
return crc;
}
uint8_t crc8_standard(const uint8_t *data, uint32_t length)
{
// <20><><EFBFBD><EFBFBD> CRC-8/MAXIM/ITU <20><>׼<EFBFBD><D7BC>poly=0x07, init=0x00, ref_out=0
return crc8_calculate(data, length, 0x07, 0x00, 0);
}
uint32_t status ;
u8 flg=0;
extern int flag_microswitch_left; // <20><><EFBFBD><EFBFBD><E7BFAA>left <20><>λ
extern int flag_microswitch_right; // <20><><EFBFBD><EFBFBD><E7BFAA>right <20><>λ
extern uint8_t g_usart1_rx_buf[USART_REC_LEN];
extern uint16_t g_usart1_rx_sta;
extern uint16_t g_usart1_rx_state;
extern uint8_t g_usart2_rx_buf[USART_REC_LEN];
extern uint16_t g_usart2_rx_sta;
extern uint16_t g_usart2_rx_state;
extern uint8_t g_usart3_rx_buf[USART_REC_LEN];
extern uint16_t g_usart3_rx_sta;
extern uint16_t g_usart3_rx_state;
extern uint16_t g_usart6_rx_state;
2026-02-09 17:29:30 +08:00
extern uint8_t g_rx1_buffer[RXBUFFERSIZE]; /* HAL<41><4C>ʹ<EFBFBD>õĴ<C3B5><C4B4>ڽ<EFBFBD><DABD>ջ<EFBFBD><D5BB><EFBFBD> */
/* <20><><EFBFBD>ջ<EFBFBD><D5BB><EFBFBD>, <20><><EFBFBD><EFBFBD>USART_REC_LEN<45><4E><EFBFBD>ֽ<EFBFBD>. */
extern uint8_t g_usart2_rx_buf[USART_REC_LEN];
extern uint16_t g_usart2_rx_sta;
extern uint8_t g_rx2_buffer[RXBUFFERSIZE]; /* HAL<41><4C>ʹ<EFBFBD>õĴ<C3B5><C4B4>ڽ<EFBFBD><DABD>ջ<EFBFBD><D5BB><EFBFBD> */
/* <20><><EFBFBD>ջ<EFBFBD><D5BB><EFBFBD>, <20><><EFBFBD><EFBFBD>USART_REC_LEN<45><4E><EFBFBD>ֽ<EFBFBD>. */
extern uint8_t g_usart3_rx_buf[USART_REC_LEN];
extern uint16_t g_usart3_rx_sta;
extern uint8_t g_rx3_buffer[RXBUFFERSIZE]; /* HAL<41><4C>ʹ<EFBFBD>õĴ<C3B5><C4B4>ڽ<EFBFBD><DABD>ջ<EFBFBD><D5BB><EFBFBD> */
/* <20><><EFBFBD>ջ<EFBFBD><D5BB><EFBFBD>, <20><><EFBFBD><EFBFBD>USART_REC_LEN<45><4E><EFBFBD>ֽ<EFBFBD>. */
extern uint8_t g_usart4_rx_buf[USART_REC_LEN];
extern uint16_t g_usart4_rx_sta;
extern uint8_t g_rx4_buffer[RXBUFFERSIZE]; /* HAL<41><4C>ʹ<EFBFBD>õĴ<C3B5><C4B4>ڽ<EFBFBD><DABD>ջ<EFBFBD><D5BB><EFBFBD> */
/* <20><><EFBFBD>ջ<EFBFBD><D5BB><EFBFBD>, <20><><EFBFBD><EFBFBD>USART_REC_LEN<45><4E><EFBFBD>ֽ<EFBFBD>. */
extern uint8_t g_usart5_rx_buf[USART_REC_LEN];
extern uint16_t g_usart5_rx_sta;
extern uint8_t g_rx5_buffer[RXBUFFERSIZE]; /* HAL<41><4C>ʹ<EFBFBD>õĴ<C3B5><C4B4>ڽ<EFBFBD><DABD>ջ<EFBFBD><D5BB><EFBFBD> */
/* <20><><EFBFBD>ջ<EFBFBD><D5BB><EFBFBD>, <20><><EFBFBD><EFBFBD>USART_REC_LEN<45><4E><EFBFBD>ֽ<EFBFBD>. */
extern uint8_t g_usart6_rx_buf[USART_REC_LEN];
extern uint16_t g_usart6_rx_sta;
extern uint8_t g_rx6_buffer[RXBUFFERSIZE]; /* HAL<41><4C>ʹ<EFBFBD>õĴ<C3B5><C4B4>ڽ<EFBFBD><DABD>ջ<EFBFBD><D5BB><EFBFBD> */
#define D_value 100 //<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ֵ
2026-02-08 17:48:22 +08:00
int main(void)
{
u8 t;
u8 len;
u16 times=0;
u8 start_vein_flg =0; //Ѱ<><D1B0><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>־
int16_t adc1_zoo =0;
int16_t adc2_zoo =0;
int16_t adc3_zoo =0; //<2F><>·<EFBFBD><C2B7><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
int16_t adc1_current =0;
int16_t adc2_current =0;
int16_t adc3_current =0; //<2F><>·<EFBFBD><C2B7><EFBFBD>ĵ<EFBFBD>ǰֵ
u8 ch =0; //<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͨ<EFBFBD><CDA8>ѡ<EFBFBD><D1A1>
2026-02-10 10:28:33 +08:00
uint8_t frame_updata[6] = {0x30,0x30,0x30,0x30,0x30,0x30};
2026-02-08 17:48:22 +08:00
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);//<2F><><EFBFBD><EFBFBD>ϵͳ<CFB5>ж<EFBFBD><D0B6><EFBFBD><EFBFBD>ȼ<EFBFBD><C8BC><EFBFBD><EFBFBD><EFBFBD>2
delay_init(168); //<2F><>ʱ<EFBFBD><CAB1>ʼ<EFBFBD><CABC>
uart1_init(115200); //<2F><><EFBFBD><EFBFBD>1<EFBFBD><31>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ115200 <20><>ָ<EFBFBD><D6B8>
uart2_init(115200); //<2F><><EFBFBD><EFBFBD>1<EFBFBD><31>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ115200 <20><>ָ<EFBFBD><D6B8>
uart3_init(115200); //<2F><><EFBFBD><EFBFBD>1<EFBFBD><31>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ115200 <20><>ָ<EFBFBD><D6B8>
uart4_init(115200); //<2F><><EFBFBD><EFBFBD>1<EFBFBD><31>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ115200 <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϣ<EFBFBD><CFA2>ӡ
uart5_init(115200);
uart6_init(115200); //<2F><><EFBFBD><EFBFBD>6<EFBFBD><36>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ115200 <20>ϴ<EFBFBD><CFB4><EFBFBD>slide
2026-02-09 17:29:30 +08:00
gpio_Init(); //<2F><>ʼ<EFBFBD><CABC>gpio
//TIM1_PWM_Init(16, 32);
//TIM2_PWM_Init(16, 32);
//TIM4_PWM_Init(16, 32);
//TIM_Cmd(TIM1, DISABLE);
//TIM_Cmd(TIM2, DISABLE);
//TIM_Cmd(TIM4, DISABLE);
//---------------------------------------------
// <20><>ʼ<EFBFBD><CABC>DRV8832<33><32><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
DRV8832_Init();
// <20><>ʼ<EFBFBD><CABC>PWM<57><4D>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ҫ<EFBFBD><D2AA><EFBFBD>٣<EFBFBD>
// PWM_Timer_Init();
motor_spi1_init();
motor_spi2_init();
// ʹ<><CAB9>ȫ<EFBFBD><C8AB><EFBFBD>ж<EFBFBD>
__enable_irq();
//=======================================================================
L_Motor_Control(MOTOR_REVERSE);
R_Motor_Control(MOTOR_REVERSE);
delay_ms(500);
M_Motor_Control(MOTOR_REVERSE);
delay_ms(500);
L_Motor_Control(MOTOR_STOP);
M_Motor_Control(MOTOR_STOP);
R_Motor_Control(MOTOR_STOP); //<2F>ϵ<EFBFBD><CFB5><EFBFBD>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ƚ<EFBFBD><C8BD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>λ<EFBFBD><CEBB><EFBFBD><EFBFBD>һ<EFBFBD><D2BB><EFBFBD>ǵ<EFBFBD><C7B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ժ<EFBFBD><D4BA>ڴ<EFBFBD><DAB4><EFBFBD>
//=======================================================================
//<2F><><EFBFBD>Ե<EFBFBD><D4B5><EFBFBD>
while(0) {
// // ʾ<><CABE>1<EFBFBD><31><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ƣ<EFBFBD>ȫ<EFBFBD><C8AB><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ת<EFBFBD><D7AA>
// Motor_Control(MOTOR_FORWARD); // <20><>ת
// // delay_ms(5000);
// Motor_SafeDirectionChange(MOTOR_REVERSE); // <20><>ȫ<EFBFBD>л<EFBFBD><D0BB><EFBFBD><EFBFBD><EFBFBD>ת
// // delay_ms(5000);
//
// Motor_Control(MOTOR_BRAKE); // ɲ<><C9B2>
// delay_ms(500);
//
// Motor_Control(MOTOR_STOP); // ֹͣ<CDA3><D6B9><EFBFBD><EFBFBD><EFBFBD>У<EFBFBD>
// delay_ms(1000);
// ʾ<><CABE>2<EFBFBD><32>PWM<57><4D><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʾ
// L_Motor_SetSpeed(50, MOTOR_FORWARD);
// M_Motor_SetSpeed(50, MOTOR_FORWARD);
// R_Motor_SetSpeed(50, MOTOR_FORWARD);
// delay_ms(5000);
// L_Motor_Control(MOTOR_STOP);
// M_Motor_Control(MOTOR_STOP);
// R_Motor_Control(MOTOR_STOP);
//
// L_Motor_SetSpeed(50, MOTOR_REVERSE);
// M_Motor_SetSpeed(50, MOTOR_REVERSE);
// R_Motor_SetSpeed(50, MOTOR_REVERSE);
// delay_ms(5000);
// L_Motor_Control(MOTOR_STOP);
// M_Motor_Control(MOTOR_STOP);
// R_Motor_Control(MOTOR_STOP);
// // <20><>ת<EFBFBD><D7AA><EFBFBD><EFBFBD>
for(uint8_t speed = 0; speed <= 100; speed += 10)
{
L_Motor_SetSpeed(speed, MOTOR_FORWARD);
M_Motor_SetSpeed(speed, MOTOR_FORWARD);
R_Motor_SetSpeed(speed, MOTOR_FORWARD);
delay_ms(200);
}
delay_ms(2000);
// // <20><>ת<EFBFBD><D7AA><EFBFBD><EFBFBD>
// for(uint8_t speed = 100; speed > 0; speed -= 10)
// {
// L_Motor_SetSpeed(speed, MOTOR_FORWARD);
// M_Motor_SetSpeed(speed, MOTOR_FORWARD);
// R_Motor_SetSpeed(speed, MOTOR_FORWARD);
// delay_ms(200);
// }
L_Motor_SetSpeed(0, MOTOR_STOP);
M_Motor_SetSpeed(0, MOTOR_STOP);
R_Motor_SetSpeed(0, MOTOR_STOP);
// <20><>ת<EFBFBD><D7AA><EFBFBD><EFBFBD>
for(uint8_t speed = 0; speed <= 100; speed += 10)
{
L_Motor_SetSpeed(speed, MOTOR_REVERSE);
M_Motor_SetSpeed(speed, MOTOR_REVERSE);
R_Motor_SetSpeed(speed, MOTOR_REVERSE);
delay_ms(200);
}
delay_ms(2000);
// // <20><>ת<EFBFBD><D7AA><EFBFBD><EFBFBD>
// for(uint8_t speed = 100; speed > 0; speed -= 10)
// {
// L_Motor_SetSpeed(speed, MOTOR_REVERSE);
// M_Motor_SetSpeed(speed, MOTOR_REVERSE);
// R_Motor_SetSpeed(speed, MOTOR_REVERSE);
// delay_ms(200);
// }
delay_ms(1000);
// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>״̬
if(L_Motor_GetFaultStatus()) {
// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ϣ<EFBFBD>ֹͣ<CDA3><D6B9><EFBFBD><EFBFBD>
L_Motor_Control(MOTOR_STOP);
// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ӹ<EFBFBD><D3B9>ϴ<EFBFBD><CFB4><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EBA3AC><EFBFBD><EFBFBD>˸LED<45>򴮿<EFBFBD><F2B4AEBF><EFBFBD><EFBFBD><EFBFBD>
// ...
// <20>ȴ<EFBFBD><C8B4><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
while(L_Motor_GetFaultStatus()) {
delay_ms(100);
}
}
}
//=======================================================================
2026-02-08 17:48:22 +08:00
while(1)
{
// printf("I love you lao zhang\n");
2026-02-10 10:28:33 +08:00
// delay_ms(300);
2026-02-10 10:28:33 +08:00
// printf("I love you zhengshuo\n");
2026-02-10 10:28:33 +08:00
// delay_ms(300);
2026-02-10 10:28:33 +08:00
// Uart5_Send_data(frame_updata,6);
//<2F><><EFBFBD><EFBFBD>ָ<EFBFBD><D6B8><EFBFBD><EFBFBD><EFBFBD>Ƶ<EFBFBD><C6B5><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6><EFBFBD>
if(g_usart6_rx_state==1) //<2F><><EFBFBD><EFBFBD>6<EFBFBD>Ľ<EFBFBD><C4BD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
{
g_usart6_rx_state = 0;
if(g_usart6_rx_buf[1]==0x01) //1ͨ<31><CDA8> BC 01 00 55 XX 66 <20><><EFBFBD><EFBFBD>
{
if(g_usart6_rx_buf[3]==0x55)
{
L_Motor_Control(MOTOR_FORWARD); //<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
}
if(g_usart6_rx_buf[3]==0xaa) //BC 01 00 aa XX 66 <20><>ת
{
L_Motor_Control(MOTOR_REVERSE);
}
if(g_usart6_rx_buf[3]==0xff) //BC 01 00 ff XX 66 <20>ر<EFBFBD>
{
L_Motor_Control(MOTOR_STOP);
}
}
if(g_usart6_rx_buf[1]==0x02) //2ͨ<32><CDA8>
{
if(g_usart6_rx_buf[3]==0x55)
{
M_Motor_Control(MOTOR_FORWARD); //<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
}
if(g_usart6_rx_buf[3]==0xaa) //BC 02 00 aa XX 66 <20><>ת
{
M_Motor_Control(MOTOR_REVERSE);
}
if(g_usart6_rx_buf[3]==0xff) //BC 02 00 ff XX 66 <20>ر<EFBFBD>
{
M_Motor_Control(MOTOR_STOP);
}
}
if(g_usart6_rx_buf[1]==0x03) //3ͨ<33><CDA8>
{
if(g_usart6_rx_buf[3]==0x55)
{
R_Motor_Control(MOTOR_FORWARD); //<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
}
if(g_usart6_rx_buf[3]==0xaa) //BC 03 00 aa XX 66 <20><>ת
{
R_Motor_Control(MOTOR_REVERSE);
}
if(g_usart6_rx_buf[3]==0xff) //BC 03 00 ff XX 66 <20>ر<EFBFBD>
{
R_Motor_Control(MOTOR_STOP);
}
}
//---------------------------------------------------------------
if(g_usart6_rx_buf[1]==0x04) //<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ַ<EFBFBD><D6B7>04 <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>У<EFBFBD><D0A3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>м<EFBFBD><D0BC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʱ<EFBFBD><CAB1><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>м<EFBFBD><D0BC><EFBFBD><EFBFBD><EFBFBD>Ѱ<EFBFBD><D1B0><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ֹͣ<CDA3><D6B9>
//<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ҳ<EFBFBD><D2B2><EFBFBD>Զ<EFBFBD>Ѱ<EFBFBD><D1B0><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ֹͣ
{
if(g_usart6_rx_buf[3]==0xaa)
{
start_vein_flg =1; //Ѱ<><D1B0><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>־
ch = 0; //<2F><><EFBFBD>м俪ʼѰ
}
if(g_usart6_rx_buf[3]==0x55)
{
start_vein_flg =2; //ֹͣѰ<D6B9><D1B0><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD>
}
if(g_usart6_rx_buf[3]==0xff)
{
start_vein_flg =3; //ֹͣ<CDA3><D6B9><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ֹͣ
}
//<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ָ<EFBFBD>ָ<EEA3AC><D6B8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>н<EFBFBD><D0BD>и<EFBFBD><D0B8>г<EFBFBD><D0B3><EFBFBD><EFBFBD>Ķ<EFBFBD><C4B6><EFBFBD>
}
}
//=============================================================================================
//<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Զ<EFBFBD><D4B6><EFBFBD><EFBFBD>Ʋ<EFBFBD><C6B2>֣<EFBFBD><D6A3>Ƿ<EFBFBD>Ҫת<D2AA>Ƶ<EFBFBD><C6B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ж<EFBFBD><D0B6>д<EFBFBD><D0B4><EFBFBD><EFBFBD><EFBFBD>
if(start_vein_flg == 1)
{
switch(ch)
{
case 0:
if((adc2_current-adc2_zoo)<= D_value)
{
M_Motor_Control(MOTOR_FORWARD); //<2F><><EFBFBD><EFBFBD>2<EFBFBD><32><EFBFBD><EFBFBD>
}
else
{
M_Motor_Control(MOTOR_STOP); //<2F><><EFBFBD><EFBFBD>2ֹͣ
ch = 1;
}
break;
//-------------------------------------------------------
case 1:
if((adc1_current-adc1_zoo)<= D_value)
{
L_Motor_Control(MOTOR_FORWARD); //<2F><><EFBFBD><EFBFBD>1<EFBFBD><31><EFBFBD><EFBFBD>
}
else
{
L_Motor_Control(MOTOR_STOP); //<2F><><EFBFBD><EFBFBD>1ֹͣ
ch = 2;
}
break;
//--------------------------------------------------------
case 2:
if((adc3_current-adc3_zoo)<= D_value)
{
R_Motor_Control(MOTOR_FORWARD); //<2F><><EFBFBD><EFBFBD>3<EFBFBD><33><EFBFBD><EFBFBD>
}
else
{
R_Motor_Control(MOTOR_STOP); //<2F><><EFBFBD><EFBFBD>3ֹͣ
ch = 3;
}
break;
}
}
if(start_vein_flg == 3) //ֹͣ ͣ<><CDA3>ʱ<EFBFBD><CAB1>Ӧ<EFBFBD><D3A6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>صĸߣ<C4B8><DFA3>м<EFBFBD><D0BC>Ļص<C4BB><D8B5>٣<EFBFBD>ʹ<EFBFBD>м<EFBFBD>ͻ<EFBFBD><CDBB>һЩ
{
L_Motor_Control(MOTOR_REVERSE);
R_Motor_Control(MOTOR_REVERSE);
delay_ms(500);
M_Motor_Control(MOTOR_REVERSE);
delay_ms(1000);
L_Motor_Control(MOTOR_STOP);
M_Motor_Control(MOTOR_STOP);
R_Motor_Control(MOTOR_STOP); //ֹͣ<CDA3><D6B9><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>slide Ҳ<><D2B2><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
start_vein_flg =0;
}
//-------------------------------------------------------------------------------
//<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
//1<><31><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>̣<EFBFBD><CCA3><EFBFBD><EFBFBD>ң<EFBFBD>ǰ<EFBFBD><C7B0><EFBFBD>ƶ<EFBFBD> ͨ<><CDA8>slide<64><65> <20><><EFBFBD><EFBFBD>X<EFBFBD><58><EFBFBD><EFBFBD>Y<EFBFBD><59><EFBFBD>Ķ<EFBFBD><C4B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͨ<EFBFBD><CDA8><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͷ<EFBFBD><CDB7>λ<EFBFBD><CEBB>)
//2<><32><EFBFBD>ҵ<EFBFBD><D2B5><EFBFBD><EFBFBD><EFBFBD>λ<EFBFBD>ú<EFBFBD><C3BA><EFBFBD>slide<64><65><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Z<EFBFBD><5A><EFBFBD><EFBFBD><EFBFBD>£<EFBFBD><C2A3>ҵ<EFBFBD><D2B5>м<EFBFBD>λ<EFBFBD>õ<EFBFBD><C3B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Z<EFBFBD><5A>ֹͣ
//3<><33><EFBFBD><EFBFBD>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>sensor<6F><72><EFBFBD><EFBFBD><EFBFBD>Ƶ<EFBFBD><C6B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD>£<EFBFBD>slide <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>̬<EFBFBD><CCAC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ҵ<EFBFBD><D2B5><EFBFBD>ȷ<EFBFBD><C8B7>
//4<><34><EFBFBD><EFBFBD><EFBFBD>ҵ<EFBFBD><D2B5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ѿ<EFBFBD><D1BE><EFBFBD>λ<EFBFBD><CEBB>
//5<><35><EFBFBD><EFBFBD>ʼ<EFBFBD><CABC><EFBFBD><EFBFBD>
//==============================================================
//<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ADC<44>ɼ<EFBFBD>
//<2F><><EFBFBD>յ<EFBFBD><D5B5><EFBFBD>ADC<44><43><EFBFBD><EFBFBD> <20><>λBB <20><>β<EFBFBD><CEB2>66 <20>м<EFBFBD><D0BC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD> 01 ADCL ADCH CRC8
//BB 01 A2 08 73 66
//BB -<2D><>λ
//01 -
//A2 -ADCL
//08 -ADCH
//73 -CRC8
//66 -<2D><>β //
//<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ݣ<EFBFBD><DDA3><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>λ<EFBFBD><CEBB><EFBFBD><EFBFBD><EFBFBD>޷<EFBFBD><DEB7><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ĸ<EFBFBD>ͨ<EFBFBD><CDA8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>,<2C><><EFBFBD>˽<EFBFBD><CBBD>ڶ<EFBFBD><DAB6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊͨ<CEAA><CDA8>
if(g_usart1_rx_state == 1)
{
// g_usart1_rx_buf[1] = 0x01;
// g_usart1_rx_buf[3] = 0x34;
// g_usart1_rx_buf[4] = crc8_standard(g_usart1_rx_buf,4);
if(start_vein_flg==0) //δ<><CEB4><EFBFBD><EFBFBD>ǰ<EFBFBD><C7B0><EFBFBD>ɼ<EFBFBD><C9BC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ<EFBFBD><CEAA>ǰͨ<C7B0><CDA8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
{
adc1_zoo =((uint16_t)g_usart1_rx_buf[3]<<8)|g_usart1_rx_buf[2];
}
else //<2F><>ǰ<EFBFBD>ɼ<EFBFBD><C9BC><EFBFBD><EFBFBD><EFBFBD>ֵ
{
adc1_current = ((uint16_t)g_usart1_rx_buf[3]<<8)|g_usart1_rx_buf[2];
}
g_usart1_rx_state = 0;
//--------------------------------------------------------------
g_usart1_rx_buf[1]=0x01; //ʵ<><CAB5><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ԭʼ<D4AD><CABC><EFBFBD><EFBFBD>û<EFBFBD>б
g_usart1_rx_buf[4] = crc8_standard(g_usart1_rx_buf,4); //<2F><><EFBFBD><EFBFBD>У<EFBFBD><D0A3>
//--------------------------------------------------------------
memcpy(frame_updata,g_usart1_rx_buf,6 );
memset(g_usart1_rx_buf, 0x0, 6);
g_rx1_buffer[0] = 0x0;
Uart6_Send_data(frame_updata,6);
}
if(g_usart2_rx_state == 1)
{
if(start_vein_flg==0) //δ<><CEB4><EFBFBD><EFBFBD>ǰ<EFBFBD><C7B0><EFBFBD>ɼ<EFBFBD><C9BC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ<EFBFBD><CEAA>ǰͨ<C7B0><CDA8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
{
adc2_zoo=((uint16_t)g_usart2_rx_buf[3]<<8)|g_usart2_rx_buf[2];
}
else //<2F><>ǰ<EFBFBD>ɼ<EFBFBD><C9BC><EFBFBD><EFBFBD><EFBFBD>ֵ
{
adc2_current = ((uint16_t)g_usart2_rx_buf[3]<<8)|g_usart2_rx_buf[2];
}
g_usart2_rx_state = 0;
//-------------------------------------------------------------------
g_usart2_rx_buf[1]=0x02; //ͨ<><CDA8><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ02
g_usart2_rx_buf[4] = crc8_standard(g_usart2_rx_buf,4); //<2F><><EFBFBD><EFBFBD>У<EFBFBD><D0A3>
//-------------------------------------------------------------------
memcpy(frame_updata,g_usart2_rx_buf,6 );
memset(g_usart2_rx_buf, 0x0, 6);
g_rx2_buffer[0] = 0x0;
Uart6_Send_data(frame_updata,6);
}
if(g_usart3_rx_state == 1)
{
if(start_vein_flg==0) //δ<><CEB4><EFBFBD><EFBFBD>ǰ<EFBFBD><C7B0><EFBFBD>ɼ<EFBFBD><C9BC><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ<EFBFBD><CEAA>ǰͨ<C7B0><CDA8><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
{
adc3_zoo=((uint16_t)g_usart3_rx_buf[3]<<8)|g_usart3_rx_buf[2];
}
else //<2F><>ǰ<EFBFBD>ɼ<EFBFBD><C9BC><EFBFBD><EFBFBD><EFBFBD>ֵ
{
adc3_current = ((uint16_t)g_usart3_rx_buf[3]<<8)|g_usart3_rx_buf[2];
}
g_usart3_rx_state = 0;
//-------------------------------------------------------------------
g_usart3_rx_buf[1]=0x03; //ͨ<><CDA8><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ϊ03
g_usart3_rx_buf[4] = crc8_standard(g_usart3_rx_buf,4); //<2F><><EFBFBD><EFBFBD>У<EFBFBD><D0A3>
//-------------------------------------------------------------------
memcpy(frame_updata,g_usart3_rx_buf,6 );
memset(g_usart3_rx_buf, 0x0, 6);
g_rx3_buffer[0] = 0x0;
Uart6_Send_data(frame_updata,6);
}
//-------------------------------------------------
2026-02-08 17:48:22 +08:00
}
}