feat: 增加can总线和步进电机指令绑定
This commit is contained in:
@@ -16,6 +16,10 @@
|
||||
<ParametersSub name="BTS1" value="CAN_BTS1_6TQ"/>
|
||||
<ParametersSub name="BTS2" value="CAN_BTS2_1TQ"/>
|
||||
<ParametersSub name="RSAW" value="CAN_RSAW_1TQ"/>
|
||||
<ParametersSub name="Filter_0_Mode" value="CAN_FILTER_MODE_ID_LIST"/>
|
||||
<ParametersSub name="Filter_0_ID1" value="006"/>
|
||||
<ParametersSub name="Filter_0_ID2" value="000"/>
|
||||
<ParametersSub name="Filter_0_ID3" value="007"/>
|
||||
</Parameters>
|
||||
</CAN1>
|
||||
<CRM>
|
||||
@@ -67,7 +71,7 @@
|
||||
<FLASH_IRQHandler>0;0;0</FLASH_IRQHandler>
|
||||
<CRM_IRQHandler>0;0;0</CRM_IRQHandler>
|
||||
<USBFS_H_CAN1_TX_IRQHandler>0;0;0</USBFS_H_CAN1_TX_IRQHandler>
|
||||
<USBFS_L_CAN1_RX0_IRQHandler>0;0;0</USBFS_L_CAN1_RX0_IRQHandler>
|
||||
<USBFS_L_CAN1_RX0_IRQHandler>1;0;0</USBFS_L_CAN1_RX0_IRQHandler>
|
||||
<CAN1_RX1_IRQHandler>0;0;0</CAN1_RX1_IRQHandler>
|
||||
<CAN1_SE_IRQHandler>0;0;0</CAN1_SE_IRQHandler>
|
||||
<EXINT9_5_IRQHandler>0;0;0</EXINT9_5_IRQHandler>
|
||||
@@ -136,7 +140,7 @@
|
||||
</PINInfo>
|
||||
<ProjectInfomation>
|
||||
<ProjectName>BC3D</ProjectName>
|
||||
<ProjectLocation>C:/Users/evan/Desktop</ProjectLocation>
|
||||
<ProjectLocation>C:/Users/ForgotDoge/Desktop/BC2024/firmware</ProjectLocation>
|
||||
<ToolchainIDE>MDK_V5</ToolchainIDE>
|
||||
<KeepUserCode>true</KeepUserCode>
|
||||
<MinHeapSize>0x200</MinHeapSize>
|
||||
|
||||
@@ -26,6 +26,7 @@ by_error_status by_can_send_stdd(uint32_t id, const uint8_t *data, uint8_t len,
|
||||
transmit_mailbox = can_message_transmit(CAN1, &tx_message_struct); /* 将以上待发送报文写入发送邮箱并请求发送 */
|
||||
|
||||
/* 等待该邮箱发送成功—对应邮箱发送成功标志置起 */
|
||||
if (timeout) {
|
||||
while (can_transmit_status_get(CAN1, (can_tx_mailbox_num_type)transmit_mailbox) != CAN_TX_STATUS_SUCCESSFUL) {
|
||||
// LOGD("CAN#SEND: timeout=%d", timeout);
|
||||
if (0 == timeout--) {
|
||||
@@ -35,6 +36,7 @@ by_error_status by_can_send_stdd(uint32_t id, const uint8_t *data, uint8_t len,
|
||||
}
|
||||
DWT_Delay(10);
|
||||
}
|
||||
}
|
||||
|
||||
return BY_SUCCESS;
|
||||
}
|
||||
|
||||
38
app/by_messy.c
Normal file
38
app/by_messy.c
Normal file
@@ -0,0 +1,38 @@
|
||||
#include "by_messy.h"
|
||||
|
||||
#include <string.h>
|
||||
#include "by_stepper.h"
|
||||
#include "by_can.h"
|
||||
|
||||
void by_messy_loop(void)
|
||||
{
|
||||
}
|
||||
|
||||
void by_messy_int(void)
|
||||
{
|
||||
can_rx_message_type can_rx_message_struct;
|
||||
can_message_receive(CAN1, CAN_RX_FIFO0, &can_rx_message_struct);
|
||||
|
||||
// 接收到位置控制帧
|
||||
if (0x006 == can_rx_message_struct.standard_id) {
|
||||
uint8_t mode = 0;
|
||||
uint8_t speed = 0;
|
||||
float position_temp = 0;
|
||||
|
||||
memcpy(&mode, can_rx_message_struct.data, 1);
|
||||
memcpy(&speed, can_rx_message_struct.data + 1, 1);
|
||||
memcpy(&position_temp, can_rx_message_struct.data + 2, 4);
|
||||
|
||||
by_stepper_set_speed((stepper_speed_t)speed);
|
||||
|
||||
if (0 == mode) {
|
||||
by_stepper_set_position_millimeter(position_temp);
|
||||
} else if (1 == mode) {
|
||||
by_stepper_add_position_millimeter(position_temp);
|
||||
}
|
||||
} else if (0x007 == can_rx_message_struct.standard_id) {
|
||||
if (CAN_TFT_REMOTE == can_rx_message_struct.frame_type) {
|
||||
by_can_send_stdd(0x007, &running_flag, 1, 0);
|
||||
}
|
||||
}
|
||||
}
|
||||
9
app/by_messy.h
Normal file
9
app/by_messy.h
Normal file
@@ -0,0 +1,9 @@
|
||||
#ifndef _BY_MESSY_H__
|
||||
#define _BY_MESSY_H__
|
||||
|
||||
#include "at32f413.h"
|
||||
|
||||
extern void by_messy_loop(void);
|
||||
extern void by_messy_int(void);
|
||||
|
||||
#endif
|
||||
108
app/by_motion.c
108
app/by_motion.c
@@ -1,108 +0,0 @@
|
||||
#include "by_motion.h"
|
||||
|
||||
#include "pid.h"
|
||||
#include "dwt_delay.h"
|
||||
#include "by_utils.h"
|
||||
#include "by_debug.h"
|
||||
|
||||
#define DRV_ENABLE() gpio_bits_set(GPIOB, GPIO_PINS_15)
|
||||
#define DRV_DISABLE() gpio_bits_reset(GPIOB, GPIO_PINS_15)
|
||||
|
||||
by_motor_param param_m1;
|
||||
by_motor_param param_m2;
|
||||
PID_TypeDef pid_m1;
|
||||
PID_TypeDef pid_m2;
|
||||
int16_t speed_m1;
|
||||
int16_t speed_m2;
|
||||
uint8_t motion_enable_flag;
|
||||
|
||||
void by_motion_set_pwm_m1(int32_t pwm_duty)
|
||||
{
|
||||
pwm_duty = clip_s32(pwm_duty, -449, 449); // 不可以拉满哦
|
||||
pwm_duty += 499;
|
||||
|
||||
// 互补 pwm 输出,499 为中值
|
||||
tmr_channel_value_set(TMR1, TMR_SELECT_CHANNEL_1, pwm_duty);
|
||||
}
|
||||
|
||||
void by_motion_set_pwm_m2(int32_t pwm_duty)
|
||||
{
|
||||
pwm_duty = clip_s32(pwm_duty, -449, 449); // 不可以拉满哦
|
||||
pwm_duty += 499;
|
||||
|
||||
// 互补 pwm 输出,499 为中值
|
||||
tmr_channel_value_set(TMR1, TMR_SELECT_CHANNEL_2, pwm_duty);
|
||||
}
|
||||
|
||||
int16_t by_motion_get_speed_m1(void)
|
||||
{
|
||||
param_m1.real_speed = (float)(-1 * (int16_t)tmr_counter_value_get(TMR2));
|
||||
tmr_counter_value_set(TMR2, 0);
|
||||
return (int16_t)param_m1.real_speed;
|
||||
}
|
||||
|
||||
int16_t by_motion_get_speed_m2(void)
|
||||
{
|
||||
param_m2.real_speed = (float)(-1 * (int16_t)tmr_counter_value_get(TMR3));
|
||||
tmr_counter_value_set(TMR3, 0);
|
||||
return (int16_t)param_m2.real_speed;
|
||||
}
|
||||
|
||||
void by_motion_set_speed_m1(int16_t speed)
|
||||
{
|
||||
param_m1.target_speed = speed;
|
||||
}
|
||||
|
||||
void by_motion_set_speed_m2(int16_t speed)
|
||||
{
|
||||
param_m2.target_speed = speed;
|
||||
}
|
||||
|
||||
void by_motion_init(void)
|
||||
{
|
||||
motion_enable_flag = 0;
|
||||
|
||||
by_motion_set_pwm_m1(0);
|
||||
by_motion_set_pwm_m2(0);
|
||||
|
||||
/* set default parameters */
|
||||
param_m1.Kp = BY_MOTION_DEFAULT_KP_M1;
|
||||
param_m1.Ki = BY_MOTION_DEFAULT_KI_M1;
|
||||
param_m1.Kd = BY_MOTION_DEFAULT_KD_M1;
|
||||
param_m2.Kp = BY_MOTION_DEFAULT_KP_M2;
|
||||
param_m2.Ki = BY_MOTION_DEFAULT_KI_M2;
|
||||
param_m2.Kd = BY_MOTION_DEFAULT_KD_M2;
|
||||
|
||||
/* load parameters form ee */
|
||||
// TODO
|
||||
|
||||
PID(&pid_m1, ¶m_m1.real_speed, ¶m_m1.out_pwm, ¶m_m1.target_speed, param_m1.Kp, param_m1.Ki, param_m1.Kd, _PID_P_ON_E, _PID_CD_DIRECT);
|
||||
PID_SetMode(&pid_m1, _PID_MODE_AUTOMATIC);
|
||||
PID_SetSampleTime(&pid_m1, 10);
|
||||
PID_SetOutputLimits(&pid_m1, -400, 400);
|
||||
|
||||
PID(&pid_m2, ¶m_m2.real_speed, ¶m_m2.out_pwm, ¶m_m2.target_speed, param_m2.Kp, param_m2.Ki, param_m2.Kd, _PID_P_ON_E, _PID_CD_DIRECT);
|
||||
PID_SetMode(&pid_m2, _PID_MODE_AUTOMATIC);
|
||||
PID_SetSampleTime(&pid_m2, 10);
|
||||
PID_SetOutputLimits(&pid_m2, -400, 400);
|
||||
|
||||
param_m1.target_speed = 17;
|
||||
|
||||
motion_enable_flag = 1;
|
||||
DRV_ENABLE();
|
||||
}
|
||||
|
||||
void by_motion_run(void)
|
||||
{
|
||||
if (motion_enable_flag) {
|
||||
by_motion_get_speed_m1();
|
||||
by_motion_get_speed_m2();
|
||||
|
||||
PID_Compute(&pid_m1);
|
||||
PID_Compute(&pid_m2);
|
||||
|
||||
LOGD("m1:%f,%f,%f", param_m1.real_speed, param_m1.target_speed, param_m1.out_pwm);
|
||||
by_motion_set_pwm_m1((int32_t)param_m1.out_pwm);
|
||||
// by_motion_set_pwm_m2((int32_t)param_m2.out_pwm);
|
||||
}
|
||||
}
|
||||
@@ -1,34 +0,0 @@
|
||||
#ifndef _BY_MOTION_H__
|
||||
#define _BY_MOTION_H__
|
||||
|
||||
#include "at32f413.h"
|
||||
|
||||
typedef struct by_motor_param {
|
||||
float Kp;
|
||||
float Ki;
|
||||
float Kd;
|
||||
float real_speed;
|
||||
float target_speed;
|
||||
float out_pwm;
|
||||
} by_motor_param;
|
||||
|
||||
#define BY_MOTION_DEFAULT_KP_M1 (13.0f)
|
||||
#define BY_MOTION_DEFAULT_KI_M1 (5.0f)
|
||||
#define BY_MOTION_DEFAULT_KD_M1 (0.1f)
|
||||
#define BY_MOTION_DEFAULT_KP_M2 (1.0f)
|
||||
#define BY_MOTION_DEFAULT_KI_M2 (0.0f)
|
||||
#define BY_MOTION_DEFAULT_KD_M2 (0.0f)
|
||||
|
||||
extern void by_motion_init(void);
|
||||
extern void by_motion_run(void);
|
||||
extern void by_motion_set_pwm_m1(int32_t pwm_duty);
|
||||
extern void by_motion_set_pwm_m2(int32_t pwm_duty);
|
||||
extern int16_t by_motion_get_speed_m1(void);
|
||||
extern int16_t by_motion_get_speed_m2(void);
|
||||
extern void by_motion_set_speed_m1(int16_t speed);
|
||||
extern void by_motion_set_speed_m2(int16_t speed);
|
||||
|
||||
extern int16_t speed_m1;
|
||||
extern int16_t speed_m2;
|
||||
|
||||
#endif
|
||||
@@ -1,46 +0,0 @@
|
||||
#include "by_param.h"
|
||||
|
||||
#include <string.h>
|
||||
#include "eeprom.h"
|
||||
#include "by_debug.h"
|
||||
|
||||
by_param_type param_index[BY_PARAM_NUM_MAX];
|
||||
uint16_t param_num = 0;
|
||||
|
||||
by_error_status by_param_init(void)
|
||||
{
|
||||
param_num = 0;
|
||||
return BY_SUCCESS;
|
||||
}
|
||||
|
||||
by_error_status by_param_reg(uint16_t reg_addr, uint16_t *data_ptr, const char *data_str)
|
||||
{
|
||||
param_index[param_num].reg_addr = reg_addr;
|
||||
param_index[param_num].data_ptr = data_ptr;
|
||||
strncpy(param_index[param_num].data_str, data_str, sizeof(param_index[param_num].data_str));
|
||||
LOGD("reg data [%s]: addr-0x%04x", param_index[param_num].data_str, param_index[param_num].reg_addr);
|
||||
param_num++;
|
||||
return BY_SUCCESS;
|
||||
}
|
||||
|
||||
by_error_status by_param_load_from_ee(uint16_t reg_addr)
|
||||
{
|
||||
for (int i = 0; i < param_num; i++) {
|
||||
if (param_index[i].reg_addr == reg_addr) {
|
||||
flash_ee_data_read(reg_addr, param_index[i].data_ptr);
|
||||
return BY_SUCCESS;
|
||||
}
|
||||
}
|
||||
return BY_ERROR;
|
||||
}
|
||||
|
||||
by_error_status by_param_save_to_ee(uint16_t reg_addr)
|
||||
{
|
||||
for (int i = 0; i < param_num; i++) {
|
||||
if (param_index[i].reg_addr == reg_addr) {
|
||||
flash_ee_data_write(reg_addr, *param_index[i].data_ptr);
|
||||
return BY_SUCCESS;
|
||||
}
|
||||
}
|
||||
return BY_ERROR;
|
||||
}
|
||||
@@ -1,19 +0,0 @@
|
||||
#ifndef _BY_PARAM_H__
|
||||
#define _BY_PARAM_H__
|
||||
|
||||
#include "at32f413.h"
|
||||
|
||||
#include "by_utils.h"
|
||||
|
||||
typedef struct by_param_type {
|
||||
uint16_t reg_addr;
|
||||
uint16_t *data_ptr;
|
||||
char data_str[20];
|
||||
} by_param_type;
|
||||
|
||||
#define BY_PARAM_NUM_MAX (20)
|
||||
|
||||
by_error_status by_param_init(void);
|
||||
by_error_status by_param_reg(uint16_t reg_addr, uint16_t *data_ptr, const char *data_str);
|
||||
|
||||
#endif
|
||||
@@ -22,6 +22,7 @@ int64_t position_aim = 0;
|
||||
int64_t position_offset = 0;
|
||||
|
||||
uint8_t running_flag = 0;
|
||||
uint8_t reset_flag = 0;
|
||||
|
||||
// TODO 是否增加一个动作列表?一般都比较简单吧
|
||||
|
||||
@@ -50,6 +51,8 @@ void by_stepper_set_speed(stepper_speed_t speed)
|
||||
void by_stepper_run(void)
|
||||
{
|
||||
// 根据预设条件发送脉冲
|
||||
gpio_bits_write(GPIOA, GPIO_PINS_9, FALSE); // EN
|
||||
|
||||
gpio_bits_write(GPIOA, GPIO_PINS_8, by_stepper.dir ? TRUE : FALSE); // DIR
|
||||
gpio_bits_write(GPIOB, GPIO_PINS_15, !gpio_output_data_bit_read(GPIOB, GPIO_PINS_15)); // CLK
|
||||
DWT_Delay(40U * (uint16_t)by_stepper.speed);
|
||||
@@ -66,6 +69,14 @@ void by_stepper_stop(uint8_t hold)
|
||||
void by_stepper_set_position_millimeter(float distance)
|
||||
{
|
||||
if (!running_flag) {
|
||||
// 设置距离较小时直接复位,减少累计定位误差
|
||||
if (distance < 3 && distance > -3) {
|
||||
reset_flag = 1;
|
||||
running_flag = 1;
|
||||
return;
|
||||
}
|
||||
|
||||
gpio_bits_write(GPIOA, GPIO_PINS_9, FALSE); // EN
|
||||
position_aim = (int64_t)(distance * ENCODER_PULSE_PER_MILLIMETER);
|
||||
position_offset = position_aim - position;
|
||||
running_flag = 1;
|
||||
@@ -75,6 +86,7 @@ void by_stepper_set_position_millimeter(float distance)
|
||||
void by_stepper_add_position_millimeter(float distance)
|
||||
{
|
||||
if (!running_flag) {
|
||||
gpio_bits_write(GPIOA, GPIO_PINS_9, FALSE); // EN
|
||||
position_aim = position + (int64_t)(distance * ENCODER_PULSE_PER_MILLIMETER);
|
||||
position_offset = position_aim - position;
|
||||
running_flag = 1;
|
||||
@@ -113,6 +125,8 @@ void by_stepper_init(void)
|
||||
}
|
||||
|
||||
position = 0; // 位置归零
|
||||
position_aim = 0;
|
||||
position_offset = 0;
|
||||
tmr_counter_value_set(TMR3, 0);
|
||||
|
||||
LOGD("by_stepper init ok");
|
||||
@@ -125,6 +139,14 @@ void by_stepper_loop(void)
|
||||
tmr_counter_value_set(TMR3, 0);
|
||||
|
||||
if (running_flag) {
|
||||
|
||||
if (reset_flag) // 复位模式
|
||||
{
|
||||
by_stepper_init();
|
||||
running_flag = 0;
|
||||
reset_flag = 0;
|
||||
} else // 正常模式
|
||||
{
|
||||
if (position_offset > 0) {
|
||||
by_stepper_set_dir(0);
|
||||
by_stepper_run();
|
||||
@@ -140,6 +162,8 @@ void by_stepper_loop(void)
|
||||
} else {
|
||||
position_offset = position_aim - position;
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
by_stepper_stop(0);
|
||||
}
|
||||
|
||||
@@ -25,5 +25,6 @@ extern void by_stpepper_int(void);
|
||||
extern int64_t position;
|
||||
extern int64_t position_aim;
|
||||
extern int64_t position_offset;
|
||||
extern uint8_t running_flag;
|
||||
|
||||
#endif
|
||||
@@ -65,6 +65,7 @@ void SVC_Handler(void);
|
||||
void DebugMon_Handler(void);
|
||||
void PendSV_Handler(void);
|
||||
|
||||
void USBFS_L_CAN1_RX0_IRQHandler(void);
|
||||
void TMR4_GLOBAL_IRQHandler(void);
|
||||
/* add user code begin exported functions */
|
||||
|
||||
|
||||
@@ -55,65 +55,6 @@ extern "C" {
|
||||
|
||||
/* add user code end exported macro */
|
||||
|
||||
/* add user code begin dma define */
|
||||
/* user can only modify the dma define value */
|
||||
//#define DMA1_CHANNEL1_BUFFER_SIZE 0
|
||||
//#define DMA1_CHANNEL1_MEMORY_BASE_ADDR 0
|
||||
//#define DMA1_CHANNEL1_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA1_CHANNEL2_BUFFER_SIZE 0
|
||||
//#define DMA1_CHANNEL2_MEMORY_BASE_ADDR 0
|
||||
//#define DMA1_CHANNEL2_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA1_CHANNEL3_BUFFER_SIZE 0
|
||||
//#define DMA1_CHANNEL3_MEMORY_BASE_ADDR 0
|
||||
//#define DMA1_CHANNEL3_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA1_CHANNEL4_BUFFER_SIZE 0
|
||||
//#define DMA1_CHANNEL4_MEMORY_BASE_ADDR 0
|
||||
//#define DMA1_CHANNEL4_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA1_CHANNEL5_BUFFER_SIZE 0
|
||||
//#define DMA1_CHANNEL5_MEMORY_BASE_ADDR 0
|
||||
//#define DMA1_CHANNEL5_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA1_CHANNEL6_BUFFER_SIZE 0
|
||||
//#define DMA1_CHANNEL6_MEMORY_BASE_ADDR 0
|
||||
//#define DMA1_CHANNEL6_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA1_CHANNEL7_BUFFER_SIZE 0
|
||||
//#define DMA1_CHANNEL7_MEMORY_BASE_ADDR 0
|
||||
//#define DMA1_CHANNEL7_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA2_CHANNEL1_BUFFER_SIZE 0
|
||||
//#define DMA2_CHANNEL1_MEMORY_BASE_ADDR 0
|
||||
//#define DMA2_CHANNEL1_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA2_CHANNEL2_BUFFER_SIZE 0
|
||||
//#define DMA2_CHANNEL2_MEMORY_BASE_ADDR 0
|
||||
//#define DMA2_CHANNEL2_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA2_CHANNEL3_BUFFER_SIZE 0
|
||||
//#define DMA2_CHANNEL3_MEMORY_BASE_ADDR 0
|
||||
//#define DMA2_CHANNEL3_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA2_CHANNEL4_BUFFER_SIZE 0
|
||||
//#define DMA2_CHANNEL4_MEMORY_BASE_ADDR 0
|
||||
//#define DMA2_CHANNEL4_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA2_CHANNEL5_BUFFER_SIZE 0
|
||||
//#define DMA2_CHANNEL5_MEMORY_BASE_ADDR 0
|
||||
//#define DMA2_CHANNEL5_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA2_CHANNEL6_BUFFER_SIZE 0
|
||||
//#define DMA2_CHANNEL6_MEMORY_BASE_ADDR 0
|
||||
//#define DMA2_CHANNEL6_PERIPHERAL_BASE_ADDR 0
|
||||
|
||||
//#define DMA2_CHANNEL7_BUFFER_SIZE 0
|
||||
//#define DMA2_CHANNEL7_MEMORY_BASE_ADDR 0
|
||||
//#define DMA2_CHANNEL7_PERIPHERAL_BASE_ADDR 0
|
||||
/* add user code end dma define */
|
||||
|
||||
/* Private defines -------------------------------------------------------------*/
|
||||
#define MODE2_PIN GPIO_PINS_12
|
||||
#define MODE2_GPIO_PORT GPIOB
|
||||
|
||||
@@ -31,6 +31,7 @@
|
||||
/* add user code begin private includes */
|
||||
#include "by_debug.h"
|
||||
#include "by_stepper.h"
|
||||
#include "by_messy.h"
|
||||
/* add user code end private includes */
|
||||
|
||||
/* private typedef -----------------------------------------------------------*/
|
||||
@@ -205,6 +206,24 @@ void PendSV_Handler(void)
|
||||
/* add user code end PendSV_IRQ 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief this function handles USB Low Priority or CAN1 RX0 handler.
|
||||
* @param none
|
||||
* @retval none
|
||||
*/
|
||||
void USBFS_L_CAN1_RX0_IRQHandler(void)
|
||||
{
|
||||
/* add user code begin USBFS_L_CAN1_RX0_IRQ 0 */
|
||||
if (SET == can_interrupt_flag_get(CAN1, CAN_RF0MN_FLAG)) {
|
||||
by_messy_int();
|
||||
can_flag_clear(CAN1, CAN_RF0MN_FLAG);
|
||||
}
|
||||
/* add user code end USBFS_L_CAN1_RX0_IRQ 0 */
|
||||
/* add user code begin USBFS_L_CAN1_RX0_IRQ 1 */
|
||||
|
||||
/* add user code end USBFS_L_CAN1_RX0_IRQ 1 */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief this function handles TMR4 handler.
|
||||
* @param none
|
||||
|
||||
@@ -201,6 +201,7 @@ void wk_nvic_config(void)
|
||||
{
|
||||
nvic_priority_group_config(NVIC_PRIORITY_GROUP_4);
|
||||
|
||||
nvic_irq_enable(USBFS_L_CAN1_RX0_IRQn, 0, 0);
|
||||
nvic_irq_enable(TMR4_GLOBAL_IRQn, 0, 0);
|
||||
}
|
||||
|
||||
@@ -424,7 +425,7 @@ void wk_tmr4_init(void)
|
||||
/* add user code end tmr4_init 1 */
|
||||
|
||||
/* configure counter settings */
|
||||
tmr_base_init(TMR4, 9999, 1999);
|
||||
tmr_base_init(TMR4, 9999, 199);
|
||||
tmr_cnt_dir_set(TMR4, TMR_COUNT_UP);
|
||||
tmr_clock_source_div_set(TMR4, TMR_CLOCK_DIV1);
|
||||
tmr_period_buffer_enable(TMR4, FALSE);
|
||||
@@ -556,17 +557,28 @@ void wk_can1_init(void)
|
||||
can_filter_init_struct.filter_number = 0;
|
||||
can_filter_init_struct.filter_fifo = CAN_FILTER_FIFO0;
|
||||
can_filter_init_struct.filter_bit = CAN_FILTER_16BIT;
|
||||
can_filter_init_struct.filter_mode = CAN_FILTER_MODE_ID_MASK;
|
||||
/*Standard identifier + Mask Mode + Data/Remote frame: id/mask 11bit --------------*/
|
||||
can_filter_init_struct.filter_id_high = 0x0 << 5;
|
||||
can_filter_init_struct.filter_id_low = 0x0 << 5;
|
||||
can_filter_init_struct.filter_mode = CAN_FILTER_MODE_ID_LIST;
|
||||
/*Standard identifier + List Mode + Data/Remote frame: id/mask 11bit --------------*/
|
||||
can_filter_init_struct.filter_id_high = 0x000 << 5;
|
||||
can_filter_init_struct.filter_id_low = 0x006 << 5;
|
||||
can_filter_init_struct.filter_mask_high = 0x0 << 5;
|
||||
can_filter_init_struct.filter_mask_low = 0x0 << 5;
|
||||
can_filter_init_struct.filter_mask_low = 0x007 << 5;
|
||||
|
||||
can_filter_init(CAN1, &can_filter_init_struct);
|
||||
|
||||
/* add user code begin can1_init 2 */
|
||||
/**
|
||||
* Users need to configure CAN1 interrupt functions according to the actual application.
|
||||
* 1. Call the below function to enable the corresponding CAN1 interrupt.
|
||||
* --can_interrupt_enable(...)
|
||||
* 2. Add the user's interrupt handler code into the below function in the at32f413_int.c file.
|
||||
* --void USBFS_L_CAN1_RX0_IRQHandler(void)
|
||||
*/
|
||||
|
||||
/*can1 rx0 interrupt config--------------------------------------------------------*/
|
||||
//can_interrupt_enable(CAN1, CAN_RF0MIEN_INT, TRUE);
|
||||
|
||||
/* add user code begin can1_init 2 */
|
||||
can_interrupt_enable(CAN1, CAN_RF0MIEN_INT, TRUE);
|
||||
/* add user code end can1_init 2 */
|
||||
}
|
||||
|
||||
|
||||
@@ -116,7 +116,8 @@ int main(void)
|
||||
|
||||
/* add user code end 2 */
|
||||
|
||||
while (1) {
|
||||
while(1)
|
||||
{
|
||||
/* add user code begin 3 */
|
||||
by_stepper_loop();
|
||||
/* add user code end 3 */
|
||||
|
||||
Reference in New Issue
Block a user