Python IndyDCP 클라이언트
Python IndyDCP 클라이언트 는 IndyDCP Protocol을 기반으로 Indy를 명령을 인가하고, 데이터를 송수신 할 수 있는 Python 모듈입니다. Python IndyDCP 클라이언트의 모든 함수들은 하나의 모듈파일에 구현이 되어 있으며, 본 장에서는 이에대한 기본 사용법 및 명령어 리스트들을 제공합니다.
설치
Python IndyDCP 클라이언트는 Python이 설치된 컴퓨터에서 실행 가능하며, 모듈 파일과 예제 노트북 파일은 아래 링크를 클릭하여 다운받을 수 있습니다.
indydcp_client.py 는 Python 모듈 소스파일이며 example_indydcp.ipynb 는 사용 예제를 담은 주피터 노트북 파일입니다.
기본 사용법
Python IndyDCP 클라이언트는 아래와 같이 indydcp_client.py 모듈을 임포트 하면 바로 사용할 수 있습니다.
1 |
|
모듈에는 소켓 연결과 명령어 리스트 등을 포함하는 IndyDCPClient 클래스가 구현되어 있으며 이를 사용하기 위해 우선 해당 클래스의 객체를 생성해야 합니다. 이 때에 바인딩 IP (인디에 연결하고자 하는 PC의 IP), 서버 IP (인디 컨트롤박스의 IP), 로봇 이름 (인디7의 경우 "NRMK-Indy7" 문자열)을 생성자의 인자로 넣어주어야 합니다.
1 2 3 4 |
|
connect() 함수를 통해 로봇에 연결할 수 있으며 is_connected() 함수를 통해 연결상태를 확인할 수 있습니다.
1 2 |
|
그 외에 전용통신 연결과 관련하여 아래 함수들이 제공됩니다.
1 2 3 |
|
IndyDCP 클라이언트 명령어 함수 리스트
모듈 내에 있는 모든 명령어 함수들은 IndyDCP 프로토콜의 명령어 리스트를 참고하여 작성된 것이므로 각 함수에 대한 설명은 IndyDCP 프로토콜의 명령어 리스트를 참고하시기 바랍니다.
Python 모듈에 포함된 명령어 함수 리스트는 아래 표에 모두 요약되어 있습니다. 표에서는 각 함수의 입출력 타입과 개수에 대해 표기되어 있으며, 모든 함수의 입력은 numpy 배열 또는 list이며, 출력은 모두 numpy 배열로 통일되어 있습니다. 그 외 비고란에서 참고사항을 확인할 수 있습니다.
C++을 포함하여 MATLAB and Labview 인터페이스 또한 모두 IndyDCP 프로토콜을 이용한 클라이언트 예제이기 때문에 함수이름과 입출력은 언어에서 추구하는 컨벤션에 따라 약간의 차이가 있을지라도 기능 및 사용법은 완전히 동일합니다. 따라서 다른 인터페이스 예제를 사용하더라도 아래 표를 참고하여 사용할 수 있습니다.
Function | 입력 | 출력 | 비고 |
---|---|---|---|
emergency_stop() | - | - | - |
reset_robot() | - | - | - |
set_servo_on_off(var_arr) | bool[DOF1] | - | - |
set_brake_on_off(var_arr) | bool[DOF] | - | Warning! 브레이크 해제 시 중력에 의해 로봇이 바닥으로 떨어짐 |
stop_motion() | - | - | - |
execute_move_command(str) | string | - | Warning! 기본프로그램에 등록된 move 이름 |
go_home() | - | - | Warning! |
go_zero() | - | - | Warning! |
joint_move_to(q) | double[DOF] | - | Warning! q[0]-q[DOF-1]: Degree |
joint_move_by(q) | double[DOF] | - | Warning! q[0]-q[DOF-1]: Degree |
task_move_to(p) | double[6] | - | Warning! p[0]-p[2] (x, y, z): Meter p[3]-p[5] (u, v, w): Degree |
task_move_by(p) | double[6] | - | Warning! p[0]-p[2] (x, y, z): Meter p[3]-p[5] (u, v, w): Degree |
start_current_program() | - | - | Warning! |
pause_current_program() | - | - | - |
resume_current_program() | - | - | - |
stop_current_program() | - | - | - |
start_default_program() | - | - | - |
set_default_program(idx) | int | - | idx: 1-9 등록된 기본프로그램 인덱스 |
get_default_program_idx() | - | int | - |
is_robot_running() | - | bool | - |
is_robot_ready() | - | bool | - |
is_emergency_stop() | - | bool | - |
is_collided() | - | bool | - |
is_error_state() | - | bool | - |
is_move_finished() | - | bool | - |
is_in_resetting() | - | bool | - |
is_direct_teaching_mode() | - | bool | - |
is_teaching_mode() | - | bool | - |
is_program_running() | - | bool | - |
is_program_paused() | - | bool | - |
is_conty_connected() | - | bool | - |
change_to_direct_teaching() | - | - | - |
finish_direct_teaching() | - | - | - |
add_joint_waypoint(q) | double[DOF] | - | - |
remove_last_joint_waypoint() | - | - | - |
clear_joint_waypoints() | - | - | - |
execute_joint_waypoints() | - | - | - |
add_task_waypoint(p) | double[6] | - | - |
remove_last_task_waypoint() | - | - | - |
clear_task_waypoints() | - | - | - |
execute_task_waypoints() | - | - | - |
set_default_tcp(tcp) | double[6] | - | - |
reset_default_tcp() | - | - | - |
set_tcp_compensation(tcp) | double[6] | - | - |
reset_tcp_compensation() | - | - | - |
set_ref_frame(ref) | double[6] | - | - |
reset_ref_frame() | - | - | - |
set_collision_level(level) | int | - | 레벨 설정 (1-5) |
set_joint_boundary_level(level) | int | - | 레벨 설정 (1-9) |
set_task_boundary_level(level) | int | - | 레벨 설정 (1-9) |
set_joint_waypoint_time(time) | double | - | - |
set_task_waypoint_time(time) | double | - | - |
set_task_base_mode(mode) | int | - | 0: reference body, 1: tool-tip |
set_joint_blend_radius(rad) | int | - | Degree |
set_task_blend_radius(rad) | double | - | mm |
get_default_tcp() | - | double[6] | - |
get_tcp_compensation() | - | double[6] | - |
get_ref_frame() | - | double[6] | - |
get_collision_level() | - | int | - |
get_joint_boundary_level() | - | int | - |
get_task_boundary_level() | - | int | - |
get_joint_waypoint_time() | - | double | - |
get_task_waypoint_time() | - | double | - |
get_task_base_mode() | - | int | - |
get_joint_blend_radius() | - | double | - |
get_task_blend_radius() | - | double | - |
get_robot_running_time() | - | double | - |
get_cmode() | - | int | - |
get_joint_servo_state() | - | char[12] | - |
get_joint_pos() | - | double[DOF] | - |
get_joint_vel() | - | double[DOF] | - |
get_task_pos() | - | double[6] | - |
get_task_vel() | - | double[6] | - |
get_torque() | - | double[DOF] | - |
get_last_emergency_info() | - | int, int[3], double[3] | - |
get_smart_di(idx) | int | char | - |
get_smart_dis() | - | char[32] | - |
set_smart_do(idx, val) | int, char | - | - |
set_smart_dos() | char[32] | - | - |
get_smart_ai() | int | int | - |
set_smart_ao(idx, val) | int, int | - | - |
get_smart_do(idx) | int | char | - |
get_smart_dos() | - | char[32] | - |
get_smart_ao(idx) | int | int | - |
Table 1. Python IndyDCP 클라이언트 명령어 함수 리스트
비고란에 Warning! 이 표기되어 있는 명령어는 로봇이 실제 움직임을 수행하는 명령어 함수들 입니다. 티칭펜던트 (Conty)를 이용하여 작업교시를 할 때에는 로봇을 목표 위치로 JOG 또는 직접교시로 이동 시킨 후에 해당 위치를 경유점으로 등록할 수 있지만, IndyDCP 클라이언트 이용시 사용자가 직접 타겟 위치 (관절각도, 작업공간 위치)를 입력해야 합니다. 이 때문에 좌표를 잘 못 입력하거나, 단위를 착각하거나, 명령어를 잘못 입력하는 등의 사용자 실수로 인해 로봇이 의도하지 않은 위치로 빠른속도로 이동할 수 있으며 이로인해 로봇이 장애물과 충돌하여 파손될 수도 있습니다. 이러한 실수를 줄이기 위해 만들고자 하는 로봇작업에 대해 시뮬레이션 모드로 먼저 실행해본 후 이를 실제 로봇에 적용해보는 것을 권장합니다. 시뮬레이션 모드의 사용법은 IndyFramework를 참고하시기 바랍니다.
Extended IndyDCP 명령어 함수 리스트
확장된 IndyDCP (Extended IndyDCP) 명령어 리스트는 아래 표와 같습니다.
Function | 입력 | 출력 | 비고 |
---|---|---|---|
move_ext_traj_binary() | Data length | - | - |
move_ext_traj_text() | Data length | - | - |
move_ext_traj_binary_file() | File path | - | - |
move_ext_traj_text_file() | File path | - | 포멧이 정해진 txt파일 |
joint_move_to_waypoint_set() | DOF*8* len | - | - |
task_move_to_waypoint_set() | 6*8*len | - | - |
Table 2. Python Extended IndyDCP 클라이언트 명령어 함수 리스트
-
로봇 관절 개수 (Indy7=6, IndyRP2 여유자유도 옵션=7)
↩