写的差不多了,没保存~~崩溃
接上贴,根据SOEM源文件已经移植完成,编译后会出现一些问题,在用法上(以KEIL工程移植过来为例)不同的地方
typedef __packed struct
{
uint16 ControlWord;
int32 TargetPos;
int8 TargetMode;
// int32 Vel_Offset;
// int32 Torque_Offset;
// int16 Target_Torque;
// // uint32 Max_Velocit;
int32 Target_Velocity;
// uint16 Velocity_Threshould;
// uint16 Velocity_Threshould_Time;
}PDO_Output;
typedef struct __attribute__((packed))
{
uint16 ControlWord;
int32 TargetPos;
int8 TargetMode;
// int32 Vel_Offset;
// int32 Torque_Offset;
// int16 Target_Torque;
// // uint32 Max_Velocit;
int32 Target_Velocity;
// uint16 Velocity_Threshould;
// uint16 Velocity_Threshould_Time;
}PDO_Output;
上面是keil(STM32F4)的用法,下面是修改后的用法
移植源码过程中有许多时间上的东西,主要是超时验证使用,例如下面的timer2=systime,systime是自定义的一个1ms定时器计数的时间。
还需要替换延时函数。
int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
{
int wkc = EC_NOFRAME;
uint32_t timer2;
timer2=systime;
do
{
/* tx frame on primary and if in redundant mode a dummy on secondary */
ecx_outframe_red(port, idx);
if (port->redstate != ECT_RED_NONE)
Delay_Us(200);
wkc = ecx_waitinframe_red(port, idx, timeout);
/* wait for answer with WKC>=0 or otherwise retry until timeout */
} while ((wkc <= EC_NOFRAME) && ((systime-timer2)<timeout));
/* if nothing received, clear buffer index status so it can be used again */
if (wkc <= EC_NOFRAME)
{
ec_setbufstat(idx, EC_BUF_EMPTY);
}
return wkc;
}
本次移植是基于PHY的EtherCat协议,就像移植Tcp/ip一样,因此是直接用到PHY的收发。
uint8_t MAC_Send(uint8_t *data, int length)
{
uint8_t i;
uint32_t buff[100];
for(i = 0; i < (length/4)+1;i++)
{
buff[i] = (data[i*4+3]<<24)+(data[i*4+2]<<16)+(data[i*4+1]<<8)+data[i*4];
}
ETH_TxPktChainMode(length,buff);
return i;
}
直接使用uint32_t ETH_TxPktChainMode(uint16_t len, uint32_t *pBuff );函数进行phy的输出,由于大小端的问题因此做了一下处理。
读数据是直接基于phy的中断进行数据收发
void WCHNET_ETHIsr( void )
{
uint8_t eth_irq_flag, estat_regval;
eth_irq_flag = R8_ETH_EIR;
if(eth_irq_flag&RB_ETH_EIR_RXIF) //Receive complete
{
R8_ETH_EIR = RB_ETH_EIR_RXIF;
/* Check if the descriptor is owned by the ETHERNET DMA */
if( DMARxDescToGet->Status & ETH_DMARxDesc_OWN )
{
estat_regval = R8_ETH_ESTAT;
if(estat_regval & \
(RB_ETH_ESTAT_BUFER | RB_ETH_ESTAT_RXCRCER | RB_ETH_ESTAT_RXNIBBLE | RB_ETH_ESTAT_RXMORE))
{
return;
}
if( ((ETH_DMADESCTypeDef*)(DMARxDescToGet->Buffer2NextDescAddr))->Status& ETH_DMARxDesc_OWN )
{
DMARxDescToGet->Status &= ~ETH_DMARxDesc_OWN;
DMARxDescToGet->Status &= ~ETH_DMARxDesc_ES;
DMARxDescToGet->Status |= (ETH_DMARxDesc_FS|ETH_DMARxDesc_LS);
DMARxDescToGet->Status &= ~ETH_DMARxDesc_FL;
DMARxDescToGet->Status |= ((R16_ETH_ERXLN+4)<<ETH_DMARxDesc_FrameLengthShift);
/* Update the ETHERNET DMA global Rx descriptor with next Rx descriptor */
/* Selects the next DMA Rx descriptor list for next buffer to read */
DMARxDescToGet = (ETH_DMADESCTypeDef*) (DMARxDescToGet->Buffer2NextDescAddr);
R16_ETH_ERXST = DMARxDescToGet->Buffer1Addr;
}
}
从这里获取到数据后保存在缓存内,但是由于中断接收几次后就会出问题
if( DMARxDescToGet->Status & ETH_DMARxDesc_OWN )
接收完数据后这个判定进不去,导致后续一直没实现,现在在调这个bug
memcpy((uint8*)(*stack->rxbuf)[idx], (uint8*)gEtherCatPara.receiveBuffer, gEtherCatPara.receiveLen);
接收完数据后copy到内部缓存里面即可。
以下是ethercat初始化函数
void DevEtherCat_Init(void)
{
INT8U i,err_code = 0;
INT16U count = 20000;
INT8U intstat;
//memset(&gEtherCatPara,0,sizeof(EtherCatType));
ETH_Init(macAddrs);
Delay_Ms(1000);
while( gEtherCatPara.socket_mode == 0 ) // 等待网络初始化,检查有网线插入,如果没有,则报警
{
Delay_Ms(1);
/*Ethernet library main task function,
* which needs to be called cyclically*/
//WCHNET_MainTask();
/*Query the Ethernet global interrupt,
* if there is an interrupt, call the global interrupt handler*/
if(WCHNET_QueryGlobalInt())
{
intstat = WCHNET_GetGlobalInt();
if (intstat & GINT_STAT_PHY_CHANGE) //PHY status change
{
i = WCHNET_GetPHYStatus();
if (i & PHY_Linked_Status)
{
gEtherCatPara.socket_mode = 1;
err_code = 0;
}
else
{
gEtherCatPara.socket_mode = 0;
err_code = 1;
}
}
}
}
printf("\r\nSocket Mode: %d\n\r", gEtherCatPara.socket_mode);
ec_init();//配置单网运行or双网冗余运行
//DrvETH_MACInit();
while( ec_slavecount == 0)
{
if( ec_config_init(TRUE)>0 )
{
printf("%d slaves found and configured.\r\n",ec_slavecount);
if((ec_slavecount >= 1)) // PDO都配置为一样的,因为控制方式一样
{
for(gEtherCatPara.slc = 1; gEtherCatPara.slc <= ec_slavecount; gEtherCatPara.slc++)
{
printf("Found %s at position %d\n", ec_slave[gEtherCatPara.slc].name, gEtherCatPara.slc);
ec_slave[gEtherCatPara.slc].PO2SOconfig = &DevEtherCat_Servosetup;
}
}
/* Run IO mapping */
ec_configdc();
for( i = 1; i <= ec_slavecount; i++) // 配置多个驱动器的DC同步时钟
{
ec_dcsync0(i, TRUE, SYNC0TIME, 250000); // SYNC0 on slave i
}
ec_config_map(&gEtherCatPara.IOmap);
printf("Slaves mapped, state to SAFE_OP.\n");
ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE*4);
ec_readstate();
printf("Slave 0 State=0x%04x\r\n",ec_slave[0].state);
printf("Slave 1 State=0x%04x\r\n",ec_slave[1].state);
ec_slave[0].state = EC_STATE_OPERATIONAL;
/* send one valid process data to make outputs in slaves happy*/
ec_send_processdata();
ec_receive_processdata(EC_TIMEOUTRET);
/* request OP state for all slaves */
ec_writestate(0);
/* wait for all slaves to reach OP state */
ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE);
count = 20000;
do
{
Delay_Ms(1);
ec_send_processdata();
ec_receive_processdata(EC_TIMEOUTRET);
err_code = 0;
for( i = 0; i <= ec_slavecount; i++) // 配置多个设备op
{
ec_statecheck(i, EC_STATE_OPERATIONAL, 50000);
err_code |= ec_slave[0].state;
}
}
// while ((ec_slave[0].state != EC_STATE_OPERATIONAL)&&(ec_slave[1].state != EC_STATE_OPERATIONAL));
while ((err_code != EC_STATE_OPERATIONAL)&& (count-- > 0));
if (ec_slave[0].state == EC_STATE_OPERATIONAL) // 判断有几个从设备,如果多或少都报警
{
printf("Operational state reached for all slaves.\n");
gEtherCatPara.flag_time = 1;
gEtherCatPara.dorun=1;
for( i = 0; i < ec_slavecount;i++) // 将从机的输入输出指向另一个结构体控制
{
outputs[i] = (PDO_Output *)ec_slave[i+1].outputs;
inputs[i] = (PDO_Input *)ec_slave[i+1].inputs;
}
}
else
{
printf("Not all slaves reached operational state.\n");
ec_readstate();
}
}
}
}
先是检测网线是否插入,若插入就进入设备检测。
if( ec_config_init(TRUE)>0 )
判定有设备之后就会进行PDO配置,DC时钟同步,OP->safeop,直到EC_STATE_OPERATIONAL完成这一次链路初始化。
以下是PDO配置,主要配置输入输出功能
INT32S DevEtherCat_Servosetup(INT16U slave)
{
INT32S retval;
INT16U u16val;
INT8U u8val;
INT32U u32val;
retval = 0;
u8val = 0;
retval += ec_SDOwrite(slave, 0x1c12, 0x00, FALSE, sizeof(u8val), &u8val, EC_TIMEOUTRXM);
u16val = 0x1601;
retval += ec_SDOwrite(slave, 0x1c12, 0x01, FALSE, sizeof(u16val), &u16val, EC_TIMEOUTRXM);
u8val = 1;
retval += ec_SDOwrite(slave, 0x1c12, 0x00, FALSE, sizeof(u8val), &u8val, EC_TIMEOUTRXM);
//RPDO Obit
u8val = 0;
retval += ec_SDOwrite(slave, 0x1601, 0x00, FALSE, sizeof(u8val), &u8val, EC_TIMEOUTRXM);
//Control Word uint16
u32val = 0x60400010;
retval += ec_SDOwrite(slave, 0x1601, 0x01, FALSE, sizeof(u32val), &u32val, EC_TIMEOUTRXM);
//Target Position int32
u32val = 0x607A0020;
retval += ec_SDOwrite(slave, 0x1601, 0x02, FALSE, sizeof(u32val), &u32val, EC_TIMEOUTRXM);
//Operation Mode int8
u32val = 0x60600008;
retval += ec_SDOwrite(slave, 0x1601, 0x03, FALSE, sizeof(u32val), &u32val, EC_TIMEOUTRXM);
//Target Tarque int16
u32val = 0x60FF0020;
retval += ec_SDOwrite(slave, 0x1601, 0x04, FALSE, sizeof(u32val), &u32val, EC_TIMEOUTRXM);
u8val = 4;
retval += ec_SDOwrite(slave, 0x1601, 0x00, FALSE, sizeof(u8val), &u8val, EC_TIMEOUTRXM);
u8val = 0;
retval += ec_SDOwrite(slave, 0x1c13, 0x00, FALSE, sizeof(u8val), &u8val, EC_TIMEOUTRXM);
u16val = 0x1a00;
retval += ec_SDOwrite(slave, 0x1c13, 0x01, FALSE, sizeof(u16val), &u16val, EC_TIMEOUTRXM);
u8val = 1;
retval += ec_SDOwrite(slave, 0x1c13, 0x00, FALSE, sizeof(u8val), &u8val, EC_TIMEOUTRXM);
//TPDO Ibit
u8val = 0;
retval += ec_SDOwrite(slave, 0x1a00, 0x00, FALSE, sizeof(u8val), &u8val, EC_TIMEOUTRXM);
//Status Word uint16
u32val = 0x60410010;
retval += ec_SDOwrite(slave, 0x1a00, 0x01, FALSE, sizeof(u32val), &u32val, EC_TIMEOUTRXM);
//Position Actual Val int32
u32val = 0x60640020;
retval += ec_SDOwrite(slave, 0x1a00, 0x02, FALSE, sizeof(u32val), &u32val, EC_TIMEOUTRXM);
//Current Actual Val int16
u32val = 0x60770010;
retval += ec_SDOwrite(slave, 0x1a00, 0x03, FALSE, sizeof(u32val), &u32val, EC_TIMEOUTRXM);
//Velocity Actual Val int32
u32val = 0x606C0020;
retval += ec_SDOwrite(slave, 0x1a00, 0x04, FALSE, sizeof(u32val), &u32val, EC_TIMEOUTRXM);
// Mode Actual Val int32
u32val = 0x60610008;
retval += ec_SDOwrite(slave, 0x1a00, 0x05, FALSE, sizeof(u32val), &u32val, EC_TIMEOUTRXM);
// // Rated Current int32
// u32val = 0x60750020;
// retval += ec_SDOwrite(slave, 0x1a00, 0x06, FALSE, sizeof(u32val), &u32val, EC_TIMEOUTRXM);
//
u8val = 5;
retval += ec_SDOwrite(slave, 0x1a00, 0x00, FALSE, sizeof(u8val), &u8val, EC_TIMEOUTRXM);
//位置 8;速度 9 ; 扭矩 10;
u8val = 9;
retval += ec_SDOwrite(slave, 0x6060, 0x00, FALSE, sizeof(u8val), &u8val, EC_TIMEOUTRXM);
return 1;
}
在主循环内,主要是链路的长链接,还可以做输入输出控制和检测
while(1)
{
/*Ethernet library main task function,
* which needs to be called cyclically*/
WCHNET_MainTask();
/*Query the Ethernet global interrupt,
* if there is an interrupt, call the global interrupt handler*/
if(WCHNET_QueryGlobalInt())
{
WCHNET_HandleGlobalInt();
}
if(gEtherCatPara.dorun==1)
{
if(gEtherCatPara.pdoTimeFlag == 1)
{
gEtherCatPara.pdoTimeFlag=0;
ec_receive_processdata(EC_TIMEOUTRET);
}
}
if( (inputs[0]->StatusWord &0xff) == 0x37) // 使能成功
{
outputs[0]->Target_Velocity = 10; ///10RPM
}
}
}
inputs和outputs对应的就是pdo的配置,结构体对应的是
typedef struct __attribute__((packed))
{
uint16 ControlWord;
int32 TargetPos;
int8 TargetMode;
// int32 Vel_Offset;
// int32 Torque_Offset;
// int16 Target_Torque;
// // uint32 Max_Velocit;
int32 Target_Velocity;
// uint16 Velocity_Threshould;
// uint16 Velocity_Threshould_Time;
}PDO_Output;
typedef struct __attribute__((packed))
{
uint16 StatusWord;
int32 PositionActualVal;
int16 TorqueActualVal;
// uint16 RatedCurrent;
int32 VelocityAtualVal;
//// uint16 ErrorCode;
uint8 ModeActualVal;
//uint8 relese;
}PDO_Input;
该结构体和DevEtherCat_Servosetup()函数需要一一对应,例如
u8val = 0;
retval += ec_SDOwrite(slave, 0x1601, 0x00, FALSE, sizeof(u8val), &u8val, EC_TIMEOUTRXM);
//Control Word uint16
u32val = 0x60400010;
代表结构体的控制字,0x60400010代表6040的命令码,0010代表16位数据,得到uint16 ControlWord;顺序一定要一致。
在ethercatconfiglist.h文件主要配置ethercat从机的xml文件,我用的是伺服驱动器,第一个大括号和第三个大括号内的内容不需要修改,只需要修改第二个大括号的内容即可。
ec_configlist_t ec_configlist[] = {
{/*Man=*/0x00000002,/*ID=*/0x13ed3052,/*Name=*/"EL5101" ,/*dtype=*/7,/*Ibits=*/40,/*Obits=*/24,/*SM2a*/0x1000,/*SM2f*/0x00010024,/*SM3a*/0x1100,/*SM3f*/0x00010020,/*FM0ac*/1,/*FM1ac*/1},
{/*Man=*/0x000116c7,/*ID=*/0x003E0402,/*Name=*/"HCFA X3E Servo Driver",/*dtype=*/7,/*Ibits=*/104,/*Obits=*/88,/*SM2a*/0x1800,/*SM2f*/0x00010064,/*SM3a*/0x1c00,/*SM3f*/0x00010020,/*FM0ac*/1,/*FM1ac*/1},//,
{/*Man=*/0x00418108,/*ID=*/0x00009252,/*Name=*/"Diamond",/*dtype=*/7,/*Ibits=*/ 112,/*Obits=*/ 64,/*SM2a*/0x1100,/*SM2f*/0x00010064,/*SM3a*/0x1400,/*SM3f*/0x00010020,/*FM0ac*/1,/*FM1ac*/1}
};
例如MAN和ID都是不同从设备不同型号特定的号码。
ibit和obit需要根据结构体来计算
例如ibit = 16+32+16+32+8 = 104
void TIM2_IRQHandler(void)
{
if (TIM_GetITStatus(TIM2, TIM_IT_Update) != RESET)
{
systime++;
if(gEtherCatPara.dorun==1)
{
gEtherCatPara.pdoTimeFlag = 1;
ecat_loop();
}
// WCHNET_TimeIsr(WCHNETTIMERPERIOD);
TIM_ClearITPendingBit(TIM2, TIM_IT_Update);
}
}
在定时器中断里面主要是需要一个计数的变量
ecat_loop内主要是伺服驱动器的初始化,例如先配置模式,再使能之类的。
至此大部分移植都完成
现在一共有2个问题
一、许多ethercat设备不支持10M的PHY,因此我现在在用交换机进行转发,不用交换机无法接收和与从设备通讯,接上交换机是能通讯,使用STM32验证成功。
二、关于phy接收中断的问题,现在只需要将这个问题解决再看后续有没有其它bug。
更多回帖