采用stm32f4作为主站,移植soem代码,现已经可以和elmo驱动器正常通讯。
以上未粘贴
if (ec_init("test"))
{
printf("ec_init succeeded.\r\n");
if ( ec_config_init(FALSE) > 0 ) //初始化soem
{
printf("%d slaves found and configured.\r\n",ec_slavecount);
int state;
state=ec_statecheck(0, EC_STATE_PRE_OP, EC_TIMEOUTSTATE); //切换状态到 pre_OP
// set PDO mapping
READ(1, 0x60FF, 0, buf32, "*target_V*");
WRITE(1, 0x60FF, 0, buf32, 0, "*V*");
READ(1, 0x60FF, 0, buf32, "*target_V*"); //着三条我是用来确定目标速度为0.
WRITE(1, 0x6060, 0, buf8, 9, "cyclic velocity");
READ(1, 0x6061, 0, buf8, "OpMode display");
//设置为速度模式
READ(1, 0x1c12, 0, buf16, "SM2:outputs");
READ(1, 0x1c13, 0, buf16, "SM3:inputs");
//修改1c12 和1c13映射
WRITE(1,0x1c12,0,buf16,0,"1c12д0");
WRITE(1,0x1c13,0,buf16,0,"1c13д0");
WRITE(1,0x1c12,1,buf16,0x1601,"1c12 Ó³Éäµ½ 1601");
WRITE(1,0x1c13,1,buf16,0x1A01,"1c12 Ó³Éäµ½ 1601");
WRITE(1,0x1c12,0,buf16,1,"1c12д1");
WRITE(1,0x1c13,0,buf16,1,"1c13д1");
READ(1, 0x1c12, 0, buf16, "SM2:outputs");
READ(1, 0x1c13, 0, buf16, "SM3:inputs");
READ(1, 0x1c12, 1, buf16, "SM2:outputs ¶ÔÓ¦");
READ(1, 0x1c13, 1, buf16, "SM3:inputs ¶ÔÓ¦");
WRITE(1, 0x6060, 0, buf8, 9, "cyclic velocity");
READ(1, 0x6061, 0, buf8, "OpMode display");
WRITE(1,0x60c2,1, buf16, 2,"cycle time");
READ(1, 0x6041, 0, buf16, "*status word*");
if(buf16 == 0x218) //如果是错误则先写128清除错误
{
WRITE(1, 0x6040, 0, buf16, 128, "*control word*"); delay_ms(100);
READ(1, 0x6041, 0, buf16, "*status word*");
}
WRITE(1, 0x6040, 0, buf16, 0, "*control word*");
delay_ms(100);
READ(1, 0x6041, 0, buf16, "*status word*");
WRITE(1, 0x6040, 0, buf16, 6, "*control word*");
delay_ms(100);
READ(1, 0x6041, 0, buf16, "*status word*");
WRITE(1, 0x6040, 0, buf16, 7, "*control word*");
delay_ms(100);
READ(1, 0x6041, 0, buf16, "*status word*");
delay_ms(5000);
READ(1, 0x6041, 0, buf16, "*status word*"); //以上都对
WRITE(1, 0x6040, 0, buf16, 15, "*control word*");
delay_ms(100);
READ(1, 0x6041, 0, buf16, "*status word*"); //这里收到的数值就不对了。
while(1);//为了方便观察后续没有写,在这里死循环
能够实现正确的状态字回复