Python IndyDCP client
Python IndyDCP client is a Python module for users to interface with Indy Framework and control Indy based on IndyDCP Protocol. All functions of Python IndyDCP client is implemented in a single module file, and this section provides basic tutorial and all command list of Python IndyDCP client.
Installation
Python IndyDCP client can be run by a computer that Python is installed. The module file and example notebook file can be downloaded by clicking the link below
indydcp_client.py is the source file of Python IndyDCP module, and example_indydcp.ipynb is a jupyter notebook file that contains usage examples.
Basic Tutorial
Python IndyDCP client can be easily used by importing indydcp_client.py as below
1 | |
The IndyDCPClient class, which contains socket connection and robot command functions, is implemented in the module file. Here, the bind IP (IP address of PC you want to connect to Indy), server IP (IP address of Indy's control box), and robot name (in case of Indy7, string "NRMK-Indy7") should be arguments of the class constructor.
1 2 3 4 | |
Using connect() function, users can connect to the robot, and can check the connection status using is_connected() function.
1 2 | |
Also, some functions that related to the socket connection are provided as below
1 2 3 | |
List of IndyDCP Command Functions
All command functions in the module is implemented by referring to IndyDCP protocol command list, so please refer to the IndyDCP protocol command list for detailed description of each command fuction.
The list of command function in the module is summarized in Table. The Table provides the type and number of arguments/returns for each function. The input is numpy array or list, and the output is numpy array. The notes are given in the remarks column.
Including C++, MATLAB and Labview interfaces are also client examples that utilize IndyDCP protocol. The name of functions and arguments are slightly different from the other interface such as C++ due to language's preferred naming convention, but the basic functionality and usage are exactly same. Therefore, users can refer to the same Table even though they use another example interface.
| Function | Input | Output | Remarks |
|---|---|---|---|
| emergency_stop() | - | - | - |
| reset_robot() | - | - | - |
| set_servo_on_off(var_arr) | bool[DOF1] | - | - |
| set_brake_on_off(var_arr) | bool[DOF] | - | Warning! When the brake is released, the robot drops to the ground by gravity |
| stop_motion() | - | - | - |
| execute_move_command(str) | string | - | Warning! The move name registered in default program |
| 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 index of the registered default program |
| 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 | - | Set level (1-5) |
| set_joint_boundary_level(level) | int | - | Set level (1-9) |
| set_task_boundary_level(level) | int | - | Set level (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. The list of Python IndyDCP client command functions
List of Extended IndyDCP Command Function
List of command functions of extended IndyDCP is summarized in below Table.
| Function | Input | Output | Remarks |
|---|---|---|---|
| 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 | - | Formatted txt file |
| joint_move_to_waypoint_set() | DOF*8*len | - | - |
| task_move_to_waypoint_set() | 6*8*len | - | - |
Table 2. The list of Python Extended IndyDCP client command functions
-
The number of robot joints (Indy7=6, IndyRP2 redundant option=7)
↩