일 | 월 | 화 | 수 | 목 | 금 | 토 |
---|---|---|---|---|---|---|
1 | 2 | 3 | 4 | |||
5 | 6 | 7 | 8 | 9 | 10 | 11 |
12 | 13 | 14 | 15 | 16 | 17 | 18 |
19 | 20 | 21 | 22 | 23 | 24 | 25 |
26 | 27 | 28 | 29 | 30 | 31 |
- matter
- raspberry pi
- 엔비디아
- 배당
- ConnectedHomeIP
- 해외주식
- 매터
- Home Assistant
- homebridge
- 국내주식
- 미국주식
- MQTT
- 코스피
- RS-485
- 애플
- 파이썬
- 나스닥
- 공모주
- 퀄컴
- 티스토리챌린지
- Python
- esp32
- 오블완
- Espressif
- 홈네트워크
- Bestin
- 월패드
- 현대통신
- Apple
- 힐스테이트 광교산
- Today
- Total
YOGYUI
[ROS2] IgH EtherCAT Master SDO Read/Write Service Node 실행방법 본문
ROS2를 EtherCAT(이더캣) 통신 기반 디바이스(서보모터, 센서 등)와 연동하는 방법에 대해 알아본 바 있다
ROS2 + IgH EtherCAT Master 구동 환경 구축
이 글에서는 이더캣 디바이스의 SDO(Service Data Object) 값을 동적으로 읽고 쓰기 위한 ROS2 Service Call 방법에 대해 알아본다
※ICude-Robotics의 ethercat_driver_ros2를 빌드 후 source하면 함께 설치되는 ethercat_manager 패키지의 ethercat_sdo_srv_server 노드를 별다른 설정없이 바로 실행할 수 있다
[공식 가이드 문서]
https://icube-robotics.github.io/ethercat_driver_ros2/user_guide/sdo_async_com.html
1. 터미널 CLI를 통한 노드 실행
터미널에서 간단하게 다음 명령어로 ethercat_manager 패키지의 ethercat_sdo_srv_server 노드를 실행할 수 있다
$ ros2 run ethercat_manager ethercat_sdo_srv_server
다른 터미널 창에서 실행중인 service 리스트를 살펴보자
$ ros2 service list | grep ethercat_manager
get_sdo, set_sdo 서비스가 실행중인 것을 확인할 수 있다
Tip) 만약 노드에 네임스페이스(namespace)를 적용하고 싶다면 다음과 같이 입력하면 된다 (CLI remapping)
$ ros2 run ethercat_manager ethercat_sdo_src_server --ros-args -r __ns:={원하는 네임스페이스}
만약 네임스페이스를 /ns_test로 지정한다면 -r __ns:=/ns_test 로 인자를 붙여주면 되며, 서비스 목록을 리스트업해보면 다음과 같이 출력되는 것을 확인할 수 있다 (네임스페이스 문자열은 슬래시 / 로 시작해야 함을 주의)
2. ROS 인터페이스 상세
두 서비스가 사용하는 ROS 인터페이스를 자세히 알아보자
2.1. Get SDO
get_sdo 서비스의 인터페이스를 알아보자 (ros2 service type 명령어 사용)
$ ros2 service type /ethercat_manager/get_sdo
get_sdo 서비스는 ethercat_msgs/srv/GetSdo 인터페이스를 사용한다
인터페이스 상세는 ros2 interface show 명령어로 확인할 수 있다
$ ros2 interface show ethercat_msgs/srv/GetSdo
이더캣 관련 인자 (master id, slave position, sdo index, sdo subindex, sdo data type)을 서비스 호출 시 입력하면 호출 성공 시 결과값을 문자열과 실수형으로 반환한다 (정수형 데이터는 실수값을 변환해줘야 한다)
TIP) data type은 bool, uint8, int8, uint16, int16, uint32, int32, uint64, int64, bitN 중 하나를 선택
2.2. Set SDO
$ ros2 service type /ethercat_manager/set_sdo
set_sdo 서비스는 ethercat_msgs/srv/SetSdo 인터페이스를 사용한다
마찬가지로 인터페이스 상세를 알아보자
$ ros2 interface show ethercat_msgs/srv/SetSdo
GetSdo와 유사하게 이더캣 관련 인자와 함께, 입력하고자 하는 값(sdo_value)을 문자열 형태로 입력해줘야 한다 (0x1234와 같이 hexadecimal 형태로 입력)
주의) data type은 bool, uint8, int8, uint16, int16, uint32, int32, uint64, int64, bitN 중 하나를 선택해야 하며, 실수형인 float32 혹은 float64는 uint32나 uint64로 적절하게 변환해서 입력해야 한다
변환 방법에 대해서는 다음 글을 참고하면 된다
IgH EtherCAT Master SDO 음수값 입력하기
3. python launch script를 통한 노드 실행
ROS2 어플리케이션은 rclpy 파이썬 패키지를 사용해 런치 스크립트 (launch script)를 작성해 여러 개의 노드를 손쉽게 한번에 실행하는 것이 좋다
다음과 같이 launch description에 Node 실행 액션을 간단하게 추가해주면 ROS2 어플리케이션 실행 시 ethercat_sdo_srv_server 노드가 함께 실행된다
from launch import LaunchDescription
from launch_ros.actions import Node, DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
def generate_launch_description() -> LaunchDescription:
ld = LaunchDescription()
# add node's namespace argument
ld.add_action(DeclareLaunchArgument(
"namespace",
default_value="my_robot",
description="Configure namespace"))
# add other nodes/actions
# ...
ld.add_action(
Node(
package="ethercat_manager",
executable="ethercat_sdo_srv_server",
output="screen",
namespace=LaunchConfiguration("namespace")
)
)
return ld
4. SDO Read/Write DEMO
실제 사용하는 방법을 소개하기 위해 모 회사의 EtherCAT 스텝/서보 모터 드라이버의 SDO 중 하나의 값을 Read/Write해보자
※ EtherCAT Master ID는 0으로 설정되어 있으며, 드라이버는 master에 연결된 최초 slave이므로 slave_index는 0이다. 위 SDO는 sdo_index 0x607E, sdo_subindex 0x00, sdo_data_type 'uint8'로 데이터를 주고 받으면 되며, 유효한 데이터는 0x00 혹은 0x80이 전부인 간단한 파라미터
4.1. Read
$ ros2 service call /{namespace}/ethercat_manager/get_sdo ethercat_msgs/srv/GetSdo "{master_id: 0, slave_position: 0, sdo_index: 0x607E, sdo_subindex: 0x00, sdo_data_type: 'uint8'}"
드라이버의 해당 SDO의 현재 값이 0 (=0x00)인 것을 확인
4.2. Write
$ ros2 service call /{namespace}/ethercat_manager/set_sdo ethercat_msgs/srv/SetSdo "{master_id: 0, slave_position: 0, sdo_index: 0x607E, sdo_subindex: 0x00, sdo_data_type: 'uint8', sdo_value: '0x80'}"
서비스 응답(response)를 보면 success=True로 값이 정상적으로 쓰여진 것을 알 수 있다
>> 확실하게 알아보려면 4.1.에서 했던 것과 동일하게 다시 값을 읽어보면 된다
값이 128 (=0x80)로 제대로 쓰여진 것을 알 수 있다
끝~!
'Software > ROS' 카테고리의 다른 글
[ROS2] Gazebo Classic - Set/Get Entity Pose by Calling ROS2 Service (0) | 2024.12.03 |
---|---|
ROS2 Control - Admittance Controller Kinematics Chain Base Link 설정 (Bug) (1) | 2024.10.22 |
IgH EtherCAT Master SDO 음수값 입력하기 (0) | 2024.07.26 |
ROS2 - Multiple Robots 환경을 위한 Namespace 설정 방법 (10) | 2024.07.23 |
ROS2 EtherCAT Beckhoff Digital I/O Slave 구동 예제 (3) | 2023.11.10 |