IGH_Master主站配置驱动伺服电机和变频器总结

IGH_Master主站配置驱动伺服电机和变频器总结

Ethercat是倍福公司提出的一种工业现场总线协议,具备很好的实时性,IGH是一种开源的Ethercat主站实现协议,本文总结了一下使用IGH_Master驱动伺服电机和变频器的经验算法

一、Ethercat_Tools的使用

安装好IGH_Master后,在/ethercat/igh/out/bin文件夹下,使用./ethercat --help命令能够查看Ethercat的工具,这些工具能够查看链接至主站的从站的各类信息,极大方便主站驱动程序的编写,下面具体的介绍了一下各参数及命令的使用,其中[ ]中为必选参数,< >为可选参数。数组

设置别名地址

命令:ethercat alias [ OPTIONS ] < ALIAS >
参数:数据结构

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对位置;
* --force -f:匹配全部从站;

例子:
sudo ethercat alias --position 0 0x2000
解析:将在bus总线上对应的从站0的别名(默认为0)为0x2000
注意:必须有从站链接才能使用此命令。app

显示总线配置

命令:ethercat config [ OPTIONS ]
参数:dom

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对位置;
* --verbose -v:显示详细信息;

例子:
sudo ethercat config -v
解析:显示全部从站的详细配置信息。
注意:必须启动应用程序才能使用此命令查看。svg

以C语言的形式输出PDO信息

说明:生成的PDO信息能够直接被应用层的ecrt_slave_config_pdos()函数调用。
命令:ethercat cstruct [ OPTIONS ]
参数:函数

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对位置;

例子:
sudo ethercat cstruct -a 100
解析:输出别名为100的从站的PDO信息。
注意:必须有从站链接才能使用此命令。工具

显示过程数据

说明:输出二进制的过程数据。
命令:ethercat data [ OPTIONS ]
参数:oop

* --domain -d <index> <index>:域的索引值,假如不填写参数则显示全部过程数据。

例子:
sudo ethercat data
解析:显示全部PDO过程数据。
注意:必须启动应用程序才能使用此命令查看。测试

设置主站调试级别

说明:设置主站的调试级别,调试信息将输出在/var/log/syslog文件中。
命令:ethercat debug <LEVEL>

其中可有如下状况:

* 0 : 无任何调试信息输出
    * 1 : 输出部分调试信息
    * 2 : 输出全部的帧的内容(因为输出信息较多,请谨慎使用)

例子:
sudo ethercat debug 1
解析:打开部分调试信息输出

配置域

说明:显示域的信息。
命令:ethercat domains [ OPTIONS ]
参数:

* --domain -d <index> <index>:根据索引号,匹配域;
* --verbose -v:显示域的详细信息(FMMU和过程数据的信息);

例子:
sudo ethercat domains执行后显示

Domain0:LogBaseAddr 0x00000000, Size 12, WorkingCounter 0/3

以上各字段的含义:

* LogBaseAddr:逻辑寻址的逻辑基地址;
* Size:域交换数据的字节数;
* WorkingCounter:第一个数字是WKC的当前值,第二个数字是WKC的指望值;

解析:显示域的基本信息。

sudo ethercat domains -v执行后显示

Domain0:LogBaseAddr 0x00000000, Size 12, WorkingCounter 3/3
    SlaveConfig 0:0, SM2 (Output), LogAddr 0x00000000, Size 6 06 00 9d aa 00 00
    SlaveConfig 0:0, SM3 (Input), LogAddr 0x00000000, Size 6 31 0a 9d aa 00 00

以上各字段的含义:
* SlaveConfig:从机配置信息,主要包含别名和地址(绝对地址或相对地址);
* SM2:同步管理器2;
* LogAddr:FMMU映射的地址;
* Size:映射地址的大小;
* 数据位:十六进制显示的过程数据;

解析:显示域的详细信息(FMMU和过程数据的信息)。
注意:必须启动应用程序才能使用此命令查看。

写入SDO

说明:向从站写一条PDO条目。
命令:ethercat download [ OPTIONS ] <INDEX> <SUBINDEX> <VALUE>

参数:
⑴ 可选参数:

* INDEX:16位无符整型的SDO索引;
* SUBINDEX:8位无符整型的SDO子索引;
* VALUE:需写入的SDO的值

⑵ [ OPTIONS ]参数:

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对位置;
* --type -t <type>:SDO条目的数据类型;

type可以使用的类型有:

bool、int八、int1六、int3二、int6四、uint八、uint1六、uint3二、uint6四、float、double、string、octet_string、unicode_string

对于sign-and-magnitude coding有:
sm八、sm1六、sm3二、sm64

例子:

sudo ethercat download -t int16 -p 0 0x6060 00 08
解析:向从站0的索引号为0x6060(16位),子索引号为00(8位)的地址写入PDO条目值”0x08“;

读取SDO

说明:向从站读取一个SDO条目。
命令:ethercat upload [ OPTIONS ] <INDEX> <SUBINDEX>
参数:
⑴ 可选参数:

* INDEX:16位无符整型的SDO索引;
* SUBINDEX:8位无符整型的SDO子索引;

⑵ [ OPTIONS ]参数:

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对位置;
* --type -t <type>:SDO条目的数据类型;

type可以使用的类型有:

bool、int八、int1六、int3二、int6四、uint八、uint1六、uint3二、uint6四、float、double、string、octet_string、unicode_string

对于sign-and-magnitude coding有:
sm八、sm1六、sm3二、sm64

例子:

sudo ethercat upload -t int16 -p 0 0x6060 00
解析:读取从站0中索引号为0x6060(16位),子索引号为00(8位)的SDO条目。

注意:必须有从站链接才能使用此命令。

建立一个拓扑图形

说明:输出总线拓扑图。
命令:ethercat graph [ OPTIONS ]

例子:
sudo ethercat graph | dot -Tsvg > ~/Desktop/bus.svg
解析:将总线拓扑图输出到桌面。

主站和以太网设备

说明:显示主站和以太网设备信息。
命令:ethercat master [ OPTIONS ]
参数:

* --master -m <indices>:indices为主站的索引。默认显示全部的设备信息;

例子:

sudo ethercat master

解析:显示全部主机的设备信息(发送帧、接收帧、参考时钟、应用时间)。

注意:欲想显示应用时间需启动应用程序。

同步管理,PDOs,PDO条目

说明:显示出同步管理器的参数和PDO任务和映射信息。
命令:ethercat pdos [OPTIONS]
参数:

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对位置;
* --skin -s <skin>:”skin”可选择”default“和”etherlab“;

例子:

sudo ethercat pdos -p 0 -s default执行后显示:

SM2:PhysAddr 0x1400, DefaultSize 64, ControlRegister 0x34, Enable 1
    RxPDO 0x1600 "Receive PDO1 Mapping"
        PDO entry 0x6040:00, 16 bit, " "
        PDO entry 0x607a:00, 32 bit, " "

以上各字段的含义:
⑴ 同步管理器信息
* SM2:同步管理器2;
* PhysAddr:物理地址开始地址;
* DefaultSize:默认数据大小;
* ControlRegister:控制寄存器;
* Enable:使能字

⑵ 显示PDO方向,索引值,PDO名字
* RxPDO:表明从站发送数据的方向(从站接收数据);
* 0x1600:PDO的索引值;
* “Receive PDO1 Mapping”:PDO的名字;

⑶ 显示PDO条目的索引和子索引(都是以16进制的形式现实的),显示位宽和描述
* 0x6040:00 : 表示索引和子索引;
* 16bit:表示该条目的位宽;
* ” “:表示该位的描述;

寄存器访问

获取对应从站寄存器的内容

命令:ethercat reg_read [ OPTIONS ] <ADDRESS> [ SIZE ]
参数:
① 可选参数

* ADDRESS:16位无符号的寄存器地址;
* SIZE:要读取的对应寄存器字节数(16位无符号值);[ SIZE ] + ADDRESS不能超过64K,假如type参数隐含要读取的字节数,则能够忽略掉[ SIZE ]参数;

② [ OPTIONS ]参数

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对位置;
* --type -t <type>:匹配数据类型;

type可以使用的类型有:

bool、int八、int1六、int3二、int6四、uint八、uint1六、uint3二、uint6四、float、double、string、octet_string、unicode_string

对于sign-and-magnitude coding有:
sm八、sm1六、sm3二、sm64

例子:

sudo ethercat reg_read -p 6 -t sm32 0x092c

解析:获取从站6的0x092C寄存器所存储的值。

将内容写入指定从站寄存器

命令:ethercat reg_write [ OPTIONS ] <ADDRESS> <DATA>
参数:
① 可选参数

* ADDRESS:16位无符号的寄存器地址;
* DATA:要写入寄存器的数据;假如制定了”type”数据类型,那么”DATA”根据指定的数据类型对数据进行解析;假如未指定”type”数据类型,则”DATA”能够为指定的文件或将”DATA”设置为” - “,表示从标准输入中得到数据;

② [ OPTIONS ]参数

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对地址;
* --type -t <type>:匹配数据类型;
* --emergency -e:以紧急的方式请求写入文件;

例子:

sudo ethercat reg_write -p 5 -t sm32 0x092c 200

解析:向从站5的寄存器0x092c写入数据200。

SDO字典

说明:列出SDO字典(SDO信息和SDO条目信息)。
命令:ethercat sdos [ OPTIONS ]
参数:

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对位置;
* --quiet -q:只输出PDOs,不输出PDO条目信息;

例子:

sudo ethercat sdos执行后显示

SDO 0x1000,"Device type"
    0x1000:0, r-r-r-, uint32, 32 bit, "Device type"

SDOs:SDO 0x1000,”Device type”
* 0x1000:SDO索引值;
* “Device type”:SDO名字;

SDO条目:0x1000:0, r-r-r-, uint32, 32 bit, “Device type”
* 0x1000:0:索引值及子索引值;
* r-r-r-:表示访问权限;
* uint32:表示该条目的数据类型;
* 32bit:表示该条目的位宽;
* “Device type”:对该条目的描述;

显示从站的信息

说明:显示总线上的从站的信息。
命令:ethercat slaves [ OPTIONS ]
参数:

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对地址;
* --verbose -v:显示从站的详细信息;

例子:

sudo ethercat slaves -v

解析:显示全部从站的详细信息。

生成从站配置描述

说明:生成从站信息描述文件。
命令:ethercat xml [ OPTIONS ]
参数:

* --alias -a <alias>:匹配从站的别名;
* --position -p <pos>:匹配从站的绝对地址;

例子:

sudo ethercat xml -p 0

解析:生成从站0的从站信息描述文件并显示出来。

这一节的内容我参考了识荒者Ethercat解析(十二)之命令行工具的使用这篇文章,这里只列出了配置伺服和变频须要用到的工具,更多工具请移步该做者原文,感谢识荒者的分享

二、主站配置要点

应用程序是用户针对自身控制系统的控制要求编写的控制程序模块,运行于内核层。包括对主站和从站的配置以及周期性实时运行的任务。在实时任务程序中实现主从站间通信以及各类数控算法。主要包括两块:

  • 主站和从站的配置;
  • 周期任务的实现 cyclic operation;

先上图:
主站配置流程

主站、从站以及数据域的配置过程以下

  • 请求用于实时操做的 EtherCAT 主站,调用 ecrt_request_master(),获取主站的指针 ec_master_t *;

    master = ecrt_request_master(0)
  • 建立新的过程数据域,调用 ecrt_master_create_domain(),获取主站的一个数据域指针 ec_domain_t *;

    domain1 = ecrt_master_create_domain(master)
  • 获取从站配置,调用 ecrt_master_slave_config(),经过输入主站指针,从站化名,从站位置,从站厂商 ID 和从站产品号从而产生从站配置信息 sc_ana_in,并得到从站配置指针 ec_slave_config_t *;

    sc_ana_in = ecrt_master_slave_config('主站指针', '配置信息','从站信息')
  • 调用 ecrt_slave_config_pdos(),经过输入从站配置信息、从站同步管理信息,定义一个完整 PDO 配置;

    ecrt_slave_config_pdos('从站配置指针', EC_END, '从站同步管理信息')
  • *调用 ecrt_slave_config_create_sdo_request(),经过输入从站配置信息、SDO 索引号、子索引号和数据长度,得到 SDO 请求指针,从而创造一个完整 SDO 请求用于实时操做的交换 SDO 数据;

    sdo = ecrt_slave_config_create_sdo_request(sc_ana_in, 0x3102, 2, 2)
  • *调用 ecrt_sdo_request_timeout(),设置 SDO 请求最大超时时间

    ecrt_sdo_request_timeout(sdo, 500); // ms
  • 调用 ecrt_domain_reg_pdo_entry_list(),经过输入数据域指针和从站 PDO 入口注册信息,为数据域注册一系列 PDO 入口

    ecrt_domain_reg_pdo_entry_list(domain1, domain1_regs)
  • 调用 ecrt_master_activate(),完成本次配置阶段,准备进入实时周期任务循环:

    ecrt_master_activate(master)
  • 调用 ecrt_domain_data(),返回数据域的过程数据指针,为数据域指针分配地址,准备实时访问数据域

    domain1_pd = ecrt_domain_data(domain1)
  • 结束配置,建立一个实时的 timer,执行周期性任务函数 cyclic_task

周期性任务函数 cyclic_task

  • 主站从设备获取数据帧而且处理报文

    // receive process data
      ecrt_master_receive(master);
  • 判断数据域报文的状态

    ecrt_domain_process(domain1);
  • 判断数据域、主站、从站状态是否发生变化,有变化就提示信息

    // check process data state (optional)
      check_domain1_state();
    
      // check for master state (optional)
      check_master_state();
      // check for islave configuration state(s) (optional)
      check_slave_config_states();
  • 读写过程数据相关函数

    EC_READ_U16("数据域指针 + 地址偏移量")
      EC_WRITE_U16("数据域指针 + 地址偏移量")
  • 将数据域的全部报文插入到主站的报文序列

    // send process data
      ecrt_domain_queue(domain1);
  • 将主站全部报文发送到传输序列

    ecrt_master_send(master)

本小节主要参考了《IGH软件代码说明》,未找到出处,在此致谢!

三、伺服电机配置要点

本次咱们使用的是台达的伺服电机,型号为ASDA-A2-E,使用 CANopen 基于 DS402 协议控制伺服电机,具体过程以下:

1.使用ethercat slaves [ OPTIONS ]命令读取从站的列表,确保从站已经正常链接至主站

0  15:0  PREOP  +  Delta ASDA-A2-E EtherCAT(CoE) Drive Rev4
1   1:0  PREOP  +  EK1100 EtherCAT Coupler (2A E-Bus)
2   2:0  PREOP  +  EL1809 16K. Dig. Eingang 24V, 3ms

解析:
    第一列为从站相对于主站的绝对位置,能够用这个绝对位置来读取从站配置,在一些命令的选项后可加上' -p 1'这样的选项来读取1号从站的信息,固然也可使用  
    ethercat alias [ OPTIONS ] < ALIAS >  
    给从站设置别名,而后使用' -a <别名>'这样的方式来访问指定的从站;
    
    后面会有从站设备的型号,帮助肯定是否是咱们指望的主站链接成功;

2.使用sudo ethercat slaves -v -p 0能够输出 0 号从站目前的全部信息

=== Master 0, Slave 0 ===           //主站和从站编号
Alias: 15                           //别名
Device: Main
State: PREOP                        //状态
Flag: +
Identity:
Vendor Id:       0x000001dd
Product code:    0x10305070         //产品ID和编号
Revision number: 0x02040608
Serial number:   0x00000000
DL information:
FMMU bit operation: no
Distributed clocks: yes, 32 bit
DC system time transmission delay: 0 ns
Port  Type  Link  Loop    Signal  NextSlave  RxTime [ns]  Diff [ns]   NextDc [ns]
0  MII   up    open    yes             -    488154000           0           0
1  MII   up    open    yes             1    488158324        4324         641
2  N/A   down  closed  no              -            -           -           -
3  N/A   down  closed  no              -            -           -           -
Mailboxes:
Bootstrap RX: 0x0000/0, TX: 0x0000/0
Standard  RX: 0x1000/128, TX: 0x10c0/128
Supported protocols: CoE
General:
Group: ServoDrive
Image name: 
Order number: 
Device name: Delta ASDA-A2-E EtherCAT(CoE) Drive Rev4       //设备型号
CoE details:                    //设置信息
    Enable SDO: yes
    Enable SDO Info: yes
    Enable PDO Assign: yes
    Enable PDO Configuration: yes
    Enable Upload at startup: no
    Enable SDO complete access: no
Flags:                          //状态信息
    Enable SafeOp: no
    Enable notLRW: no
Current consumption: 0 mA


经过这些信息咱们就能够判断从站目前的状态,可操做性等;

Vendor Id:       0x000001dd
Product code:    0x10305070
这是从站的信息,能够用它肯定目标从站,因此能够先创建一个设备:

    #define asda_Pos0 0, 0
    #define asda 0x000001dd, 0x10305070

3.如今咱们须要在程序里创建从站配置指针:

static ec_slave_config_t *sc_asda;
static ec_slave_config_state_t sc_asda_state;

而且,使用ethercat xml -p 0命令,咱们能够查看设备的描述文件:

<?xml version="1.0" ?>
<EtherCATInfo>
<!-- Slave 0 -->                //从站0
<Vendor>
    <Id>477</Id>
</Vendor>
<Descriptions>
    <Devices>
    <Device>
        <Type ProductCode="#x10305070" RevisionNo="#x02040608"></Type>
        <Name><![CDATA[Delta ASDA-A2-E EtherCAT(CoE) Drive Rev4]]></Name>
        <Sm Enable="1" StartAddress="#x1000" ControlByte="#x36" DefaultSize="128" />
        <Sm Enable="1" StartAddress="#x10c0" ControlByte="#x32" DefaultSize="128" />
        <Sm Enable="1" StartAddress="#x1180" ControlByte="#x24" DefaultSize="6" />
        <Sm Enable="1" StartAddress="#x1480" ControlByte="#x0" DefaultSize="6" />
        /*
            该设备拥有四个同步管理通道:
                ·前两个为邮箱 MBox 传输方式,用于 COE 协议的通信,负责对 SDO 的传输;
                ·后两个为过程数据传输方式,负责对 PDO 的传输;
            其中:
            StartAddress 参数为物理起始地址,即该同步管理通道在双口 RAM 上的起始地址;
            ControlByte 参数为控制字,包含了该通道的传输方式、传输方向等信息;
            MinSize、MaxSize 和 DefaultSize 三个参数规定了该通道的大小。  
        */
        
        <RxPdo Sm="2" Fixed="1" Mandatory="1">
        <Index>#x1600</Index>           //RXPDO地址
        <Name>RxPDO</Name>              //接收(从主站)PDO
        <Entry>
            <Index>#x6040</Index>
            <SubIndex>0</SubIndex>  //索引号为0
            <BitLen>16</BitLen>   //字节大小,决定了你要用EC_WRITE_U16写入
            <Name></Name>
            <DataType>UINT16</DataType>
        </Entry>
        <Entry>
            <Index>#x607a</Index>
            <SubIndex>0</SubIndex>
            <BitLen>32</BitLen>
            <Name></Name>
            <DataType>UINT32</DataType>
        </Entry>
        <Entry>
            <Index>#x6060</Index>
            <SubIndex>0</SubIndex>
            <BitLen>8</BitLen>
            <Name></Name>
            <DataType>UINT8</DataType>
        </Entry>
        </RxPdo>
        <TxPdo Sm="3" Fixed="1" Mandatory="1">
        <Index>#x1a00</Index>           //TXPDO地址
        <Name>TxPDO</Name>              //发送(向主站)PDO
        <Entry>
            <Index>#x6041</Index>
            <SubIndex>0</SubIndex>
            <BitLen>16</BitLen>   //字节大小,决定了你要用EC_READ_U16读取
            <Name></Name>
            <DataType>UINT16</DataType>
        </Entry>
        <Entry>
            <Index>#x6064</Index>
            <SubIndex>0</SubIndex>
            <BitLen>32</BitLen>
            <Name></Name>
            <DataType>UINT32</DataType>
        </Entry>
        <Entry>
            <Index>#x6061</Index>
            <SubIndex>0</SubIndex>
            <BitLen>8</BitLen>
            <Name></Name>
            <DataType>UINT8</DataType>
        </Entry>
        <Entry>
            <Index>#x603f</Index>
            <SubIndex>0</SubIndex>
            <BitLen>16</BitLen>
            <Name></Name>
            <DataType>UINT16</DataType>
        </Entry>
        </TxPdo>
    </Device>
    </Devices>
</Descriptions>
</EtherCATInfo>

4.使用ethercat cstruct -p 0命令获得Ethercat主站自动生成的C语言PDO信息,这个信息能够直接粘贴到程序里;

/* Master 0, Slave 0
* Vendor ID:       0x000001dd
* Product code:    0x10305070
* Revision number: 0x02040608
*/

ec_pdo_entry_info_t slave_0_pdo_entries[] = {
    {0x6040, 0x00, 16},         //DS402操做字
    {0x607a, 0x00, 32},
    {0x6060, 0x00, 8},
    {0x6041, 0x00, 16},         //DS402状态字
    {0x6064, 0x00, 32},
    {0x6061, 0x00, 8},
    {0x603f, 0x00, 16},
};

ec_pdo_info_t slave_0_pdos[] = {
    {0x1600, 3, slave_0_pdo_entries + 0}, /* RxPDO */
    {0x1a00, 4, slave_0_pdo_entries + 3}, /* TxPDO */
};

ec_sync_info_t slave_0_syncs[] = {
    {0, EC_DIR_OUTPUT, 0, NULL, EC_WD_DISABLE},
    {1, EC_DIR_INPUT, 0, NULL, EC_WD_DISABLE},
    {2, EC_DIR_OUTPUT, 1, slave_0_pdos + 0, EC_WD_DISABLE},
    {3, EC_DIR_INPUT, 1, slave_0_pdos + 1, EC_WD_DISABLE},
    {0xff}
};

仔细观察生成的PDO信息我发现:
第一步:slave_0_pdo_entries[]创建了一个操做数组;
第二步:在slave_0_pdos[]中,根据前面获得的XML信息,将slave_0_pdo_entries[]中从0号位置(slave_0_pdo_entries + 0)开始的3个地址对应到伺服驱动器RxPDO地址->0x1600;
slave_0_pdo_entries[]中从3号位置(slave_0_pdo_entries + 3)开始的4个地址对应到伺服驱动器TxPDO地址->0x1a00;
第三步:将PDO信息 slave_0_pdos[] 对应到同步信息 slave_0_syncs[] 中:
slave_0_pdos + 0 是 {0x1600, 3, slave_0_pdo_entries + 0}, /* RxPDO */,方向为OUTPUT
slave_0_pdos + 1 是 {0x1a00, 4, slave_0_pdo_entries + 3}, /* TxPDO */,方向为INPUT

    应用程序将以上同步管理信息写入数据结构 ec_sync_info_t 中,做为
ecrt_slave_config_pdos()的参数,经过调用该函数最终完成完整的 PDO 配置。

    这是个人我的理解,有问题欢迎指出;

5.获取从站配置,调用 ecrt_master_slave_config(),经过输入主站指针, 从站化名 / 从站位置 / 从站厂商 ID 和从站产品号从而产生从站配置信息 sc_ana_in,并得到从站配置指针ec_slave_config_t *;

ecrt_master_slave_config(master, asda_Pos0, asda);

6.调用 ecrt_slave_config_pdos(),经过输入从站配置指针、从站同步管理信息,定义一个完整 PDO 配置;

ecrt_slave_config_pdos(sc_asda, EC_END, asda_syncs);

参数:
1->从站指针;
2->EC_END(查看库文件发现 -> #define EC_END ~0U,注释里面说:/**End of list marker(列表结束标记),是一个固定格式,应该还有其余参数,不过没有用到,目前就没有深究);
3->同步信息

7.调用 ecrt_domain_reg_pdo_entry_list(),经过输入数据域指针和从站 PDO 入口注册信息,为数据域注册一系列 PDO 入口

domainServoOutput = ecrt_master_create_domain(master);
domainServoInput = ecrt_master_create_domain(master);
//经过ecrt_master_create_domain("主站指针”)建立新的数据域

static unsigned int cntlwd;                     //控制字
static unsigned int ipData;                     //目标位置
static unsigned int status|;                     //状态字
static unsigned int actpos|;                     //当前回授位置
static unsigned int modes_of_operation|;         //6060
static unsigned int modes_of_operation_display|; //6061
static unsigned int errcode;                    //错误代码
//定义从站信息接收变量

ec_pdo_entry_reg_t domainServoOutput_regs[] = {
{asda_Pos0, asda, 0x6040, 0x00, &cntlwd, NULL},
{asda_Pos0, asda, 0x607a, 0x00, &ipData, NULL},
{asda_Pos0, asda, 0x6060, 0x00, &modes_of_operation[0], NULL},
{}};
//写操做状态字注册,以第一条为例,每一条都须要提供的参数有:
    asda_Pos0 主从站编号
    asda 从站信息
    0x6040 PDO 地址
    0x00 偏移地址
    &cntlwd 从站信息变量
    NULL 

    
ec_pdo_entry_reg_t domainServoInput_regs[] = {
{asda_Pos0, asda, 0x6064, 0x00, &actpos, NULL},
{asda_Pos0, asda, 0x6041, 0x00, &status, NULL},
{asda_Pos0, asda, 0x6061, 0x00, &modes_of_operation_display[0], NULL},
{asda_Pos0, asda, 0x603f, 0x00, &errcode, NULL},
{}};
                    //读操做状态字注册

ecrt_domain_reg_pdo_entry_list(domainServoOutput, domainServoOutput_regs)
ecrt_domain_reg_pdo_entry_list(domainServoInput, domainServoInput_regs)
//参数为:数据域指针,PDO入口注册信息列表

//这里将 OUTPUT PDO 和 INPUT PDO 分开成了两个域,分别注册成domainServoOutput和domainServoInput两个域,方便读写操做;

static uint8_t *domainOutput_pd = NULL;
static uint8_t *domainInput_pd = NULL;      //定义数据域指针

domainOutput_pd = ecrt_domain_data(domainServoOutput)
domainInput_pd = ecrt_domain_data(domainServoInput)
//调用 ecrt_domain_data(),获得数据域的过程数据指针,为数据域指针分配地址,准备实时访问数据域

//数据域是 EtherCAT 过程数据(PDO)向程序中的数据结构的映射,它提供了用户程序对总线上各个从站进行数据访问的入口。当从站 PDO 入口注册成功后,不一样从站都将得到一个属于本身的地址偏移量,用户可经过“数据域过程数据指针 + 地址偏移量”的方法对所需 PDO 进行读写操做。

//在读取写入的时候使用各自的数据域过程数据指针+偏移地址(例如cntlwd,errcode)对PDO进行操做

例:
    EC_READ_U16(domainInput_pd + status);

8.到这里,PDO的配置就完成了,接下来是根据伺服电机的说明手册对PDO映射表中对应的字节进行读写

对PDO中的地址进行读写操做使用的函数为:

EC_READ_U16("数据域指针 + 地址偏移量")
EC_WRITE_U16("数据域指针 + 地址偏移量")

U32,U16,U8为要读取的字节宽度,EC_READ_U8()则是读取8 bite宽度的数据
例:
    EC_READ_U16(domainInput_pd + Status)
    domainInput_pd为数据域过程数据指针,Status为地址偏移量

查阅手册得知驱动器必须按照标准 DS402 协议规定的流程引导伺服驱动器,伺服驱动器才可运行于指定的状态,具体流程以下:

台达伺服驱动流程

各个状态的说明:

初始化 驱动器初始化、内部自检已经完成。驱动器的参数不能设置,也不能执行驱动功能。
伺服无端障 伺服驱动器无端障或错误已排除。驱动器参数能够设置
伺服准备好 伺服驱动器已准备好。驱动器参数能够设置。
等待打开伺服使能 伺服驱动器等待打开伺服使能。驱动器参数能够设置。
伺服运行 驱动器正常运行,已使能某一伺服运行模式,电机已通电,指令不为0 时,电机旋转。驱动器参数属性为“运行更改”的能够设置,其余不可。
快速停机 快速停机功能被激活,驱动器正在执行快速停机功能。驱动器参数属性为“运行更改”的能够设置,其余不可。
故障停机 驱动器发生故障,正在执行故障停机过程当中。驱动器参数属性为“运行更改”的能够设置,其余不可。
故障 故障停机完成,全部驱动功能均被禁止,同时容许更改驱动器参数以便排除故障。

6040状态字

启动的流程为:向6040PDO中依次写入6-7-15(要根据6041状态字反馈信号依次写入,通过实践代表不建议直接按字节校验状态,简易按位校验状态,由于可能其余位出现正常变化会致使字节不一样,建议直接判断位的状态)

(EC_READ_U16(domainInput_pd + status[i]) & 0x031) == 49
序号 描述 6040控制字 6041位状态
2 伺服无端障 伺服准备好 0x0006 0010 0011 0001(b)
3 伺服准备好 等待打开伺服使能 0x0007 0010 0011 0011(b)
4 等待打开伺服使能 伺服运行 0x000F 0100 0011 0011(b)

示例程序以下:

if ((cur_status[i] & 0x0250) == 592)
{
    printf("*********************Servo Power on*********************\n");
    EC_WRITE_U16(domainOutput_pd + cntlwd[i], 0x06);
}
if ((cur_status[i] & 0x031) == 49)
            {
                if ((cur_status[i] & 0x033) == 51)
                {
                    if ((cur_status[i] & 0x0433) == 1075)
                    {
                        EC_WRITE_U16(domainOutput_pd + cntlwd[i], 0x1f);

                    }
                    else
                    {
                        printf("*********************Servo Waitting*********************\n");
                        EC_WRITE_U16(domainOutput_pd + cntlwd[i], 0x0f);
                    }

                }
                else
                {
                    printf("*********************Servo Enable*********************\n");
                    EC_WRITE_U16(domainOutput_pd + cntlwd[i], 0x07);
                }    
            }
        }

6040控制字寄存器各个位描述

6040操做字

6041状态字寄存器各个位描述
6041操做字

这一小节的内容引用了燕骏博客汇川IS620N伺服CIA402状态机切换步骤-6040控制字及6041状态字描述这篇文章,在此致谢!

9.到这里对于伺服电机的配置就基本完成了,可是在实际测试的时候咱们发现:

  • 当程序没有正常结束(手动Ctrl+c关闭),或者程序结束后没有使电机进入等待状态,后面再进行操做的时候电机就会没有反应(除非断电对伺服电机从新上电),这种状况是由于电机产生了fault,也就是6041h状态字的3号位会为1,这种状况下电机是不会工做的,这时咱们就须要清除故障,也就是对6040h的7号位置1,而后从新使能,这样电机就会进入正常的工做;

    cur_status = EC_READ_U16(domainInput_pd + status);
      if (EC_READ_U16(domainInput_pd + errcode) != 0 || (cur_status & 0x0008))
      {
          printf("Error Capture:servo %d error\n", i);
    
          for (int i = 0; i < drive_count; i++)
          {
              if (EC_READ_U16(domainInput_pd + errcode[i]) != 0 || (cur_status[i] & 0x0008))
              {
                  EC_WRITE_U16(domainOutput_pd + cntlwd[i], (EC_READ_U16(domainOutput_pd + cntlwd[i]) | 0x0080));
              }
              else
              {
                  EC_WRITE_U16(domainOutput_pd + cntlwd[i], (EC_READ_U16(domainOutput_pd + cntlwd[i]) & 0xff7f));
              }
          }
    
          if ((cur_status[i] & 0x031) == 49)
          {
              if ((cur_status[i] & 0x033) == 51)
              {
                  if ((cur_status[i] & 0x0433) == 1075)
                  {
                      EC_WRITE_U16(domainOutput_pd + cntlwd[i], 0x1f);
    
                  }
                  else
                  {
                      printf("33\n");
                      EC_WRITE_U16(domainOutput_pd + cntlwd[i], 0x0f);
                  }
              }
              else
              {
                  printf("31\n");
                  EC_WRITE_U16(domainOutput_pd + cntlwd[i], 0x07);
              }
          }
          printf("Error Solved!!!!\n");
      }

四、变频器驱动配置要点

此次咱们使用的是欧姆龙的3G3MX2型变频器搭配ECT型Ethercat选配件做为从站

变频器配置

1.硬件上的设置:在硬件上须要对A001和A002进行设置,以保证正常通讯,具体内容以下:

A001 = 04 频率给定选择,04 = 选配件
A002 = 04 运行指令选择,04 = 选配件
A003 = 50 基准频率 = 50Hz,电机额定频率
A004 = 60Hz 最大频率 = 60Hz
A044 = 00 控制方式,00 = 恒转矩
A061 = 60Hz 频率上限
A062 = 0Hz 频率下限
F002 = 2 加速时间,2s
F003 = 2 减速时间,2s
F004 = 00 运转方向,00 = 正向,01 = 反向
H003 = 0.55 电机容量 = 0.55kW

2.PDO配置:

Command(5000h) 控制启停及正反转
Frequency Reference(5010h) 运行频率给定

Status(5100h) 变频器运行状态
Output frequency monitor(5110h) 变频器频率输出监控

3.操做字及状态字位含义

5000h:电机启动、正反转、复位
5000h

5010h: 频率给定,直接给一个hex值

5100h:变频器状态反馈
5100h

5110h:变频器频率反馈->hex值

4.注意!!

  • 变频器操做顺序:5000h = 0x0 -> 5010h = '频率16进制' -> 5000h = 0x1

就是说,必须先给命令字置0,而后给频率,最后命令字置1启动

EC_WRITE_U16(domainOutput_pd + ECT_Command, 0);
EC_WRITE_U16(domainOutput_pd + ECT_Frequency, ECTFrequency);
EC_WRITE_U16(domainOutput_pd + ECT_Command, 0x1);
  • 变频器和伺服器同样,在程序没有正常运行完就关闭,会产生fault,5100h的第三位会为 1,这时候一样须要清除错误,相比来讲变频器清楚错误就简单一些,只须要将变频器的第 7 位置 1 就能够,而后再操做即可以正常;

    if (EC_READ_U16(domainInput_pd + ECT_Status) & 0x8)
      {
          EC_WRITE_U16(domainOutput_pd + ECT_Command, 0x80);
      }

以上就是IGH_Master应用程序驱动伺服和变频器的操做步骤和可能遇到的问题,在进行工业领域的设计操做时,设备的手册必定是重中之重,仍是要多看手册。

本文参考了不少网上资料,对主要参考资料都进行了标注,还有一些可能未进行标注,在此一并感谢!

相关文章
相关标签/搜索