跳到主要内容

CiA 402 -- 伺服驱动器辅助

CiA 402 (IEC 61800-7-204) 是基于 CoE 的伺服驱动器设备协议。SDK 提供两个层级的 CiA 402 支持:

  • CiA402 -- 基础接口,通过 slave.cia402 访问,提供使能/禁用/故障复位等基本操作
  • CiA402Advanced -- 高级接口,独立创建,支持 PDO 映射扫描与类型化位置/速度/转矩访问

CiA 402 运行在 CoE (SDO) 之上,仅当从站支持 CoE 时可用。

通过 slave.cia402 访问。从站不支持 CiA 402 时为 None

CiA402Advanced 为高级 API

本页示例中出现的 CiA402Advanced(master._dll, master.master_index, slave_index) 写法属于内部高级 API, 仅在需要 PDO 映射扫描或类型化位置/速度/转矩访问时使用。常规使能/禁用/故障复位/状态查询走 slave.cia402 (基础接口) 即可。 高级 API 的句柄参数后续可能调整, 请勿在生产代码中长期固化该构造形式。

PDO 初始化

scan_pdo_mapping()

def scan_pdo_mapping(self) -> None

初始化所有 PDO 偏移缓存。读取 0x1C12/0x1C13 PDO Assignment 配置,解析各对象在 IOmap 中的偏移位置。

备注

通常无需手动调用 -- 首次访问 state 等 PDO 属性时自动初始化。仅在需要提前确认 PDO 映射正确时手动调用。

示例:

from ethercat import CiA402Advanced

drv = CiA402Advanced(master._dll, master.master_index, 1)
drv.scan_pdo_mapping()

状态控制

enable(max_retries=10)

def enable(self, max_retries: int = 10) -> bool

使能驱动器: SDK 自动按 CiA 402-2 完成 SwitchOnDisabled → ReadyToSwitchOn → SwitchedOn → OperationEnabled 全套时序、Fault 复位、QuickStop 恢复 (含 0x605A 选项码判断)。

参数:

  • max_retries (int) — 最大重试次数 (默认 10)

返回值:

  • boolTrue = 已使能到 OperationEnabled, False = 失败/超时

disable()

def disable(self) -> None

禁用伺服 (-> SwitchOnDisabled)。完全断电。

disable_operation()

def disable_operation(self) -> None

禁用运行 (Transition 5: OperationEnabled -> SwitchedOn)。电机仍通电,可快速重新 enable()

quick_stop()

def quick_stop(self) -> None

快速停止 (-> QuickStopActive)。

fault_reset()

def fault_reset(self) -> None

清除故障。发送 Fault Reset 位 (Bit 7),产生上升沿清除驱动器故障。

示例:

cia = slave.cia402

# 一次性使能 (内部完成状态机)
if not cia.enable():
print(f"使能失败, 当前状态: {cia.state}")

# 禁用驱动器
cia.disable()

# 故障复位
cia.fault_reset()

# 快速停止
cia.quick_stop()

状态读取

state

@property
def state(self) -> StateCiA402

解析当前驱动器状态。

StateCiA402 枚举 (唯一定义来源: slave/cia402.py):

class StateCiA402(IntEnum):
NOT_READY_TO_SWITCH_ON = 0 # 初始化中
SWITCH_ON_DISABLED = 1 # 驱动禁用
READY_TO_SWITCH_ON = 2 # 准备就绪
SWITCHED_ON = 3 # 已开启
OPERATION_ENABLED = 4 # 运行使能
QUICK_STOP_ACTIVE = 5 # 快速停止
FAULT_REACTION_ACTIVE = 6 # 故障反应中
FAULT = 7 # 故障
UNKNOWN = 99 # 未知状态
别名导出

ethercat.data.types 也导出同名 StateCiA402 (历史兼容), 与 slave/cia402.py 中的为同一含义/值, 推荐统一从 ethercat 顶层或 slave.cia402 导入, 避免双源混用。

示例:

state = slave.cia402.state
print(f"驱动器状态: {state.description}")

status_word

@property
def status_word(self) -> int

读取状态字 (0x6041)。

control_word

@property
def control_word(self) -> int

@control_word.setter
def control_word(self, value: int) -> None

读取或写入控制字 (0x6040)。

相关属性:

  • target_reached (bool) — 目标已到达 (Bit 10)
  • has_fault (bool) — 存在故障 (Bit 3)
  • has_warning (bool) — 存在警告 (Bit 7)
  • is_remote (bool) — 远程模式已激活 (Bit 9)

示例:

cia = slave.cia402
sw = cia.status_word
print(f"StatusWord: 0x{sw:04X}")

if cia.target_reached:
print("目标已到达")
if cia.has_fault:
print("存在故障")

操作模式

set_mode() / get_mode()

def set_mode(self, mode: ModeCiA402) -> None
def get_mode(self) -> ModeCiA402

设置或读取操作模式。

ModeCiA402 枚举:

class ModeCiA402(IntEnum):
PP = 1 # 轮廓位置模式
VL = 2 # 速度模式
PV = 3 # 轮廓速度模式
PT = 4 # 轮廓转矩模式
HM = 6 # 回零模式
IP = 7 # 插补位置模式
CSP = 8 # 周期同步位置模式
CSV = 9 # 周期同步速度模式
CST = 10 # 周期同步转矩模式
CSTCA = 11 # 周期同步转矩加速度模式

示例:

from ethercat import ModeCiA402

cia = slave.cia402
cia.set_mode(ModeCiA402.CSP)
mode = cia.get_mode()
print(f"操作模式: {mode.description}")

运动参数

属性类型访问说明
actual_positionint只读实际位置 (0x6064)
velocity_actualint只读实际速度 (0x606C)
torque_actualint只读实际转矩,千分之额定 (0x6077)
target_positionint读写目标位置 (0x607A)
target_velocityint读写目标速度 (0x60FF)
target_torqueint读写目标转矩,千分之额定 (0x6071)

示例:

drv = CiA402Advanced(master._dll, master.master_index, 1)
drv.scan_pdo_mapping()

# 读取实际值
print(f"位置: {drv.actual_position}")
print(f"速度: {drv.velocity_actual}")

# 写入目标值
drv.target_position = 100000
drv.target_velocity = 5000

轮廓参数

属性类型访问说明
profile_velocityint读写轮廓速度 (0x6081)
profile_accelerationint读写轮廓加速度 (0x6083)
profile_decelerationint读写轮廓减速度 (0x6084)

示例:

drv.profile_velocity = 10000
drv.profile_acceleration = 50000
drv.profile_deceleration = 50000

极性与轮廓配置

属性类型访问说明
polarityint读写极性配置 (0x607E)。位 6 = 速度极性反转,位 7 = 位置极性反转
motion_profile_typeint读写运动轮廓类型 (0x6086)。0 = 梯形,1 = S 形
quick_stop_decelerationint读写快速停止减速度 (0x6085)
quick_stop_option_codeint读写快速停止选项码 (0x605A)

示例:

# 反转位置方向
drv.polarity = 0x80 # 位 7 = 位置极性反转

# 设置 S 形轮廓
drv.motion_profile_type = 1

# 设置快速停止减速度
drv.quick_stop_deceleration = 100000

触探功能 (Touch Probe)

configure_touch_probe()

def configure_touch_probe(self, function: int) -> None

配置触探功能 (0x60B8)。通过设置功能位启用/禁用触探及其触发条件。

参数:

  • function (int) — 触探功能字。位 0 = 启用探针 1,位 1 = 上升沿/下降沿选择,等

相关属性:

  • touch_probe_status (int, 只读) — 触探状态 (0x60B9)
  • touch_probe_positive_value (int, 只读) — 上升沿捕获位置 (0x60BA)
  • touch_probe_negative_value (int, 只读) — 下降沿捕获位置 (0x60BB)

示例:

# 启用触探 1,上升沿触发
drv.configure_touch_probe(0x0001)

# 读取触探结果
if (drv.touch_probe_status & 0x0002) != 0: # 上升沿已捕获
captured_pos = drv.touch_probe_positive_value
print(f"触探捕获位置: {captured_pos}")

回零速度与加速度

属性类型访问说明
homing_methodint读写回零方法 (0x6098)
home_offsetint读写回零偏移 (0x607C)
homing_speed_searchint读写回零搜索速度 (0x6099:01),快速搜索参考信号
homing_speed_zeroint读写回零零位速度 (0x6099:02),慢速精确定位零位
homing_accelerationint读写回零加速度 (0x609A)

start_homing()

def start_homing(self) -> None

HM 模式启动回零。需先设置 homing_method

相关属性:

  • homing_attained (bool) — 回零完成 (Bit 12)
  • homing_error (bool) — 回零错误 (Bit 13)

示例:

drv.set_mode(ModeCiA402.HM)
drv.homing_method = 35 # 当前位置回零

# 设置回零速度和加速度
drv.homing_speed_search = 5000 # 搜索速度
drv.homing_speed_zero = 500 # 零位速度
drv.homing_acceleration = 10000 # 回零加速度

# 使能后启动回零
drv.enable()
drv.start_homing()
# 后续检查 drv.homing_attained / drv.homing_error

扩展运动参数

属性类型访问说明
max_torqueint读写最大转矩 (0x6072),千分之额定转矩
motor_rated_torqueint读写电机额定转矩 (0x6076),单位 mNm
position_offsetint读写位置偏移 (0x60B0),CSP 模式下叠加到目标位置
velocity_offsetint读写速度偏移 (0x60B1),CSV 模式下叠加到目标速度
interpolation_time_period_valueint读写插补时间周期值 (0x60C2:01)
interpolation_time_period_indexint读写插补时间周期指数 (0x60C2:02),实际周期 = Value x 10^Index 秒

示例:

# 转矩配置
drv.max_torque = 1000 # 最大转矩 = 100% 额定
rated = drv.motor_rated_torque

# CSP 模式偏移叠加
drv.position_offset = 100 # 位置附加偏移
drv.velocity_offset = 50 # 速度附加偏移

# 插补时间周期 (1ms = 1 x 10^(-3) 秒)
drv.interpolation_time_period_value = 1
drv.interpolation_time_period_index = -3

力矩限制

属性类型访问说明
positive_torque_limitint读写正方向力矩限制 (0x60E0),千分之额定转矩
negative_torque_limitint读写负方向力矩限制 (0x60E1),千分之额定转矩

示例:

# 限制正负方向转矩为额定的 50%
drv.positive_torque_limit = 500
drv.negative_torque_limit = 500

数字 IO

属性类型访问说明
digital_inputsint只读数字输入 (0x60FD),32 位位图
digital_outputsint读写数字输出 (0x60FE),32 位位图

示例:

# 读取数字输入
inputs = drv.digital_inputs
limit_switch = (inputs & 0x01) != 0 # 位 0

# 设置数字输出
drv.digital_outputs = 0x03 # 输出位 0 和位 1

软件位置限位

属性类型访问说明
software_position_limit_minint读写软件位置限位下限 (0x607D:01)
software_position_limit_maxint读写软件位置限位上限 (0x607D:02)

示例:

# 设置运动范围限制
drv.software_position_limit_min = -1000000
drv.software_position_limit_max = 1000000

快速运动控制

new_setpoint()

def new_setpoint(self, position: int, relative: bool = False) -> None

PP 模式发送新定位命令。设置目标位置并触发 Controlword Bit 4 (New Setpoint)。

参数:

  • position (int) — 目标位置
  • relative (bool) — True = 相对定位,False = 绝对定位(默认)

示例:

drv.set_mode(ModeCiA402.PP)
drv.profile_velocity = 10000
drv.profile_acceleration = 50000

drv.enable()

# 发送定位命令
drv.new_setpoint(100000) # 绝对定位到 100000
# drv.new_setpoint(5000, True) # 或相对移动 5000

clear_new_setpoint()

def clear_new_setpoint(self) -> None

PP 模式清除 NewSetpoint 标志(Controlword Bit4=0)。在 target_reached 后调用,完成 SetPointAck 握手。

示例:

if drv.target_reached:
drv.clear_new_setpoint()

驱动器信息

supported_drive_modes

@property
def supported_drive_modes(self) -> int

支持的驱动模式位掩码 (0x6502, 只读)。Bit 0=PP, Bit 1=VL, Bit 2=PV, Bit 3=PT, Bit 5=HM, Bit 6=IP, Bit 7=CSP, Bit 8=CSV, Bit 9=CST。

is_mode_supported()

def is_mode_supported(self, mode: ModeCiA402) -> bool

检查驱动器是否支持指定操作模式。

示例:

if drv.is_mode_supported(ModeCiA402.CSP):
drv.set_mode(ModeCiA402.CSP)

supported_homing_methods

@property
def supported_homing_methods(self) -> List[int]

读取驱动器支持的回零方法列表 (0x60E3)。返回所有支持的回零方法编号列表。

示例:

methods = drv.supported_homing_methods
print(f"支持 {len(methods)} 种回零方法: {methods}")

TxPDO 数据有效性

tx_pdo_data_invalid

@property
def tx_pdo_data_invalid(self) -> bool

TxPDO 数据是否无效 (0x603E)。非零表示驱动器 TxPDO 数据不可信,例如编码器未就绪时位置值无意义。

示例:

if not drv.tx_pdo_data_invalid:
pos = drv.actual_position # 数据有效,可安全使用

同步功能

属性类型访问说明
synchronization_settingsint读写同步设置 (0x60D9:01),同步使能位掩码
drive_sync_statusint只读驱动同步状态 (0x60DA),指示驱动器是否已同步到主站时钟

示例:

# 读取驱动器同步状态
sync_status = drv.drive_sync_status
print(f"同步状态: 0x{sync_status:04X}")

# 配置同步设置
drv.synchronization_settings = 0x0001

高级接口 (CiA402Advanced)

CiA402Advanced 继承自 CiA402,额外支持 PDO 映射扫描与类型化访问。

from ethercat import CiA402Advanced

drv = CiA402Advanced(master._dll, master.master_index, 1)

PDO 映射扫描

# 扫描 PDO 映射 (0x1C12 / 0x1C13)
drv.scan_pdo_mapping()
print(f"PDO 映射完成: {drv.is_pdo_mapped}")
print(f"映射信号: {drv.pdo_offsets}")

扫描完成后,读写运动参数会优先通过 PDO(零延迟),无映射时回退到 SDO。

相关属性:

  • status_word_pdo (int, 只读) — 通过 PDO 读取状态字 (0x6041)
  • control_word_pdo (int, 读写) — 通过 PDO 读写控制字 (0x6040)

标准对象索引常量

常量说明
OD_CONTROLWORD0x6040控制字
OD_STATUSWORD0x6041状态字
OD_QUICK_STOP_OPTION_CODE0x605A快速停止选项码
OD_MODES_OF_OPERATION0x6060操作模式设置
OD_MODES_DISPLAY0x6061操作模式显示
OD_POSITION_ACTUAL0x6064实际位置
OD_TARGET_TORQUE0x6071目标转矩
OD_MAX_TORQUE0x6072最大转矩
OD_MOTOR_RATED_TORQUE0x6076电机额定转矩
OD_TORQUE_ACTUAL0x6077实际转矩
OD_TARGET_POSITION0x607A目标位置
OD_HOME_OFFSET0x607C回零偏移
OD_SOFTWARE_POSITION_LIMIT0x607D软件位置限制
OD_POLARITY0x607E极性
OD_MAX_PROFILE_VELOCITY0x6080最大轮廓速度
OD_PROFILE_VELOCITY0x6081轮廓速度
OD_PROFILE_ACCELERATION0x6083轮廓加速度
OD_PROFILE_DECELERATION0x6084轮廓减速度
OD_QUICK_STOP_DECELERATION0x6085快速停止减速度
OD_MOTION_PROFILE_TYPE0x6086运动轮廓类型
OD_HOMING_METHOD0x6098回零方法
OD_HOMING_SPEEDS0x6099回零速度
OD_HOMING_ACCELERATION0x609A回零加速度
OD_POSITION_OFFSET0x60B0位置偏移 (CSP)
OD_VELOCITY_OFFSET0x60B1速度偏移 (CSV)
OD_TORQUE_OFFSET0x60B2转矩偏移
OD_TOUCH_PROBE_FUNCTION0x60B8Touch Probe 功能控制
OD_TOUCH_PROBE_STATUS0x60B9Touch Probe 状态
OD_TOUCH_PROBE_POS_EDGE0x60BATouch Probe 正边沿位置
OD_TOUCH_PROBE_NEG_EDGE0x60BBTouch Probe 负边沿位置
OD_INTERPOLATION_TIME_PERIOD0x60C2插补时间周期
OD_VELOCITY_ACTUAL0x606C实际速度
OD_DIGITAL_INPUTS0x60FD数字输入
OD_DIGITAL_OUTPUTS0x60FE数字输出
OD_TARGET_VELOCITY0x60FF目标速度
OD_SUPPORTED_DRIVE_MODES0x6502支持的驱动模式位掩码

控制字命令常量

常量说明
CW_SHUTDOWN0x06关机命令
CW_SWITCH_ON0x07开启命令
CW_ENABLE_OPERATION0x0F使能运行
CW_DISABLE_VOLTAGE0x00禁用电压
CW_QUICK_STOP0x02快速停止
CW_FAULT_RESET0x80故障复位
CW_HALT0x0100暂停位 (Bit 8, 暂停运动但不禁用)

状态字位掩码常量

常量说明
SW_READY_TO_SWITCH_ON0x0001 (Bit 0)准备就绪
SW_SWITCHED_ON0x0002 (Bit 1)已开启
SW_OPERATION_ENABLED0x0004 (Bit 2)运行使能
SW_FAULT0x0008 (Bit 3)故障
SW_VOLTAGE_ENABLED0x0010 (Bit 4)电压已使能
SW_QUICK_STOP0x0020 (Bit 5)快速停止
SW_SWITCH_ON_DISABLED0x0040 (Bit 6)开启已禁用
SW_WARNING0x0080 (Bit 7)警告
SW_REMOTE0x0200 (Bit 9)远程模式
SW_TARGET_REACHED0x0400 (Bit 10)目标已到达
SW_INTERNAL_LIMIT0x0800 (Bit 11)内部限位激活
SW_OP_MODE_SPECIFIC_10x1000 (Bit 12)模式相关位 1
SW_OP_MODE_SPECIFIC_20x2000 (Bit 13)模式相关位 2

完整示例

CSP 模式 -- 周期同步位置控制

from ethercat import EtherCATMaster, EcState, CiA402Advanced

with EtherCATMaster() as master:
master.set_network(r"\\Device\\NPF_{GUID}")
master.set_state(EcState.OP)
master.start()

# 创建 CiA402 高级接口
drv = CiA402Advanced(master._dll, master.master_index, 1)

# 扫描 PDO 映射
drv.scan_pdo_mapping()

# 设置 CSP 模式
drv.set_mode(ModeCiA402.CSP)

# 一次性使能 (内部完成完整状态机)
if not drv.enable():
print(f"使能失败, 当前状态: {drv.state}")
return

# PDO 周期回调中控制
def on_pdo(mi):
drv.target_position = calculate_next_position()

master.on_pdo_cycle(on_pdo, sync=False)

import time
time.sleep(10)
drv.disable()
master.stop()

PP 模式 -- 轮廓位置控制

drv = CiA402Advanced(master._dll, master.master_index, 1)
drv.scan_pdo_mapping()

drv.set_mode(ModeCiA402.PP)
drv.profile_velocity = 10000
drv.profile_acceleration = 50000
drv.profile_deceleration = 50000

drv.enable()

# 发送定位命令
drv.new_setpoint(100000)

# 等待到达
import time
while not drv.target_reached:
time.sleep(0.01)
drv.clear_new_setpoint()
print("定位完成")

通过 SDO 直接控制

slave = master[1]

# 设置操作模式 (CSP)
slave.coe.sdo_write_value(0x6060, 0, 8, dtype='i8')

# 写入控制字: Shutdown
slave.coe.sdo_write_value(0x6040, 0, 0x06, dtype='u16')

# 写入控制字: Switch On
slave.coe.sdo_write_value(0x6040, 0, 0x07, dtype='u16')

# 写入控制字: Enable Operation
slave.coe.sdo_write_value(0x6040, 0, 0x0F, dtype='u16')

# 读取状态字
sw = slave.coe.sdo_read_value(0x6041, 0, dtype='u16')
print(f"StatusWord: 0x{sw:04X}")

# 写入目标位置
slave.coe.sdo_write_value(0x607A, 0, 100000, dtype='i32')