일 | 월 | 화 | 수 | 목 | 금 | 토 |
---|---|---|---|---|---|---|
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 |
- 힐스테이트 광교산
- 배당
- raspberry pi
- SK텔레콤
- Home Assistant
- Apple
- 현대통신
- Python
- 미국주식
- Bestin
- MQTT
- 홈네트워크
- 티스토리챌린지
- 나스닥
- homebridge
- esp32
- 애플
- 매터
- Espressif
- 국내주식
- ConnectedHomeIP
- 오블완
- 월패드
- 해외주식
- matter
- RS-485
- 공모주
- 파이썬
- 코스피
- cluster
- Today
- Total
YOGYUI
IgH EtherCAT Master SDO 음수값 입력하기 본문
EtherLab의 리눅스용 이더캣(EtherCAT) 마스터 소스코드인 IgH EtherCAT Master for Linux에서 제공하는 CLI(Command Line Interface)를 통해 손쉽게 이더캣 슬레이브에 SDO(Service Data Object, 메일박스를 이용한 비주기 통신 프로토콜)를 통한 Object Dictionary 읽기/쓰기를 할 수 있다
https://gitlab.com/etherlab.org/ethercat
이 때, CLI로 값 입력 시 음수를 입력할 때는 약간의 트릭(?)이 필요하기에 그 방법을 간단하게 공유하도록 한다
대상 소스코드 버전: IgH EtherCAT Master stable-1.5
1. SDO Read/Write
SDO Write는 ethercat 실행 바이너리의 'download' 명령어를 사용하면 된다
옵션 인자는 ethercat station alias, slave position, sdo index, sdo subindex, value to write 등이 있으며, 자세한 내용은 CLI의 help message를 참고
$ sudo ethercat download -h
ethercat download [OPTIONS] <INDEX> <SUBINDEX> <VALUE>
[OPTIONS] <INDEX> <VALUE>
Write an SDO entry to a slave.
This command requires a single slave to be selected.
The data type of the SDO entry is taken from the SDO
dictionary by default. It can be overridden with the
--type option. If the slave does not support the SDO
information service or the SDO is not in the dictionary,
the --type option is mandatory.
The second call (without <SUBINDEX>) uses the complete
access method.
These are valid data types to use with
the --type option:
bool,
int8, int16, int32, int64,
uint8, uint16, uint32, uint64,
float, double,
string, octet_string, unicode_string.
For sign-and-magnitude coding, use the following types:
sm8, sm16, sm32, sm64
Arguments:
INDEX is the SDO index and must be an unsigned
16 bit number.
SUBINDEX is the SDO entry subindex and must be an
unsigned 8 bit number.
VALUE is the value to download and must correspond
to the SDO entry datatype (see above). Use
'-' to read from standard input.
Command-specific options:
--alias -a <alias>
--position -p <pos> Slave selection. See the help of
the 'slaves' command.
--type -t <type> SDO entry data type (see above).
Numerical values can be specified either with decimal (no
prefix), octal (prefix '0') or hexadecimal (prefix '0x') base.
예를 들어 alias 0, position 0인 슬레이브의 <index 0x607D, sub-index 0x02>인 SDO의 값을 12345678로 변경하려면 아래와 같은 커맨드 라인을 입력하면 된다 (두 라인 모두 동일한 기능)
※ 데이터 형식(크기 및 부호)은 ESI를 참고해야 한다
$ sudo ethercat download --alias 0 --position 0 --type int32 0x607D 0x02 12345678
$ sudo ethercat download -a 0 -p 0 -t int32 0x607D 0x02 12345678
※ 루트 권한이라면 sudo 키워드는 필요없다
만약 엉뚱한 SDO에 접근했을 경우 다음과 같은 오류메시지를 확인할 수 있다 (정상적으로 쓰여졌을 경우는 별도의 로그가 남지 않는다)
SDO Read 방법은 Write와 거의 동일하다 ('upload' 명령어 사용)
$ sudo ethercat upload --alias 0 --position 0 --type int32 0x607D 0x02
$ sudo ethercat upload -a 0 -p 0 -t int32 0x607D 0x02
앞서 쓴 값인 12345678 (0x00BC614E)가 제대로 레지스터에 저장된 것을 확인할 수 있다
2. 음수 입력 시 문제상황 및 해결방법
IgH EtherCAT Master CLI를 통한 SDO 쓰기 시 직면하는 번거로운 문제는 바로 '음수'값을 쓸 때 발생한다
만약 alias 0, position 0, index 0x607D, sub-index 0x01 SDO에 음수값인 -12345678을 쓰려고 하면 오류메시지가 발생한다
$ sudo ethercat download -a 0 -p 0 -t int32 0x607D 0x01 -12345678
문제 원인은 음수를 나타내기 위한 하이픈(hyphen, -)이 CLI의 인자(argument) 구별자로 쓰이기 때문에 음수를 구별짓지 못하기 때문이다
이를 해결하기 위해서는 데이터 타입을 signed에서 unsigned로 바꾸고 값을 16비트 헥사값(hexadecimal)으로 입력해주면 된다
$ sudo ethercat download -a 0 -p 0 -t uint32 0x607D 0x01 0xFF439EB2
실제 레지스터 값은 부호있는 데이터 타입 (int32)이지만, SDO write시에는 부호없는 데이터타입 (uint32)으로 입력했다는 점에 유의
write 후 다시 실제 데이터타입으로 읽어보면 값이 제대로 쓰여진 것을 알 수 있다
$ sudo ethercat upload -a 0 -p 0 -t int32 0x607D 0x01
3. Python 코드로 구현
EtherCAT 기반 서보모터를 IgH EtherCAT Master + ROS2 환경과 연동할 때 사용하는 ICube-Robotics의 ethercat_driver_ros2는 이더캣 슬레이브 SDO Read/Write를 위한 서비스(ethercat_sdo_srv_server)를 제공한다
https://icube-robotics.github.io/ethercat_driver_ros2/
서비스 인터페이스(SetSdo.srv)를 보면 데이터 타입과 데이터 값을 모두 'string' 형태로 입력하게 되어 있는 것을 알 수 있다
따라서 값을 쓸 때 양수/음수를 가리지 말고 모두 부호없는 값으로 처리한 뒤, 헥사값으로 전달하게 다음과 같이 코드를 짜면 부호에 대해서는 신경쓸 필요가 없게된다
※ 음수를 hex값으로 변환 시, 2의 보수 (2's complement) 원리를 이용한 bit 연산으로 간단하게 구현 가능
from rclpy.node import Node
from ethercat_msgs.srv import SetSdo
alias, slave_position = 0, 0
sdo_index = 0x607D
sdo_subindex = 0x01
data_size = 32
data_value = -12345678
node = Node("test_node")
client = node.create_client(SetSdo, "ethercat_manager/set_sdo")
# 양수/음수 관계없이 모두 hex값으로 변환
data_type_str = f'uint{data_size}'
data_str = hex(data_value) if data >= 0 else hex((data_value + (1 << data_size)) % (1 << data_size))
request = SetSdo.Request(
master_id=alias,
slave_position=position,
sdo_index=sdo_index,
sdo_subindex=sdo_subindex,
sdo_data_type=data_type_str,
sdo_value=data_str
)
future = self._client_ecat_set_sdo.call_async(request)
# future.add_done_callback(my_callback_func)
※ rclpy init, shutdown 등의 코드는 제외
'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 |
ROS2 - Multiple Robots 환경을 위한 Namespace 설정 방법 (10) | 2024.07.23 |
ROS2 EtherCAT Beckhoff Digital I/O Slave 구동 예제 (2) | 2023.11.10 |
ROS2 + IgH EtherCAT Master 구동 환경 구축 (0) | 2023.11.10 |