Dynamixel电机xm430-w210(TTL 协议2)stm32控制:多模式运动和参数读取

Dynamixel电机本身提供了Arduino的库,但没有对stm32开发提供支持。本文完成协议撰写及依靠HAL库对单个电机开发多模式运动(速度模式、位置模式等)和参数读取(位置电流等),可直接用于多电机(经测试,可实现运动及参数读取),以及其他Dynamixel的电机开发,都是通用的。主要C++。

1.硬件

硬石的板子Stm32F407,Dynamixel Shield板,xm430-w210(ttl)电机,2个12V电源

1)接线:主要关注shield(DYNAMIXEL Shield (robotis.com))

a-拔出跳线帽,12V电源线接Power Connector;

b-三个TTL接口,随便一个接电机引出线

c-DXL_DIR接32板子的一个GPIO口(推挽) ,RX接32板串口RX,TX接32板串口TX

d-右图中棕色和黑色线为shield板上的5V和GND接口,分别接32的5V和GND接口

2)接线解释

c主要根据shield板官网介绍,rx接rx,tx接tx,其中GPIO负责使能tx_enable,虽然图中说该口需要接5V输入,经测试3.3V输出的GPIO口也可实现TX和RX的转换;shield板的主要功能就在于上图的芯片(自己在网上没找到类似芯片,要不也不需要花100多买shield板了)

d自己经测试,不接5v无法实现信号传输,GND实现与32供地;

2.cubeMX设置

自己选芯片设置时钟和其他初始设置,仅进行关键介绍

1)TX_Enable GPIO

我这边选了PD12,随便挑一个就行,复用推完,起始输出高(和我后面程序逻辑有关,也可以低);PH9是我的一个led,不用管

2)TX,RX串口通过shield与电机通信

UART4,异步通信,波特率115200(修改电机波特率比较麻烦,可以先按电机默认波特率57600设置);启用收发DMA,关闭接收DMA中断;NVIC最后设置,此处仅展示;

注意此处的TX RX GPIO max output speed必须设置为low,否则会导致无法进入接收中断,可以在下图中修改

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

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

USART1异步通信,波特率115200,接收DMA;parameter setting同uart4

4)NVIC设置,主要把和电脑通信的优先级设置低就好

5)Tim

可以自行加一个定时器定时向电脑发送电机反馈,本文逻辑非此;可参考小米电机CyberGear--STM32控制:绝对零点设置及位置模式正弦运动-CSDN博客中Tim章节进行设置

3.控制代码

1)dynamixelDriver.h/cpp:含基础设置及CRC校验计算

dynamixelDriver.h
#ifndef _DYNAMIXEL_DRIVER_H_
#define _DYNAMIXEL_DRIVER_H_
#include "main.h"

//xm430
typedef enum {
    Model_Number = 0,
    ID = 7,
	Baud_Rate = 8,
    Return_Delay_Time = 9,
    Operating_Mode = 11,
    Protocol_Type = 13,
	Max_Position_Limit = 48,
	Min_Position_Limit = 52,
    SHUTDOWN = 63,
    LED = 65,
    Torque_Enable = 64,
	Hardware_Error = 70,
    Profile_Acceleration = 108,
    Profile_Velocity = 112,
    Goal_Position = 116,
    Goal_Velocity = 104,
    Present_Current = 126,
    Present_Velocity = 128,
    Present_Position = 132,
    Present_Temperature = 146,
    Velocity_Limit = 44,
    Position_P_Gain = 84,
    Position_I_Gain = 82,
    Position_D_Gain = 80,
    Velocity_P_Gain = 78,
    Velocity_I_Gain = 76
} CONTROL_TABLE;

// 枚举:控制表项的大小
typedef enum {
    Model_Number_sz = 2,
    ID_sz = 1,
	Baud_Rate_sz = 1,
    Return_Delay_Time_sz = 1,
    Operating_Mode_sz = 1,
    Protocol_Type_sz = 1,
	Max_Position_Limit_sz = 4,
	Min_Position_Limit_sz = 4,
    SHUTDOWN_sz = 1,
    LED_sz = 1,
    Torque_Enable_sz = 1,
	Hareward_Error_sz = 1,
    Profile_Acceleration_sz = 4,
    Profile_Velocity_sz = 4,
    Goal_Position_sz = 4,
    Goal_Velocity_sz = 4,
    Present_Current_sz = 2,
    Present_Velocity_sz = 4,
    Present_Position_sz = 4,
    Present_Temperature_sz = 1,
    Velocity_Limit_sz = 4,
    PID_sz = 2,
} CONTROL_TABLE_SZ;


typedef enum
{
	P_Position_Gain, //0
	I_Position_Gain, //1
	D_Position_Gain, //2
	P_Velocity_Gain, //3
	I_Velocity_Gain  //4
}ControlTableItem;

typedef enum 
{
	Current_Control,
	Velocity_Control,
	Position_Control=3,
	Extended_Position_Control,
	Current_based_Position_Control,
	PWM_Control=16
}ReadMode;

typedef enum 
{
	Baud_9600,
	Baud_Default,
	Baud_115200,
	Baud_1M,
	Baud_2M,
	Baud_3M,
	Baud_4M,
	Baud_4_5M
}BaudRate;

unsigned short update_crc(unsigned short crc_accum, unsigned char *data_blk_ptr, unsigned short data_blk_size);

#endif
dynamixelDriver.cpp
#include "dynamixelDriver.h" //xm430ControlTable

unsigned short update_crc(unsigned short crc_accum, unsigned char *data_blk_ptr, unsigned short data_blk_size)
{
    unsigned short i, j;
    unsigned short crc_table[256] = {
        0x0000, 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011,
        0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D, 0x8027, 0x0022,
        0x8063, 0x0066, 0x006C, 0x8069, 0x0078, 0x807D, 0x8077, 0x0072,
        0x0050, 0x8055, 0x805F, 0x005A, 0x804B, 0x004E, 0x0044, 0x8041,
        0x80C3, 0x00C6, 0x00CC, 0x80C9, 0x00D8, 0x80DD, 0x80D7, 0x00D2,
        0x00F0, 0x80F5, 0x80FF, 0x00FA, 0x80EB, 0x00EE, 0x00E4, 0x80E1,
        0x00A0, 0x80A5, 0x80AF, 0x00AA, 0x80BB, 0x00BE, 0x00B4, 0x80B1,
        0x8093, 0x0096, 0x009C, 0x8099, 0x0088, 0x808D, 0x8087, 0x0082,
        0x8183, 0x0186, 0x018C, 0x8189, 0x0198, 0x819D, 0x8197, 0x0192,
        0x01B0, 0x81B5, 0x81BF, 0x01BA, 0x81AB, 0x01AE, 0x01A4, 0x81A1,
        0x01E0, 0x81E5, 0x81EF, 0x01EA, 0x81FB, 0x01FE, 0x01F4, 0x81F1,
        0x81D3, 0x01D6, 0x01DC, 0x81D9, 0x01C8, 0x81CD, 0x81C7, 0x01C2,
        0x0140, 0x8145, 0x814F, 0x014A, 0x815B, 0x015E, 0x0154, 0x8151,
        0x8173, 0x0176, 0x017C, 0x8179, 0x0168, 0x816D, 0x8167, 0x0162,
        0x8123, 0x0126, 0x012C, 0x8129, 0x0138, 0x813D, 0x8137, 0x0132,
        0x0110, 0x8115, 0x811F, 0x011A, 0x810B, 0x010E, 0x0104, 0x8101,
        0x8303, 0x0306, 0x030C, 0x8309, 0x0318, 0x831D, 0x8317, 0x0312,
        0x0330, 0x8335, 0x833F, 0x033A, 0x832B, 0x032E, 0x0324, 0x8321,
        0x0360, 0x8365, 0x836F, 0x036A, 0x837B, 0x037E, 0x0374, 0x8371,
        0x8353, 0x0356, 0x035C, 0x8359, 0x0348, 0x834D, 0x8347, 0x0342,
        0x03C0, 0x83C5, 0x83CF, 0x03CA, 0x83DB, 0x03DE, 0x03D4, 0x83D1,
        0x83F3, 0x03F6, 0x03FC, 0x83F9, 0x03E8, 0x83ED, 0x83E7, 0x03E2,
        0x83A3, 0x03A6, 0x03AC, 0x83A9, 0x03B8, 0x83BD, 0x83B7, 0x03B2,
        0x0390, 0x8395, 0x839F, 0x039A, 0x838B, 0x038E, 0x0384, 0x8381,
        0x0280, 0x8285, 0x828F, 0x028A, 0x829B, 0x029E, 0x0294, 0x8291,
        0x82B3, 0x02B6, 0x02BC, 0x82B9, 0x02A8, 0x82AD, 0x82A7, 0x02A2,
        0x82E3, 0x02E6, 0x02EC, 0x82E9, 0x02F8, 0x82FD, 0x82F7, 0x02F2,
        0x02D0, 0x82D5, 0x82DF, 0x02DA, 0x82CB, 0x02CE, 0x02C4, 0x82C1,
        0x8243, 0x0246, 0x024C, 0x8249, 0x0258, 0x825D, 0x8257, 0x0252,
        0x0270, 0x8275, 0x827F, 0x027A, 0x826B, 0x026E, 0x0264, 0x8261,
        0x0220, 0x8225, 0x822F, 0x022A, 0x823B, 0x023E, 0x0234, 0x8231,
        0x8213, 0x0216, 0x021C, 0x8219, 0x0208, 0x820D, 0x8207, 0x0202
    };

    for(j = 0; j < data_blk_size; j++)
    {
        i = ((unsigned short)(crc_accum >> 8) ^ data_blk_ptr[j]) & 0xFF;
        crc_accum = (crc_accum << 8) ^ crc_table[i];
    }

    return crc_accum;
};

2)servo.h/cpp 通信协议,设置及读取参数

servo.h
#ifndef SERVO_H_
#define SERVO_H_

#include "stdio.h"	
#include "main.h"
#include "string.h"
#include "dynamixelDriver.h" //xm430ControlTable
#include "dma.h"
#include "usart.h"
#include "pc_communication.h"

#ifdef __cplusplus
extern "C" {
#endif
    
#define TX_Enable(state) HAL_GPIO_WritePin(GPIOD, GPIO_PIN_12, (state) ? GPIO_PIN_SET : GPIO_PIN_RESET)
#define Servo_Max_Param 20
extern volatile uint8_t USART_TX_STA;
//extern volatile uint8_t USART_TX_STA;
//32发信息
enum ServoCommand
{
    PING = 1,//电机信息
    READ = 2,
    WRITE = 3
};

//32收信息
typedef struct
{
	__I uint8_t id;
	__I uint16_t length;
    __I uint8_t error;
	__I uint8_t command;
    __I uint8_t params[Servo_Max_Param];
	__I uint16_t crc;
} ServoStatus;

//extern uint8_t USART_TX_STA;
extern ServoStatus usart_status;
#ifdef __cplusplus
class Servo{
	public:
		Servo(uint32_t ini_baudrate=115200)//default 57600
        {
			baudrate=ini_baudrate;
		}
		
		bool servoInit(const uint8_t servoId);
		bool ping(const uint8_t servoId);
        bool setProtocolType(const uint8_t servoId, const uint8_t value);
		bool setBaudRate(const uint8_t servoId, const uint8_t value);
		bool setReturnDelayTime(const uint8_t servoId, const uint8_t value);
		bool changeId(const uint8_t servoId, const uint8_t new_id);
		bool setOperatingMode(const uint8_t servoId, const uint8_t value);
		
		bool torque(const uint8_t servoId, uint8_t onoff);
		bool torqueOn(const uint8_t servoId);
		bool torqueOff(const uint8_t servoId);
		bool led(const uint8_t servoId, uint8_t onoff);
		bool ledOn(const uint8_t servoId);
		bool ledOff(const uint8_t servoId);
		
		bool setGoalPosition(const uint8_t servoId, const double Goal_Deg, Unit mode = Unit_Deg);
		bool setGoalVelocity(const uint8_t servoId, const int32_t value);
		bool setPositionLimit(const uint8_t servoId, const uint16_t min_value, const uint16_t max_value);
		
		bool setProfileVelocity(const uint8_t servoId, const uint16_t value);
		bool setProfileAcceleration(const uint8_t servoId, const uint16_t value);
		bool setVelocityLimit(const uint8_t servoId, const uint16_t value);
		bool setPID(const uint8_t servoId, ControlTableItem item, const uint16_t value);
		
		short readTemperature(const uint8_t servoId);
		short readHardwareError(const uint8_t servoId);
		float readPresentPosition(const uint8_t servoId, Unit mode = Unit_Deg);
		double readPresentVelocity(const uint8_t servoId, Unit mode = Unit_RPM);
		float readPresentCurrent(const uint8_t servoId, Unit mode = Unit_mA);
		

private:
		void sendServoCommand (const uint8_t servoId, const ServoCommand commandByte, const uint16_t numParams, const uint8_t *params);

        
private:
		uint32_t baudrate;

};

#endif

void ProcessReceivedData(void);
#ifdef __cplusplus
}
#endif

#endif
servo.cpp
 
#include "servo.h" 
#include "string.h"
#include "stdlib.h"
#include "stm32f4xx_hal.h"

// Status location
#define SERVO_ID_POS 4
#define SERVO_LEN_L_POS 5
#define SERVO_LEN_H_POS 6
#define SERVO_ERROR_POS 8
#define SERVO_PARAM_POS 9

ServoStatus usart_status;
volatile uint8_t USART_TX_STA=1;
static uint8_t *TxPacket = NULL;


bool Servo::servoInit(const uint8_t servoId)
{
	setOperatingMode(servoId, Position_Control);
	setReturnDelayTime(servoId, 40);
	torqueOn(servoId);

	return true;
}

bool Servo::ping(const uint8_t servoId)
{
	sendServoCommand (servoId, PING, 0, 0);

	return true;
}

bool Servo::setProtocolType(const uint8_t servoId, const uint8_t value)
{
	uint8_t address_Value_low = (uint8_t)Protocol_Type& 0xff;
	uint8_t address_Value_high = (uint8_t)(Protocol_Type>> 8)  & 0xff;
	
    const uint8_t params[Protocol_Type_sz+2]={address_Value_low,address_Value_high, value};
    sendServoCommand(servoId, WRITE, Protocol_Type_sz+2, params);

	return 1;
}

bool Servo::setBaudRate(const uint8_t servoId, const uint8_t value)
{
	uint8_t address_Value_low = (uint8_t)Baud_Rate& 0xff;
	uint8_t address_Value_high = (uint8_t)(Baud_Rate>> 8)  & 0xff;
	
    const uint8_t params[Protocol_Type_sz+2]={address_Value_low,address_Value_high, value};
    sendServoCommand(servoId, WRITE, Baud_Rate_sz+2, params);

	return 1;
}

bool Servo::setOperatingMode(uint8_t servoId, uint8_t value)
{
	uint8_t address_Value_low = (uint8_t)Operating_Mode& 0xff;
	uint8_t address_Value_high = (uint8_t)(Operating_Mode>> 8)  & 0xff;
	
    const uint8_t params[Operating_Mode_sz+2]={address_Value_low,address_Value_high, value};
    sendServoCommand(servoId, WRITE, Operating_Mode_sz+2, params);

	return 1;
}

bool Servo::setReturnDelayTime(const uint8_t servoId, const uint8_t value)
{
	uint8_t address_Value_low = (uint8_t)Return_Delay_Time& 0xff;
	uint8_t address_Value_high = (uint8_t)(Return_Delay_Time>> 8)  & 0xff;
	
    const uint8_t params[Return_Delay_Time_sz+2]={address_Value_low, address_Value_high, value};
    sendServoCommand(servoId, WRITE, Return_Delay_Time_sz+2, params);

	return 1;
}

bool Servo::torque(uint8_t servoId, uint8_t onoff)
{
	uint8_t address_Value_low = (uint8_t)Torque_Enable& 0xff;
	uint8_t address_Value_high = (uint8_t)(Torque_Enable>> 8)  & 0xff;
	
	const uint8_t params[Torque_Enable_sz+2] = {address_Value_low,address_Value_high, onoff};
	sendServoCommand(servoId, WRITE, Torque_Enable_sz+2, params);
	
	return 1;
}

bool Servo::torqueOn(uint8_t servoId)
{
	return torque(servoId, 1);
}

bool Servo::torqueOff(uint8_t servoId)
{
	return torque(servoId, 0);
}

bool Servo::led(uint8_t servoId, uint8_t onoff)
{
	uint8_t address_Value_low = (uint8_t)LED& 0xff;
	uint8_t address_Value_high = (uint8_t)(LED>> 8)  & 0xff;
	
	const uint8_t params[LED_sz+2] = {address_Value_low, address_Value_high, onoff};
	sendServoCommand(servoId, WRITE, LED_sz+2, params);
	
	return 1;;
}

bool Servo::ledOn(uint8_t servoId)
{
	return led(servoId, 1);
}

bool Servo::ledOff(uint8_t servoId)
{
	return led(servoId, 0);
}

//degree->pulse
int16_t Deg2Value(double Goal_Deg)
{
  const uint16_t Goal_Position_Value = uint16_t(Goal_Deg/360*4096);
  return Goal_Position_Value;
}

//-360~360
bool Servo::setGoalPosition(const uint8_t servoId, double Goal_Deg, Unit mode)
{
	uint16_t Goal_Position_Value;
	if (mode==Unit_Deg)
	{
		//if(Goal_Deg<0) Goal_Deg = 360+ Goal_Deg;
		Goal_Position_Value = Deg2Value(Goal_Deg);
	}
	else Goal_Position_Value = Goal_Deg;
	
	uint8_t PositionValue_low = (uint8_t) Goal_Position_Value & 0xff;
	uint8_t PositionValue_high = (uint8_t)(Goal_Position_Value >> 8)  & 0xff;
	
	uint8_t address_Value_low = (uint8_t)Goal_Position& 0xff;
	uint8_t address_Value_high = (uint8_t)(Goal_Position>> 8)  & 0xff;
	
	const uint8_t params[Goal_Position_sz+2]={address_Value_low,address_Value_high, PositionValue_low, PositionValue_high,0x00 ,0x00};
	sendServoCommand(servoId, WRITE, Goal_Position_sz+2, params);
	
	return 1;
}

bool Servo::setGoalVelocity(const uint8_t servoId, int32_t value)
{
	uint8_t Value_1 = (uint8_t) value & 0xff;
	uint8_t Value_2 = (uint8_t)(value >> 8)  & 0xff;
	uint8_t Value_3 = (uint8_t)(value >> 16)  & 0xff;
	uint8_t Value_4 = (uint8_t)(value >> 24)  & 0xff;
	
	uint8_t address_Value_low = (uint8_t)Goal_Velocity& 0xff;
	uint8_t address_Value_high = (uint8_t)(Goal_Velocity>> 8)  & 0xff;
	
	const uint8_t params[Goal_Velocity_sz+2]={address_Value_low,address_Value_high, Value_1, Value_2, Value_3 ,Value_4};
	sendServoCommand(servoId, WRITE, Goal_Velocity_sz+2, params);
	
	return 1;
}

//dont work
bool Servo::setPositionLimit(const uint8_t servoId, const uint16_t min_value, const uint16_t max_value)
{
	uint8_t min_Value_1 = (uint8_t) min_value & 0xff;
	uint8_t min_Value_2 = (uint8_t)(min_value >> 8)  & 0xff;
	uint8_t address_min_low = (uint8_t)Min_Position_Limit& 0xff;
	uint8_t address_min_high = (uint8_t)(Min_Position_Limit>> 8)  & 0xff;
	const uint8_t params_min[Min_Position_Limit_sz+2]={address_min_low, address_min_high, min_Value_1, min_Value_2,0x00 ,0x00};
	sendServoCommand(servoId, WRITE, Min_Position_Limit_sz+2, params_min);
	
	HAL_Delay(10);
	
	uint8_t max_Value_1 = (uint8_t) max_value & 0xff;
	uint8_t max_Value_2 = (uint8_t)(max_value >> 8)  & 0xff;
	uint8_t address_max_low = (uint8_t)Max_Position_Limit& 0xff;
	uint8_t address_max_high = (uint8_t)(Max_Position_Limit>> 8)  & 0xff;
	const uint8_t params_max[Max_Position_Limit_sz+2]={address_max_low, address_max_high, max_Value_1, max_Value_2,0x00 ,0x00};
	sendServoCommand(servoId, WRITE, Max_Position_Limit_sz+2, params_max);

	return 1;
}

bool Servo::setProfileVelocity(const uint8_t servoId, uint16_t value)
{
	uint8_t value_low = (uint8_t) value & 0xff;
	uint8_t value_high = (uint8_t)(value >> 8)  & 0xff;
	
	uint8_t address_Value_low = (uint8_t)Profile_Velocity& 0xff;
	uint8_t address_Value_high = (uint8_t)(Profile_Velocity>> 8)  & 0xff;
	
	const uint8_t params[Profile_Velocity_sz+2]={address_Value_low, address_Value_high, 
	                                           value_low, value_high, 0x00 ,0x00};
	
	sendServoCommand(servoId, WRITE, Profile_Velocity_sz+2, params);
	
	return 1;
}

bool Servo::setVelocityLimit(const uint8_t servoId, uint16_t value)
{
	uint8_t unit_low = (uint8_t) value & 0xff;
	uint8_t unit_high = (uint8_t)(value >> 8)  & 0xff;
	
	uint8_t address_Value_low = (uint8_t)Velocity_Limit& 0xff;
	uint8_t address_Value_high = (uint8_t)(Velocity_Limit>> 8)  & 0xff;
	
	const uint8_t params[Velocity_Limit_sz+2]={address_Value_low, address_Value_high, 
	                                           unit_low, unit_high, 0x00 ,0x00};
	
	sendServoCommand(servoId, WRITE, Profile_Velocity_sz+2, params);

	return 1;
}

bool Servo::setProfileAcceleration(const uint8_t servoId, uint16_t unit)
{
	uint8_t unit_low = (uint8_t) unit & 0xff;
	uint8_t unit_high = (uint8_t)(unit >> 8)  & 0xff;
	
	uint8_t address_Value_low = (uint8_t)Profile_Acceleration& 0xff;
	uint8_t address_Value_high = (uint8_t)(Profile_Acceleration>> 8)  & 0xff;
	
	const uint8_t params[Profile_Acceleration_sz+2]={address_Value_low, address_Value_high, 
	                                           unit_low, unit_high, 0x00 ,0x00};

	sendServoCommand(servoId, WRITE, Profile_Acceleration_sz+2, params);
	
	return 1;
}
	


//read present position
float Servo::readPresentPosition(const uint8_t servoId, Unit mode)
{
	uint8_t Present_Position_low = (uint8_t) Present_Position & 0xff;
	uint8_t Present_Position_high = (uint8_t)(Present_Position >> 8)  & 0xff;
	
	const uint8_t params[Present_Position_sz+2]={Present_Position_low, Present_Position_high,  0x04, 0x00};
	sendServoCommand(servoId, READ, 4, params);

	int16_t pre_position_pulses;

	pre_position_pulses = usart_status.params[1];//得到的脉冲值
	pre_position_pulses = (pre_position_pulses << 8) | usart_status.params[0];
	
	float pre_position;
	if (mode==Unit_Deg) 
    {
        pre_position = int(pre_position_pulses) % 4095 * 0.088;
    }//位置模式下位置限制为0~4095,速度模式下无限
	else 
	{
		pre_position = int(pre_position_pulses) % 4095;
		if(pre_position<0) pre_position += 4095;
	}

	return pre_position;
}

double Servo::readPresentVelocity(const uint8_t servoId, Unit mode)
{
	uint8_t Present_Velocity_low = (uint8_t) Present_Velocity & 0xff;
	uint8_t Present_Velocity_high = (uint8_t)(Present_Velocity >> 8)  & 0xff;
	
	const uint8_t params[Present_Position_sz+2]={Present_Velocity_low, Present_Velocity_high,  0x04, 0x00};
	sendServoCommand(servoId, READ, 4, params);//read no question
	
	int16_t pre_velocity_pulses;

	pre_velocity_pulses = usart_status.params[1];//得到的脉冲值
	pre_velocity_pulses = (pre_velocity_pulses << 8) | usart_status.params[0];
	
	double pre_velocity;
	if (mode==Unit_RPM) pre_velocity = pre_velocity_pulses * 0.229;
	else pre_velocity=pre_velocity_pulses;
	
	return pre_velocity;
}

/*得到的是mA值*/
float Servo::readPresentCurrent(const uint8_t servoId, Unit mode)
{
	uint8_t Present_Current_low = (uint8_t) Present_Current & 0xff;
	uint8_t Present_Current_high = (uint8_t)(Present_Current >> 8)  & 0xff;
	
	const uint8_t params[Present_Position_sz+2]={Present_Current_low, Present_Current_high,  0x04, 0x00};
	sendServoCommand(servoId, READ, 4, params);//read no question
	int16_t pre_current_pulses;

	pre_current_pulses = usart_status.params[1];//得到的脉冲值
	pre_current_pulses = (pre_current_pulses << 8) | usart_status.params[0];
	
	float pre_current;
	if (mode==Unit_mA) 
    {
        pre_current = pre_current_pulses * 2.69;
    }
	else pre_current=pre_current_pulses;
	
	return pre_current;
}

short Servo::readTemperature(const uint8_t servoId)
{
	uint8_t Present_Temperature_low = (uint8_t) Present_Temperature & 0xff;
	uint8_t Present_Temperature_high = (uint8_t)(Present_Temperature >> 8)  & 0xff;
	
	const uint8_t params[4] = {Present_Temperature_low, Present_Temperature_high, 0x04, 0x00};
	sendServoCommand(servoId, READ, 4, params);
	int8_t tempreture = usart_status.params[0];

	return tempreture;
}

short Servo::readHardwareError(const uint8_t servoId)
{
	uint8_t Hardware_Error_low = (uint8_t) Hardware_Error & 0xff;
	uint8_t Hardware_Error_high = (uint8_t)(Hardware_Error >> 8)  & 0xff;
	
	const uint8_t params[4] = {Hardware_Error_low, Hardware_Error_high, 0x04, 0x00};
	sendServoCommand(servoId, READ, 4, params);

	int8_t HD_Err = usart_status.params[0];
	return HD_Err;
}

bool Servo::changeId(uint8_t servoId, uint8_t new_id)
{
	uint8_t address_Value_low = (uint8_t)ID& 0xff;
	uint8_t address_Value_high = (uint8_t)(ID>> 8)  & 0xff;
	
	const uint8_t params[ID_sz+2] = {address_Value_low, address_Value_high, new_id};
	sendServoCommand(servoId, WRITE, ID_sz+2, params);

	return 1;
}

bool Servo::setPID(const uint8_t servoId, ControlTableItem item, uint16_t value) 
{
    uint16_t address_Value;

    switch (item) {
        case P_Position_Gain: address_Value = Position_P_Gain; break;
        case I_Position_Gain: address_Value = Position_I_Gain; break;
        case D_Position_Gain: address_Value = Position_D_Gain; break;
        case P_Velocity_Gain: address_Value = Velocity_P_Gain; break;
        case I_Velocity_Gain: address_Value = Velocity_I_Gain; break;
        default: return false; // Handle invalid item values
    }

    uint8_t address_Value_low = static_cast<uint8_t>(address_Value) & 0xff;
    uint8_t address_Value_high = static_cast<uint8_t>(address_Value >> 8) & 0xff;
    
    uint8_t Value_low = static_cast<uint8_t>(value) & 0xff;
    uint8_t Value_high = static_cast<uint8_t>(value >> 8) & 0xff;
    
    uint8_t params[PID_sz + 2] = {address_Value_low, address_Value_high, Value_low, Value_high};
    
    sendServoCommand(servoId, WRITE, PID_sz + 2, params);
    return true;
}

void Servo::sendServoCommand (const uint8_t servoId,
                       const ServoCommand commandByte, // commandByte 分别是Read Write Reg Write等
                       const uint16_t numParams,
                       const uint8_t *params)
{
    
    memset(&usart_status, 0, sizeof(usart_status));

    // 计算数据包长度
    uint16_t Length = numParams + 3; // 参数字节 + 指令字节 + 长度字节
    uint8_t Low_Length = Length & 0xFF;
    uint8_t High_Length = Length >> 8;

    unsigned short packet_length = 10 + numParams;
    TxPacket = (unsigned char *)malloc(packet_length * sizeof(unsigned char));

    // 填充数据包
    TxPacket[0] = 0xff;
    TxPacket[1] = 0xff;
    TxPacket[2] = 0xfd;
    TxPacket[3] = 0x00;
    TxPacket[4] = servoId;
    TxPacket[5] = Low_Length;
    TxPacket[6] = High_Length;
    TxPacket[7] = (uint8_t)commandByte;
    memcpy(&TxPacket[8], params, numParams);

    // 计算校验和,不包括最后2个CRC字节
    unsigned short crc = update_crc(0, TxPacket, packet_length - 2);
    // 将校验和加入到数据包中
    TxPacket[packet_length - 2] = (crc & 0x00FF);
    TxPacket[packet_length - 1] = (crc >> 8) & 0x00FF;

    // 发送数据包
    __disable_irq();// 关闭所有中断
    HAL_UART_Transmit_DMA(&huart4, TxPacket, packet_length);

    while (!__HAL_UART_GET_FLAG(&huart4, UART_FLAG_TC));
    TX_Enable(0);
    USART_TX_STA=0;
    __enable_irq();

    free(TxPacket);
    TxPacket = NULL;
    while(!USART_TX_STA);

}

//接收处理
void ProcessReceivedData(void)
{
    TX_Enable(1);
    USART_TX_STA = 1;
	if (xUART4.ReceiveData[0] == 0xff && xUART4.ReceiveData[1] == 0xff &&
		xUART4.ReceiveData[2] == 0xfd && xUART4.ReceiveData[3] == 0x00) 
	{
		usart_status.id = xUART4.ReceiveData[4];
        usart_status.length = (uint16_t)xUART4.ReceiveData[6] << 8 | xUART4.ReceiveData[5];
        usart_status.command = xUART4.ReceiveData[7];
        usart_status.error = xUART4.ReceiveData[8];
        for(uint8_t i=9;i<xUART4.ReceiveNum-3;i++)
        {
            usart_status.params[i-9] = xUART4.ReceiveData[i];
        }
        
        usart_status.crc = (uint16_t)xUART4.ReceiveData[5+usart_status.length] << 8 | xUART4.ReceiveData[6+usart_status.length];

    }
   
}


3)motionControl.h/cpp实现电机位置正弦运动及读取位置和电流

motionControl.h
#ifndef __MOTORCONTROL_H
#define __MOTORCONTROL_H

#include <stdbool.h>
#include <stdint.h>
#include "servo.h"

#ifdef __cplusplus
extern "C" {
#endif
    
enum MotorEnum
{
  Pitch_Id=1,
  Flap_Id=2,
};

enum MotionEnum
{
	FixedMotion=0,
	SinMotion=1,
	TriMotion=2,
	linerMotion=3,
	Vel_mode=4,
	CosMotion=5
};

void myMotor(void);
void excitation(void);

#ifdef __cplusplus
}
#endif

#ifdef __cplusplus
class Motor : public Servo 
{
public:
    Motor(uint8_t ini_id = 0, uint16_t ini_pos = 180) : Servo(115200)
	{
		id = ini_id;
		des_pos = ini_pos;
	
		servoInit(id);
		setGoalPosition(id, des_pos);
		//setPositionLimit(id, 1365, 2730);
		pre_pos = des_pos;
		pre_vel = 0;
		pre_cur = 0;
		setPID(id, P_Position_Gain, 800);
		setPID(id, I_Position_Gain, 0);
		setPID(id, D_Position_Gain, 0);
		HAL_Delay(800);
	}
	
	uint8_t id;
	volatile uint8_t begin;
    double pre_pos, des_pos;
	int16_t des_pos_pulses, pre_pos_pulses;
    int16_t pre_vel, des_vel, des_vel_pulses, pre_vel_pulses;
    int16_t pre_cur, des_cur;
    uint32_t baud;
	volatile int8_t HD_Err, temperature;
	
	volatile double amplitude; // Sin motion amplitude,in degrees
	volatile int period;
	volatile double delay;     // Phase delay, in degrees
	volatile double offset;    // Initial motion offset,in degrees
	volatile uint8_t funcMode;    // Triangular/Sine/Fixed/
	volatile double downRatio; //downstroke to total period
	volatile double amplitude_up;
	volatile double amplitude_down;
	
	bool motorPreState();
	bool motionInit(float ini_amplitude, float ini_period, float ini_offset, float ini_delay, uint8_t ini_funcMode, float ini_downRatio = 0.5);
	bool motionGeneration();
	void fix_Motion();
	void sin_Motion();
	void cos_Motion();

};

#endif
#endif
motionControl.cpp
#include "motorControl.h"
#include "servo.h"
#include "math.h"

#define PI 3.1415926535

bool Motor::motorPreState()
{
	pre_pos_pulses = readPresentPosition(id, Unit_Pulses);
	pre_pos = pre_pos_pulses * 0.088;
	pre_cur = readPresentCurrent(id);

	return true;
}

bool Motor::motionInit(float ini_amplitude, float ini_period, float ini_offset, float ini_delay, uint8_t ini_funcMode, float ini_downRatio)
{
	begin = 1;
	amplitude = ini_amplitude;
	period = ini_period;
	offset = ini_offset;
	delay = ini_delay;
	funcMode = ini_funcMode;
	downRatio = ini_downRatio;
	amplitude_up = amplitude;
	amplitude_down = amplitude;
	
	
	return true;
}

bool Motor::motionGeneration()
{
	switch (funcMode) 
	{
        case FixedMotion: fix_Motion(); break;
        case SinMotion: sin_Motion(); break;//1
        case CosMotion: cos_Motion();break;//5

        default: return false; 
    }
	
	return 1;
}


void Motor::sin_Motion()
{
	int t = HAL_GetTick() % period;
    int periodPositive = period * downRatio;
	int periodNegative = period * (1 - downRatio);
	
	if (t <= periodPositive)
	{
		des_pos = amplitude_up * sin(2 * PI * t / (periodPositive * 2)) + offset;
	}
	else
	{
		des_pos = amplitude_down * sin(2 * PI * (t-periodPositive+periodNegative) / (periodNegative * 2)) + offset;
	}
    
    setGoalPosition(id, des_pos);
    motorPreState();
}

void Motor::cos_Motion()
{
	int t = HAL_GetTick() % period;
    int periodPositive = period * downRatio;
	int periodNegative = period * (1 - downRatio);
	
	if (t <= periodPositive/2)
	{
		des_pos = cos(2 * PI * t / (periodPositive * 2)+delay* PI/180);
	}
	else if (t>=periodPositive/2 + periodNegative)
	{
		des_pos = cos(2 * PI * (t-periodNegative-periodPositive) / (periodPositive * 2)+delay* PI/180);
	}
	else
	{
		des_pos = cos(2 * PI * (t - periodPositive/2 + periodNegative/2)/ (periodNegative * 2)+delay* PI/180);
	}
	amplitude = (des_pos >= 0) ? amplitude_up : amplitude_down;
	des_pos = des_pos * amplitude+offset;
    
    setGoalPosition(id, des_pos);
    
    motorPreState();
}


void Motor::fix_Motion()
{
	des_pos = offset;
}

void myMotor()
{
	Motor Pitch(Pitch_Id);
	double Pitch_amp, Flap_amp;
	int16_t Pitch_per, Flap_per;
	double Pitch_offset, Flap_offset;
	double Pitch_delay, Flap_delay;
	Pitch_amp = 20; Flap_amp = 20;
	Pitch_per = 1000; Flap_per = 1000;
	Pitch_delay = 0; Flap_delay = 90;
	Pitch_offset = 180; Flap_offset = 180;
	
	Pitch.motionInit(Pitch_amp, Pitch_per, Pitch_offset, Pitch_delay, FixedMotion);
    Pitch.funcMode = 5;
	while(1)
	{
		if(Pitch.begin == 1)
		{
			Pitch.motionGeneration();
		}
        curve_Display(Pitch.pre_pos,0.0, Pitch.pre_cur,0.0);
	}
}

3.串口设置等(对自动生成函数进行补充)

1)usart.h

补充typedef

typedef struct
{
uint16_t ReceiveNum;
uint8_t ReceiveData[64];
uint8_t BuffTemp[64];
}xUATR_TypeDef;

extern xUATR_TypeDef xUSART1;
extern xUATR_TypeDef xUART2;
extern xUATR_TypeDef xUART3;
extern xUATR_TypeDef xUART4;
extern xUATR_TypeDef xUART5;
extern xUATR_TypeDef xUART6;
2)usart.c

#include 补充

xUATR_TypeDef xUSART1;
xUATR_TypeDef xUART2;
xUATR_TypeDef xUART3;
xUATR_TypeDef xUART4;
xUATR_TypeDef xUART5;
xUATR_TypeDef xUART6;

MX_UART4_Init(void)最后补充,使能空闲中断

__HAL_UART_ENABLE_IT(&huart4, UART_IT_IDLE);
HAL_UARTEx_ReceiveToIdle_DMA(&huart4, (uint8_t*) xUART4.BuffTemp, 64);

代码最下面补充,中断后进入下面回调函数

void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size)
{
    if (huart->Instance == UART4)
    {
        HAL_UART_DMAStop(huart);
        xUART4.ReceiveNum = Size;
        memcpy(xUART4.ReceiveData, xUART4.BuffTemp, sizeof(xUART4.BuffTemp));
        ProcessReceivedData(); 
        memset(xUART4.BuffTemp, 0, sizeof(xUART4.BuffTemp));
        HAL_UARTEx_ReceiveToIdle_DMA(huart, (uint8_t*) xUART4.BuffTemp, 64);
    }
}
3)main.c

初始化后面直接调用,或者在while(1)中调用,可以实现电机正弦运动

myMotor();

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

使用VOFA+(上位机软件,类似串口助手)的FireWater显示数据,通过curve_Display实现向电脑端的发送;也可使用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.控制思路简述

主要围绕servo.h/cpp中的sendServoCommand和DMA空闲中断接收不定长数据

1)sendServoCommand中计算完全部的TxPacket中的内容后,需要关闭全部中断,发送完成后打开中断(根据官网协议2Tx, Rx Direction

2)由于使用DMA发送(非阻塞式),需要判断DMA发送完成后才能关闭中断(如果直接串口发送则不需要判断,由于阻塞式发送),同时在判断发送完成后TX_Enable(0),使能RX,并更改USART_TX_STA为0;注意初始GPIO设置中TX_Enable对应端口设置为HIGH LEVEL,以第一次可以发送;

3)使能中断后,while(!USART_TX_STA)以等待中断完成;

4)进入中断后,中断中修改使能TX,并更改USART_TX_STA为1,以进行下一次的发送;具体实现在ProcessReceivedData函数中,被回调函数HAL_UARTEx_RxEventCallback引用;

5)motionControl中实际执行了循环

发送电机期望位置->获取当前位置->获取当前电流->发送电机期望位置

6)使用VOFA+的FireWater显示数据,通过curve_Display实现向电脑端的发送

5.踩坑

1.shield板上没接5V,导致无法发送成功

2.TX RX GPIO max output speed设置为high,导致发送失败/中断无法进入

原因可能是:1)高速输出可能会导致时序问题,例如数据到达接收端的时间不稳定或不可预测,这可能会导致接收端无法正确捕获数据;2)高速输出可能会引入电气干扰,干扰其他设备或信号线,导致通信失败或中断无法触发;3)高速输出可能会导致信号完整性问题,例如信号波形失真或噪声引入

3.空闲中断设置,似乎RX DMA必须把中断关闭

  • 13
    点赞
  • 16
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值