YOGYUI

EtherCAT Driver ROS2 Stack SDO Async exchange service - ioctl magic difference 문제 해결 방법 본문

Software/ROS

EtherCAT Driver ROS2 Stack SDO Async exchange service - ioctl magic difference 문제 해결 방법

요겨 2023. 9. 18. 13:00
반응형

 

EtherCAT Driver ROS2 Stack SDO Async exchange service - ioctl magic difference issue

더보기

ROS2 중급 개발자 이상을 대상으로 작성된 글 (workspace, colcon 등 기초적인 내용은 다루지 않음) 

1. 문제 상황

회사에서 자체적으로 만든 EtherCAT 모터 드라이버 기반 6축 다관절 로봇 제어 솔루션 구현을 위해 ROS2(Humble) / ros2_control / IgH EtherCAT Master(EtherLAB)를 설치한 뒤 ICube-Robotics의 EtherCAT Driver ROS2 Stack 패키지를 사용하고 있다

document page: https://icube-robotics.github.io/ethercat_driver_ros2 

github repository: https://github.com/ICube-Robotics/ethercat_driver_ros2

 

PDO 통신은 다양한 통신 주기 (1ms, 2ms, 4ms, 10ms)에서 문제없이 동작해 로봇 제어가 잘 되는데, SDO 통신을 위해 ethercat_manager 패키지의 ethercat_sdo_src_server 서비스 호출 시 다음과 같이 ioctl() 매직넘버 미스매치 문제가 발생했다

[ERROR] [...] [ethercat_manager]: ioctl() version magic is differing: /dev/EtherCAT0: 32, ethercat tool: 31

Ubuntu 22.04.03 LTS에 Real-time을 위한 PREEMPT_RT 커널 5.15.113-rt64 버전을 패치해서 사용중인데, 이를 기반으로 빌드한 IgH EtherCAT Master (1.5 stable) 바이너리의 ioctl 매직버전은 32라 미스매치가 발생한 것 같다

커널 버전때문인지, IgH 소스코드 문제인지는 좀 더 파봐야 할 듯?.. 문제 해결책이 워낙에 간단하다보니 문제 발생 근본 원인에 대해서는 깊게 생각하고 싶지가 않다 ㅎㅎ

※ ROS 버전 문제인 것으로 파악 완료! 나도 모르게 Iron 버전을 활성화한게 문제였다 -_- Humble 버전에서는 magic 넘버가 31이어야 한다

 

2. 문제 해결

EtherCAT Driver ROS2 의 ethercat_manager 소스코드를 좀 까보니 금방 해결책을 찾을 수 있었다

ethercat_driver_ros2/ethercat_manager/include/ethercat_manager/ec_master_async_io.hpp 파일을 열어보면 매크로 상수 EC_IOCTL_VERSION_MAGIC가 31로 하드코딩된 것을 알 수 있다

#define EC_IOCTL_TYPE 0xa4
#define EC_IO(nr)  _IO(EC_IOCTL_TYPE, nr)
#define EC_IOR(nr, type)  _IOR(EC_IOCTL_TYPE, nr, type)
#define EC_IOW(nr, type)  _IOW(EC_IOCTL_TYPE, nr, type)
#define EC_IOWR(nr, type)  _IOWR(EC_IOCTL_TYPE, nr, type)
#define EC_IOCTL_VERSION_MAGIC 31
#define EC_IOCTL_MODULE  EC_IOR(0x00, ec_ioctl_module_t)
#define EC_IOCTL_SLAVE_SDO_UPLOAD  EC_IOWR(0x0e, ec_ioctl_slave_sdo_upload_t)
#define EC_IOCTL_SLAVE_SDO_DOWNLOAD  EC_IOWR(0x0f, ec_ioctl_slave_sdo_download_t)

같은 경로 내에 있는 ec_master_async.hpp 파일의 EcMasterAsync 클래스 내부 코드를 보면 오류가 발생하는 구문을 확인할 수 있다

class EcMasterAsync
{
    /* ... */
    void open(Permissions perm)
    {
        /* ... */
        getModule(&module_data);
        if (module_data.ioctl_version_magic != EC_IOCTL_VERSION_MAGIC) {
            std::stringstream err;
            err << "ioctl() version magic is differing: "
            << deviceName.str() << ": " << module_data.ioctl_version_magic
            << ", ethercat tool: " << EC_IOCTL_VERSION_MAGIC;
            throw MasterException(err.str());
        }
        mcount_ = module_data.master_count;
    }
    /* ... */
};

 

손쉽게 해결하기 위해 EC_IOCTL_VERSION_MAGIC 값을 바꾼 뒤 colcon으로 다시 빌드해주자

// #define EC_IOCTL_VERSION_MAGIC 31
#define EC_IOCTL_VERSION_MAGIC 32

 

$ colcon build --packages-select ethercat_manager

빌드 후 asyclic SDO exchange 서비스를 실행해준다 (여기서는 간단히 read 기능만 데모)

서비스/인터페이스 명세는 아래와 같다 

$ ros2 run ethercat_manager ethercat_sdo_srv_server

서비스 호출 시 SDO Read하려면 ethercat_manager/get_sdo를, Write하려면 ethercat_manager/set_sdo를 호출하면 되며, 인터페이스는 ROS2 사용하듯이 dictionary 형태로 입력해주면 된다

3. DEMO

특정 slave의 원하는 object 값을 읽어보자

로봇 손목에 장착한 ATI사의 force-torque 센서 Axia80의 vendor ID와 product code를 SDO 통신으로 읽어와보자 (ethercat_sdo_srv_server 서비스 서버가 구동중이어야 한다)

$ ros2 service call /ethercat_manager/get_sdo ethercat_msgs/srv/GetSdo\
    "{\
        master_id: 0,\
        slave_position: 6,\
        sdo_index: 0x2019,\
        sdo_subindex: 0x01,\
        sdo_data_type: uint32\
    }"

requester: making request: ethercat_msgs.srv.GetSdo_Request(master_id=0, slave_position=6, sub_index=8217, sdo_subindex=1, sdo_data_type='uitn32')

response:
ethercat_msgs.srv.GetSdo_Response(success=True, sdo_return_message='SDO upload done succesfully', sdo_return_value_string='0x00000732', sdo_return_value=1842.0)
$ ros2 service call /ethercat_manager/get_sdo ethercat_msgs/srv/GetSdo\
    "{\
        master_id: 0,\
        slave_position: 6,\
        sdo_index: 0x2019,\
        sdo_subindex: 0x02,\
        sdo_data_type: uint32\
    }"

requester: making request: ethercat_msgs.srv.GetSdo_Request(master_id=0, slave_position=6, sub_index=8217, sdo_subindex=2, sdo_data_type='uitn32')

response:
ethercat_msgs.srv.GetSdo_Response(success=True, sdo_return_message='SDO upload done succesfully', sdo_return_value_string='0x26483053', sdo_return_value=642265171.0)

response를 보면 vendor ID는 0x00000732, product code는 0x26483053으로 제대로 읽히는 것을 알 수 있다

 

끝~!

 

반응형