小米电机CyberGear--STM32控制:绝对零点设置及位置模式正弦运动

本文参考了小米电机CyberGear STM32HAL 使用指南_小米电机瞬时电流串口指令-CSDN博客(没有关注提供代码中VOFA+通信内容),借助HAL库仅控制单个小米电机。可以实现小米电机绝对零点的设置,以及在位置模式下的正弦运动(运控模式经测试页是可行的),并向电脑反馈电机信息。

CyberGear官方提供的文档:小米企业网盘 -- 分享文件 (mioffice.cn),提取码QDD1,包含说明书,固件包,电机三维图,上位机软件

注意:笔者在使用之前对CAN无了解,仅对串口传输有较充分的认识,调试CyberGear前搞清楚扩展帧和数据区后,根据官方说明书4.2章节以及参考博客,可以顺利对电机开发。

1.硬件

硬石的板子Stm32F407(含CAN接口),电源使用学生电源24V,电机接口使用网购的XT30PB(2+2)带线(不到20元),使用了板上的1个串口(通过仿真器与电脑通信)和CAN接口。

具体连接:通过仿真器TX\RX(板上USB接电脑同样可行,设置好对应串口即可)和板上一串口的RX\TX相连,电机引出线连到板上CAN口。

2.机械限位

SW2022绘制(低版本无法打开),3D打印制作,运动范围为60度。

结构中白色部分是一个120度的运动范围,对应可以做±60的运动。

注意:左图红色部分,电机自带的背面三颗螺钉无法拆卸

具体结构分享至网盘链接:https://pan.baidu.com/s/1mzTPC6rWjv7DBBEoDq2fhQ 
提取码:1234 

3.cubeMX设置

芯片选择其他初始设置在此不赘述,仅介绍关键内容

1)时钟

STM32F407芯片,时钟如下

2)CAN

电机默认波特率1Mbps,需要根据芯片时钟对CAN参数设置,笔者直接借助GPT,要求其根据上述时钟,分析产生1Mbps的波特率,设置如下

使能接收中断,具体是RX0还是RX1,要根据自己的板子确定,可参考他人博客。

3)板子与电脑串口通信(仅电脑接收板子传输的数据)

我使用仿真器的RX接口和32板的USART1与电脑连接;直接对应串口USB与电脑接也是可以

UART4异步通信,波特率115200,接收DMA;

4)TIM2

每隔10ms发送电机信息到电脑,不一定要定时器,也可以每次收到反馈之后,立刻把此次接收的数据传输给电脑

5)NVIC

4.控制程序

1)cybergear与电机交互部分,通信协议

xiaomi_driver.h,存储其定义的一些参数,cybergear.h直接引用即可

#ifndef _XIAOMI_DRIVER_H_
#define _XIAOMI_DRIVER_H_
#include "main.h"

typedef enum {
    RunMode_idx = 0x7005,
    IqRef_idx = 0x7006,
    SpdRef_idx = 0x700A,
    LimitTorque_idx = 0x700B,
    CurKp_idx = 0x7010,
    CurKi_idx = 0x7011,
    CurFiltGain_idx = 0x7014,
    LocRef_idx = 0x7016,
    LimitSpd_idx = 0x7017,
    LimitCur_idx = 0x7018,
    MechPos_idx = 0x7019,
    IqFilt_idx = 0x701A,
    MechVel_idx = 0x701B,
    Vbus_idx = 0x701C,
    Rotation_idx = 0x701D,
    LocKp_idx = 0x701E,
    SpdKp_idx = 0x7020,
    SpdKi_idx = 0x7020
} ControlTable;

typedef enum {
    RunMode_Typ = 's', 
    IqRef_Typ = 'f',
    SpdRef_Typ = 'f',
    LimitTorque_Typ = 'f',
    CurKp_Typ = 'f',
    CurKi_Typ = 'f',
    CurFiltGain_Typ = 'f',
    LocRef_Typ = 'f',
    LimitSpd_Typ = 'f',
    LimitCur_Typ = 'f',
    MechPos_Typ = 'f',
    IqFilt_Typ = 'f',
    MechVel_Typ = 'f',
    Vbus_Typ = 'f',
    Rotation_Typ = 's',
    LocKp_Typ = 'f',
    SpdKp_Typ = 'f',
    SpdKi_Typ = 'f'
} ControlTableType;

//控制参数最值,谨慎更改
#define P_MIN -12.5f
#define P_MAX 12.5f
#define V_MIN -30.0f
#define V_MAX 30.0f
#define KP_MIN 0.0f
#define KP_MAX 500.0f
#define KD_MIN 0.0f
#define KD_MAX 5.0f
#define T_MIN -12.0f
#define T_MAX 12.0f
#define MAX_P 720
#define MIN_P -720

//控制命令宏定义
#define Communication_Type_GetID 0x00           //获取设备的ID和64位MCU唯一标识符
#define Communication_Type_MotionControl 0x01 	//用来向主机发送控制指令
#define Communication_Type_MotorRequest 0x02	//用来向主机反馈电机运行状态
#define Communication_Type_MotorEnable 0x03	    //电机使能运行
#define Communication_Type_MotorStop 0x04	    //电机停止运行
#define Communication_Type_SetPosZero 0x06	    //设置电机机械零位
#define Communication_Type_CanID 0x07	        //更改当前电机CAN_ID
#define Communication_Type_Control_Mode 0x12
#define Communication_Type_GetSingleParameter 0x11	//读取单个参数
#define Communication_Type_SetSingleParameter 0x12	//设定单个参数
#define Communication_Type_ErrorFeedback 0x15

enum CONTROL_MODE   //控制模式定义
{
    Motion_mode = 0,//运控模式
    Position_mode,  //位置模式
    Velcity_mode,     //位置模式
    Current_mode    //电流模式
};
enum ERROR_TAG      //错误回传对照
{
    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//未标定
};

#endif

cybergear.h,协议部分(含设置电机等),暂未提供电脑接收数据相关设置(后续补充)。

注:修正了参考博客中设置电机零位中的错误,参考电机说明书内容

#ifndef __CYBERGEAR_H
#define __CYBERGEAR_H

#include "main.h"
#include "can.h"
#include "xiaomi_driver.h"
#include "pc_communication.h"

#ifdef __cplusplus
extern "C" {
#endif
    
extern volatile float motor_info[4];

//主机CANID设置
#define Master_CAN_ID 0x00                      //主机ID

//参数读取宏定义

#define Gain_Angle 720/32767.0
#define Bias_Angle 0x8000
#define Gain_Speed 30/32767.0
#define Bias_Speed 0x8000
#define Gain_Torque 12/32767.0
#define Bias_Torque 0x8000
#define Temp_Gain   0.1

#define Motor_Error 0x00
#define Motor_OK 0X01

typedef enum 
{
	Unit_Default,
	Unit_Deg=1,
	Unit_RPM=1,
	Unit_mA=1
}Unit;

typedef struct{
    
    volatile float freq;
    volatile float amp;//角度值
    volatile float delay;
    volatile float offset;
    volatile float downRatio;
    
} SinMotion;

typedef struct{           //小米电机结构体
	uint8_t CAN_ID;       //CAN ID
    uint8_t MCU_ID;       //MCU唯一标识符[后8位,共64位]

	float des_cur;
	float des_vel;
	float des_pos;
    
    float pre_cur;
    float pre_vel;
    float pre_pos;
    float pre_tor;
    float pre_temperature;
    uint8_t error_code;
    
    //零位选择通过Init_CyberZero()设置
    float ini_tor;
    float ini_vel;
    float ini_pos;
    float ini_kp, sin_kp;
    float ini_kd, sin_kd;
    
    //最大限制
    float max_tor;
    float max_pos;
    float max_vel;
    float tor_threshold;
    
	float zero_pos;
    
    SinMotion MotionPara;
    

}Cyber_Motor;


    
extern Cyber_Motor Cyber;
/*****************************初始化*****************************/
void Init_Cyber(Cyber_Motor *Motor, uint8_t Can_Id);
void Start_Cyber(Cyber_Motor *Motor);
void Stop_Cyber(Cyber_Motor *Motor, uint8_t clear_error);

/*****************************设置电机参数*****************************/
void Set_Cyber_Mode(Cyber_Motor *Motor, uint8_t Mode);
void Set_Cyber_ZeroPos(Cyber_Motor *Motor);
void Set_Cyber_Pos(Cyber_Motor *Motor, float value);//仅位置模式, value单位为Deg
void Set_Cyber_limitSp(Cyber_Motor *Motor, float value);//同时设置电机结构体中的max_spd, value单位为RPM
void Set_Cyber_limitTor(Cyber_Motor *Motor, float value);//同时设置电机结构体中的max_tor, value单位为Nm
void Set_Cyber_RotNum(Cyber_Motor *Motor, float value);//设置电机当前圈数
void Read_Cyber_Pos(Cyber_Motor *Motor);//获得反馈,发送位置可以时刻获得位置,这个呢
/*****************************运动控制模式*****************************/
void Cyber_ControlMode(Cyber_Motor *Motor,float tor, float vel_rads, float pos_rad, float kp, float kd);//仅运控模式

/*****************************反馈帧处理回调函数 负责接回传信息 *****************************/
void request_motor_feedback(Cyber_Motor *Motor);
void Motor_Data_Handler(Cyber_Motor *Motor,uint8_t DataFrame[8],uint32_t IDFrame);


/*****************************暂时没用,电机参数读取设置*****************************/
void Check_Cyber(uint8_t ID);

void set_CANID_cybergear(Cyber_Motor *Motor, uint8_t CAN_ID);
void Set_Cyber_Cur(Cyber_Motor *Motor, float Current);
uint32_t Get_Motor_ID(uint32_t CAN_ID_Frame);

/*****************************电机协议*****************************/
float uint16_to_float(uint16_t x,float x_min,float x_max,int bits);
int float_to_uint(float x, float x_min, float x_max, int bits);
void Set_Cyber_Parameter(Cyber_Motor *Motor,uint16_t Index,float Value,char Value_type);
void Set_Cyber_Parameter(Cyber_Motor *Motor,uint16_t Index,float Value,char Value_type);
void Read_Cyber_Parameter(Cyber_Motor *Motor,uint16_t Index);

#ifdef __cplusplus
  }
#endif
  
#endif

cybergear.c

#include "main.h"
#include "can.h"
#include "cybergear.h"
#include "math.h"

Cyber_Motor Cyber;//小米电机定义
CAN_RxHeaderTypeDef rxMsg;//发送接收结构体
CAN_TxHeaderTypeDef txMsg;//发送配置结构体
uint8_t rx_data[8];       //接收数据
uint32_t Motor_Can_ID;    //接收数据电机ID
uint8_t byte[4];          //转换临时数据
uint32_t send_mail_box = {0};//NONE
 
#define can_txd() HAL_CAN_AddTxMessage(&hcan1, &txMsg, tx_data, &send_mail_box)//CAN发送宏定义

const float pi = 3.14159265358979323846f;

/***************************************初始化**************************************/
//@brief          小米电机初始化参数
void Init_Cyber(Cyber_Motor *Motor,uint8_t Can_Id)
{
    txMsg.StdId = 0;            //配置CAN发送:标准帧清零 
    txMsg.ExtId = 0;            //配置CAN发送:扩展帧清零     
    txMsg.IDE = CAN_ID_EXT;     //配置CAN发送:扩展帧
    txMsg.RTR = CAN_RTR_DATA;   //配置CAN发送:数据帧
    txMsg.DLC = 0x08;           //配置CAN发送:数据长度
    
    Motor->CAN_ID=Can_Id;       //ID设置 

}

//@brief          使能电机
void Start_Cyber(Cyber_Motor *Motor)
{
    uint8_t tx_data[8] = {0}; 
    txMsg.ExtId = Communication_Type_MotorEnable<<24|Master_CAN_ID<<8|Motor->CAN_ID;
    can_txd();
}

//@brief          停止电机
void Stop_Cyber(Cyber_Motor *Motor,uint8_t clear_error)
{
	uint8_t tx_data[8]={0};
	tx_data[0]=clear_error;//清除错误位设置 clear_error=1时清除故障
	txMsg.ExtId = Communication_Type_MotorStop<<24|Master_CAN_ID<<8|Motor->CAN_ID;
    can_txd();
}


/*****************************设置电机参数*****************************/
//@brief          设置电机模式(必须停止时调整!)
void Set_Cyber_Mode(Cyber_Motor *Motor,uint8_t Mode)
{	
	Set_Cyber_Parameter(Motor,RunMode_idx,Mode,'s');
}

//@brief          设置电机位置,单位弧度;补充value为角度时的内容
void Set_Cyber_Pos(Cyber_Motor *Motor, float value) 
{
    float pos = value * pi / 180;
    Set_Cyber_Parameter(Motor, LocRef_idx, pos, 'f');
    Motor->des_pos = value;
}

//@brief          设置电机当前位置为零点
void Set_Cyber_ZeroPos(Cyber_Motor *Motor)
{
    uint8_t tx_data[8]={0};
    tx_data[0]=1;
    txMsg.ExtId = Communication_Type_SetPosZero<<24|Master_CAN_ID<<8|Motor->CAN_ID;
    can_txd();
}

//@brief          设置电机运动限速,单位弧度/s
void Set_Cyber_limitSp(Cyber_Motor *Motor, float value) {
    Set_Cyber_Parameter(Motor, LimitSpd_idx, value, 'f');
    Motor->max_vel = value;
}

//@brief          设置电机运动最大扭矩,单位Nm
void Set_Cyber_limitTor(Cyber_Motor *Motor, float value)
{
    Set_Cyber_Parameter(Motor, LimitTorque_idx, value, 'f');
    Motor->max_tor = value;
}

//@brief          设置电机当前圈数
void Set_Cyber_RotNum(Cyber_Motor *Motor, float value)
{
    Set_Cyber_Parameter(Motor, Rotation_idx, value, 'f');
    //Motor->max_tor = value;
}

void Read_Cyber_Pos(Cyber_Motor *Motor)
{
    Read_Cyber_Parameter(Motor, LocRef_idx);
}

/***************************************反馈帧处理回调函数 负责接回传信息 ***************************************/
//反馈电机信息
void request_motor_feedback(Cyber_Motor *Motor)
{
    uint8_t tx_data[8]={0};
	txMsg.ExtId = Communication_Type_MotorRequest<<24|Master_CAN_ID<<8|Motor->CAN_ID;
    can_txd();
}
/**
  * @brief          电机回复帧数据处理函数
  * @param[in]      Motor:对应控制电机结构体   
  * @param[in]      DataFrame:数据帧
  * @param[in]      IDFrame:扩展ID帧
  * @retval         None
  */
void Motor_Data_Handler(Cyber_Motor *Motor,uint8_t DataFrame[8],uint32_t IDFrame)
{	
    Motor->pre_pos=uint16_to_float(DataFrame[0]<<8|DataFrame[1],MIN_P,MAX_P,16);//DataFrame[0]<<8|DataFrame[1]低8位和高8位合并
    Motor->pre_vel=uint16_to_float(DataFrame[2]<<8|DataFrame[3],V_MIN,V_MAX,16);
    Motor->pre_tor=uint16_to_float(DataFrame[4]<<8|DataFrame[5],T_MIN,T_MAX,16);
    Motor->pre_temperature=(DataFrame[6]<<8|DataFrame[7])*Temp_Gain;
    Motor->error_code=(IDFrame&0x1F0000)>>16;
}

/***************************************电机信息接受和发送**************************************/

/**
  * @brief          hal库CAN回调函数,接收电机数据
  * @param[in]      hcan:CAN句柄指针
  * @retval         none
  */
void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan)
{
    HAL_CAN_GetRxMessage(hcan, CAN_RX_FIFO1, &rxMsg, rx_data);//接收数据  
    Motor_Data_Handler(&Cyber,rx_data,rxMsg.ExtId);
}



//@brief          小米运控模式指令
void Cyber_ControlMode(Cyber_Motor *Motor,float tor, float vel_rpm, float pos_deg, float kp, float kd)
{
    float pos_rad = pos_deg * pi / 180;
    float vel_rads = vel_rpm * 30 / pi;
    
    uint8_t tx_data[8];//发送数据初始化
    //装填发送数据
    tx_data[0]=float_to_uint(pos_rad,P_MIN,P_MAX,16)>>8;  
    tx_data[1]=float_to_uint(pos_rad,P_MIN,P_MAX,16);  
    tx_data[2]=float_to_uint(vel_rads,V_MIN,V_MAX,16)>>8;  
    tx_data[3]=float_to_uint(vel_rads,V_MIN,V_MAX,16);  
    tx_data[4]=float_to_uint(kp,KP_MIN,KP_MAX,16)>>8;  
    tx_data[5]=float_to_uint(kp,KP_MIN,KP_MAX,16);  
    tx_data[6]=float_to_uint(kd,KD_MIN,KD_MAX,16)>>8;  
    tx_data[7]=float_to_uint(kd,KD_MIN,KD_MAX,16); 
    
    txMsg.ExtId = Communication_Type_MotionControl<<24|float_to_uint(tor,T_MIN,T_MAX,16)<<8|Motor->CAN_ID;//装填扩展帧数据
    can_txd();
}



/***************************************暂时不用***************************************/
//@brief          设置电机CANID
void set_CANID_cybergear(Cyber_Motor *Motor,uint8_t CAN_ID)
{
	uint8_t tx_data[8]={0};
	txMsg.ExtId = Communication_Type_CanID<<24|CAN_ID<<16|Master_CAN_ID<<8|Motor->CAN_ID;
    Motor->CAN_ID = CAN_ID;//将新的ID导入电机结构体
    can_txd();	
}
//@brief          电流控制模式下设置电流
void Set_Cyber_Cur(Cyber_Motor *Motor,float Current)
{
	Set_Cyber_Parameter(Motor,IqRef_idx,Current,'f');
}

/**
  * @brief          提取电机回复帧扩展ID中的电机CANID
  * @param[in]      CAN_ID_Frame:电机回复帧中的扩展CANID   
  * @retval         电机CANID
  */
uint32_t Get_Motor_ID(uint32_t CAN_ID_Frame)
{
	return (CAN_ID_Frame&0xFFFF)>>8;
}


//@brief          小米电机ID检查
void Check_cyber(uint8_t ID)
{
    uint8_t tx_data[8] = {0};
    txMsg.ExtId = Communication_Type_GetID<<24|Master_CAN_ID<<8|ID;
    can_txd();
}


/***************************************电机内部协议***************************************/
/**
  * @brief          浮点数转4字节函数
  * @param[in]      f:浮点数
  * @retval         4字节数组
  * @description  : IEEE 754 协议
  */
uint8_t* Float_to_Byte(float f)
{
	unsigned long longdata = 0;
	longdata = *(unsigned long*)&f;       
	byte[0] = (longdata & 0xFF000000) >> 24;
	byte[1] = (longdata & 0x00FF0000) >> 16;
	byte[2] = (longdata & 0x0000FF00) >> 8;
	byte[3] = (longdata & 0x000000FF);
	return byte;
}

/**
  * @brief          小米电机回文16位数据转浮点
  * @param[in]      x:16位回文
  * @param[in]      x_min:对应参数下限
  * @param[in]      x_max:对应参数上限
  * @param[in]      bits:参数位数
  * @retval         返回浮点值
  */
float uint16_to_float(uint16_t x,float x_min,float x_max,int bits)
{
    uint32_t span = (1 << bits) - 1;
    float offset = x_max - x_min;
    return offset * x / span + x_min;
}

/**
  * @brief          小米电机发送浮点转16位数据
  * @param[in]      x:浮点
  * @param[in]      x_min:对应参数下限
  * @param[in]      x_max:对应参数上限
  * @param[in]      bits:参数位数
  * @retval         返回浮点值
  */
int float_to_uint(float x, float x_min, float x_max, int bits)
{
  float span = x_max - x_min;
  float offset = x_min;
  if(x > x_max) x=x_max;
  else if(x < x_min) x= x_min;
  return (int) ((x-offset)*((float)((1<<bits)-1))/span);
}

/**
  * @brief          写入电机参数
  * @param[in]      Motor:对应控制电机结构体
  * @param[in]      Index:写入参数对应地址
  * @param[in]      Value:写入参数值
  * @param[in]      Value_type:写入参数数据类型
  * @retval         none
  */
void Set_Cyber_Parameter(Cyber_Motor *Motor,uint16_t Index,float Value,char Value_type)
{
	uint8_t tx_data[8]= {0};
	txMsg.ExtId = Communication_Type_SetSingleParameter<<24|Master_CAN_ID<<8|Motor->CAN_ID;
    memcpy(&tx_data[0],&Index,2);
	if(Value_type == 'f')
    {
        memcpy(&tx_data[4], &Value, sizeof(Value));
	}
	else if(Value_type == 's')
        {
		tx_data[4]=(uint8_t)Value;
	}
	can_txd();	
    HAL_Delay(1);
}

/**
  * @brief          读取电机参数
  * @param[in]      Motor:对应控制电机结构体
  * @param[in]      Index:写入参数对应地址
  * @param[in]      Value:写入参数值
  * @param[in]      Value_type:写入参数数据类型
  * @retval         none
  */
void Read_Cyber_Parameter(Cyber_Motor *Motor,uint16_t Index)
{
	uint8_t tx_data[8]= {0};
	txMsg.ExtId = Communication_Type_GetSingleParameter<<24|Master_CAN_ID<<8|Motor->CAN_ID;
	tx_data[0]=Index;
	tx_data[1]=Index>>8;
	can_txd();	
}

2)具体控制完成零点设置以及位置模式下的正弦运动

注:修改模式为运控模式,并将set_cyber_pos修改为cybergear.h/c中的cyber_controlMode同样可以实现正弦运动函数;

cybermotor.h

#ifndef __CYBERMOTOR_H
#define __CYBERMOTOR_H

#include "cybergear.h"
#include <math.h>
//该文件应该包括 绝对零点设置;正弦运动设置;
#ifdef __cplusplus
extern "C" {
#endif
    
/*****************************获取期望零位*****************************/
void Init_CyberZero(Cyber_Motor *Motor);
void Init_Sin(Cyber_Motor *Motor);

void Setting_AbsoluteZero(Cyber_Motor *Motor);
void Motion_CyberSin(Cyber_Motor *Motor);
    
#ifdef __cplusplus
}
#endif
#endif

cybermotor.cpp

#include "cybermotor.h"

const float pi = 3.14159265358979323846f;


//@brief   绝对零点设置,包括电机初始化,运控模式达到极限值;
void Setting_AbsoluteZero(Cyber_Motor *Motor)
{
    Init_Cyber(Motor, 0x7F);
    //设置当前位置为0位
    Init_CyberZero(Motor);//初始化电机结构体,即运控模式的参数Cyber_ControlMode
    Set_Cyber_Mode(Motor,Position_mode);
    //Set_Cyber_RotNum(Motor, 0);
    Start_Cyber(Motor);//使能电机
    Set_Cyber_RotNum(Motor, 0);
    Set_Cyber_ZeroPos(Motor);
    Set_Cyber_limitSp(Motor,1);
    Set_Cyber_limitTor(Motor,0.2);
    HAL_Delay(100);
    Set_Cyber_Pos(Motor, 10);
    HAL_Delay(100);
    Set_Cyber_Pos(Motor, 20);
    HAL_Delay(100);
    Set_Cyber_Pos(Motor, 40);
    HAL_Delay(100);
    Set_Cyber_Pos(Motor, 130);
    HAL_Delay(100);
    
    
    
    while (1)
    {
        //Set_Cyber_Pos(Motor, 30);
        Set_Cyber_RotNum(Motor, 0);
        
        // 检查力矩和速度
        if (Motor->pre_vel < 0.01)
        {
            Set_Cyber_ZeroPos(Motor);
            Set_Cyber_limitSp(Motor,6);
            Set_Cyber_Pos(Motor, -60);
            HAL_Delay(3000);
            //Set_Cyber_ZeroPos(Motor);
            //break;

            Motion_CyberSin(Motor);

        }
    }
}



// 控制电机正弦运动的函数
void Motion_CyberSin(Cyber_Motor *Motor) 
{
    Init_Sin(Motor);
    uint32_t current_time;
    float position;
    //HAL_Delay(1000);
    
    float period = 1/Motor->MotionPara.freq;
    //float periodPositive = period * Motor->downRatio;
	//float periodNegative = period - periodPositive;
    
//    Init_Cyber(Motor, 0x7F);
//    Set_Cyber_ZeroPos(Motor);
    Set_Cyber_limitSp(Motor, 5);

    // 循环持续指定的时间
    while(1)
    {
        //float amp_rad = Motor->MotionPara.amp * pi/180;
        current_time = HAL_GetTick(); // 更新当前时间
        position = Motor->MotionPara.amp * sinf(2 * pi * Motor->MotionPara.freq * (current_time / 1000.0f))-60;
        Motor->des_pos = position / pi * 180;

        Set_Cyber_Pos(Motor, position);
 
        // 添加延时来控制更新频率
        HAL_Delay(3);
    }
}


/*****************************零位初始化*****************************/
void Init_CyberZero(Cyber_Motor *Motor)
{
    Motor->ini_tor=0.1;
    Motor->ini_vel=0;
    Motor->ini_pos=120;
    Motor->ini_kp=0.8;
    Motor->ini_kd=0.3;
    Motor->tor_threshold=0.15;
}

/*****************************实际驱动函数*****************************/
void Init_Sin(Cyber_Motor *Motor)
{
    Motor->sin_kp = 3;
    Motor->sin_kd = 0.5;
    Motor->MotionPara.amp=20;//角度值
    Motor->MotionPara.freq=3;
    Motor->MotionPara.delay=0;
    Motor->MotionPara.offset=0;
    Motor->MotionPara.downRatio=0.5;//上下扑动的duration相同
}

3)pc_communication.h/c,发送当前位置和电流或其他数据到PC

在定时器回调函数中调用curve_Display函数实现发送;使用VOFA+(一个上位机软件,类似串口助手)的FireWater显示数据,通过curve_Display实现向电脑端的发送,不使用curveDisplay,直接printf也是可以的

pc_communication.h

#ifndef __PCCOM_H
#define __PCCOM_H
 
#include "stm32f4xx_hal.h"  // 根据你的STM32系列调整,如stm32f1xx_hal.h
#include "dma.h"            // 包含 DMA 初始化和配置的头文件
#include <string.h>         // 用于 strlen 函数
#include <stdarg.h>         // 用于可变参数函数
#include <stdio.h>
#include "usart.h"
 
#ifdef __cplusplus
extern "C" {
#endif
    
void PC_Communication(UART_HandleTypeDef* huart, const char* format, ...);
void curve_Display(float a, float b, float c, float d);
    
#ifdef __cplusplus
}
#endif
 
#endif

pc_communication.c

#include "pc_communication.h"
 
volatile float motor_info[5];//不能设置为uint_8,必须要和实际的Motor结构体的一致,否则无法发送
#ifdef __cplusplus
extern "C" {
#endif
    
void PC_Communication(UART_HandleTypeDef* huart, const char* format, ...) {
    static char buffer[1000];
    va_list args;
    va_start(args, format);
    vsnprintf(buffer, sizeof(buffer), format, args);
    va_end(args);
    
    HAL_UART_Transmit_DMA(huart, (uint8_t*)buffer, strlen(buffer));
}
 
void curve_Display(float a, float b, float c, float d)
{
    PC_Communication(&huart1, "d: %.2f, %.2f, %.2f, %.2f\r\n", a, b, c, d);
}
 
#ifdef __cplusplus
|
#endif
 
 

4)定时器回调函数,补充在tim.c最下面

/**
  * @brief          hal库TIM回调函数,发送数据到电脑
  * @param[in]      hcan:TIM句柄指针
  * @retval         none
  */
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
{
    if (htim->Instance == TIM2) // 检查是哪个定时器产生了中断
    {
        motor_info[0] = Cyber.des_pos;
        motor_info[1] = Cyber.pre_pos;
        motor_info[2] = Cyber.pre_vel;
        motor_info[3] = Cyber.pre_tor;
        //motor_info[4] = Cyber.pre_temperature;
        //printf("Desired Position: %f\n", motor_info[0]);
       //printf("Present Position: %f\n", motor_info[1]);
        //printf("Present Velocity: %f\n", motor_info[2]);
        //printf("Present Current: %f\n", motor_info[3]);
        curve_Display(motor_info[0],motor_info[1],motor_info[2],motor_info[3]);
    }
}

每隔10ms,向电机反馈电机的数据

注意:根据说明书,发送一次,只能在发送的时刻瞬间收到一次电机反馈。

例如,如果仅单次发送设置位置1rad,仅在发送的瞬间反馈一次位置命令。如果想要获取电机的运动曲线,必须在while中发送才能绘制相关运动曲线图。

5.绝对零点实现方式解释

1 具体实现在CyberMotor.h/cpp中Setting_AbsoluteZero:

设置运动模式->使能电机->设置当前位置为零点->设置位置模式限速/扭矩->设置位置->进入循环

循环中:设置电机圈数(目的,获取电机反馈(参考说明书,获取通信类型2的反馈),进而获取电机的位置速度扭矩信息)->判断当前速度大小是否小于一个很小的值->如果小于说明电机达到限位,即进入if条件句中->设置当前位置为零点->调整电机限速/扭矩->回到我需要正弦运动的位置(-60的位置)->delay等待达到实际位置(可以修改一下判断是否达到当前位置,通过反馈,而不是delay)->正弦运动函数

2. 遇到的一些问题

使能电机,并设置一个目标位置后,电机会先顺逆运动(方向每一次都不一样)1s多,才会按实际要求运动。因为此,笔者以为每次的位置模式启动后,正角度对应的不是固定顺时针/逆时针;实际是对应的。

可能原因:

1)初始Kp,Kd设置不当; 2)本身传感器可能存在误差; 3)电机本身控制算法中存在误差修正或者启动过程中的初始调整

  • 37
    点赞
  • 24
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值