Python IndyDCP client
Python IndyDCP client is a Python module for users to interface with Indy Framework and control Indy based on IndyDCP Protocol. 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
indy_utils/indydcp_client.py is the source file of Python IndyDCP module, and indydcp_example.ipynb is a jupyter notebook file that contains usage examples. Also, indy_utils/indy_program_maker.py and indy_program_example.ipynb are a module of Program maker and a jupyter notebook file used in the next section. Attached jupyter notebook file includes description about each cell, so users can practice the simple examples.
Basic Tutorial
Python IndyDCP client can be easily used by importing indydcp_client.py as below.
1 2 3 4 5 |
|
Users can connect or disconnect with robot using the connect() and disconnect() functions below. These should be added to the beginning and end of the program using the IndyDCP client.
1 2 |
|
The indydcp_client.py module implements the IndyDCPClient class, which includes all IndyDCP command functions, and creates a class object (indy). When creating the object, the robot_ip (the IP address of the IndyCB) and the robot_name ("NRMK-Indy7" string for Indy7) must be put as arguments. If indy object is created successfully, the examples below will work.
Request Command for Robot State
Users can use all command functions with the indy object. For example, users can execute the following commands for getting the robot state and printing it out.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 |
|
The commands above return True or False value depending on the current robot state. But, the get_robot_status() command can get all robot state more quickly.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 |
|
Request Command for Robot Position in Joint or Task Space
The commands below are for obtaining the joint angles in the joint space, and the position and orientation in the task space.
1 2 3 4 |
|
The joint angles (q1-q6) are represented in degree, and translations (x, y, z) and orientation (u, v, w) of task space are in meter and degree each. The u, v, w represent the rotation angles along the x, y, z axes respectively.
Also, velocity of both space and torque output are accessible as follows.
1 2 3 4 5 |
|
Robot Motion Command
Robot moves to preset home and zero position by the commands below.
1 |
|
1 |
|
1 |
|
Also, joint or task move can be executed with user defined position as follows.
1 2 |
|
1 2 |
|
1 |
|
The above motion command is for a single waypoint. Please refer to the Program maker for robot programming with complex logic such as multiple waypoints and tool commands.
Defalut Program Command
Users can load and run default programs which are pre-written and registered with Conty. The programs have indexes 1 to 10 and can be executed through the indexes. The following commands are an example of calling first default program and executing it.
1 2 3 4 5 |
|
1 |
|
List of IndyDCP Command Functions
The list of command function in the module is summarized in Table1. 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.
Warning
The functions marked with Warning! in the remarks column are the command functions that the robot performs the actual motion. When teaching robots using Conty, the robot should be moved to the target position by JOG or direct teaching, and then the position can be registered as a waypoint. However, when using the IndyDCP client, users have to directly input the target position (joint angles or task space position). This can cause the robot to move to unintended position due to user mistakes such as a wrong input of target position, mistake of the unit, wrong use of command function, and so on, which may cause the robot to collide with an obstacle and be damaged. To reduce these mistakes, it is highly recommended that users run the robot with the emergency stop button to stop the robot immediately in case of such a mistake.
Function | Parameters | Remarks |
---|---|---|
Joint servo commands | ||
emergency_stop() | - | - |
reset_robot() | - | - |
set_servo(arr) | arr (list): length DOF | ex) arr = [1, 1, 1, 1, 1, 0] |
set_brake(arr) | arr (list): length DOF | ex) arr = [1, 1, 1, 1, 0, 0] Warning! When the brake is released, the robot drops to the ground by gravity |
Motion commands | ||
stop_motion() | - | - |
execute_move(cmd_name) | cmd_name (string): command name | Warning! The move block execution registered in default program of Conty ex) cmd_name = "j_move1" |
go_home() | - | - |
go_zero() | - | - |
joint_move_to(q) | q (list): absolute joint angles [deg] | ex) q=[0, -20, -90, 0, -60, 0] Warning! Move command to target position |
joint_move_by(q) | q (list): relative joint angles [deg] | ex) q=[0, 0, 0, 0, 0, 20] Rotate only joint 6 by 20 degrees Warning! Move command to target position |
task_move_to(p) | p (list): absolute task-space pose [m, deg] | ex) p=[0.5, -0.2, 0.3, 180, -10, 180] Warning! Move command to target position |
task_move_by(p) | p (list): relative task-space pose [m, deg] | ex) p=[0, 0, -0.1, 0, 0, 0] Move -0.1 m along z-axis Warning! Move command to target position |
Default program and current program control | ||
start_current_program() | - | - |
pause_current_program() | - | - |
resume_current_program() | - | - |
stop_current_program() | - | - |
start_default_program() | - | Warning! Execute registered default program |
set_default_program(idx) | idx (int): default program index | - |
idx=get_default_program() | idx (int): default program index | - |
Robot state | ||
ret=is_robot_running() | ret (bool): True or False | - |
ret=is_robot_ready() | ret (bool): True or False | - |
ret=is_emergency_stop() | ret (bool): True or False | - |
ret=is_collided() | ret (bool): True or False | - |
ret=is_error_state() | ret (bool): True or False | - |
ret=is_busy() | ret (bool): True or False | - |
ret=is_move_finished() | ret (bool): True or False | - |
ret=is_home() | ret (bool): True or False | - |
ret=is_zero() | ret (bool): True or False | - |
ret=is_in_resetting() | ret (bool): True or False | - |
ret=is_direct_teaching_mode() | ret (bool): True or False | - |
ret=is_teaching_mode() | ret (bool): True or False | - |
ret=is_program_running() | ret (bool): True or False | - |
ret=is_program_paused() | ret (bool): True or False | - |
ret=is_conty_connected() | ret (bool): True or False | - |
Direct teaching mode | ||
change_to_direct_teaching() | - | - |
finish_direct_teaching() | - | - |
Waypoint move | ||
push_back_joint_waypoint(q) | q (list): absolute joint angles | - |
pop_back_joint_waypoint() | - | - |
clear_joint_waypoints() | - | - |
execute_joint_waypoints() | - | Warning! Execute registered waypoint motion |
push_back_task_waypoint(p) | p (list): absolute task-space pose | - |
pop_back_task_waypoint() | - | - |
clear_task_waypoints() | - | - |
execute_task_waypoints() | - | Warning! Execute registered waypoint motion |
Set properties | ||
set_default_tcp(tcp) | tcp (list): tool center point (pose) | ex) tcp=[0, 0, 0.1, 0, 0, 0] TCP in 0.1 m along the z-axis |
reset_default_tcp() | - | - |
set_tcp_compensation(tcp) | tcp (list): offset from default TCP | - |
reset_tcp_compensation() | - | - |
set_ref_frame(ref) | ref (list): reference frame | - |
reset_ref_frame() | - | - |
set_collision_level(level) | level (int): 1-5 level | - |
set_joint_speed_level(level) | level (int): 1-9 level | - |
set_task_speed_level(level) | level (int): 1-9 level | - |
set_joint_waypoint_time(time) | time (double): 0.5-4 sec | - |
set_task_waypoint_time(time) | time (double): 0.5-4 sec | - |
set_task_base_mode(mode) | mode (int): 0=reference body, 1=end-effector tool tip | - |
set_joint_blend_radius(radius) | radius (int): 3-27 deg | - |
set_task_blend_radius(radius) | radius (double): 0.02-0.2 m | - |
Get properties | ||
tcp=get_default_tcp() | tcp (list): current TCP | - |
tcp=get_tcp_compensation() | tcp (list): current TCP offset | - |
ref=get_ref_frame() | ref (list): current reference frame | - |
level=get_collision_level() | level (int): current collision level | - |
level=get_joint_speed_level() | level (int): current joint speed level | - |
level=get_task_speed_level() | level (int): current task speed level | - |
time=get_joint_waypoint_time() | time (double): current joint waypoint time | - |
time=get_task_waypoint_time() | time (double): current task waypoint time | - |
mode=get_task_base_mode() | mode (int): current task-move base mode | - |
radius=get_joint_blend_radius() | radius (double): current joint blend radius | - |
radius=get_task_blend_radius() | radius (double): current task blend radius | - |
time=get_robot_running_time() | time (double): Total execution time after resetting robot | - |
cmode=get_cmode() | cmode (int): control mode | - |
servo, brake =get_servo_state() |
servo (list): servo state brake (list): brake state |
- |
Robot data and information | ||
j_pos=get_joint_pos() | j_pos (list): current joint angles | - |
j_vel=get_joint_vel() | j_vel (list): current joint velocities | - |
t_pos=get_task_pos() | t_pos (list): current task-space pose | - |
t_vel=get_task_vel() | t_vel (list): current task-space velocity | - |
j_tor=get_torque() | j_tor (list): current torques applied to joints | - |
err, err_idx, err_val =get_last_emergency_info() |
err (int): error code err_idx (list): error index err_val (list): error value |
- |
Digital I/O and Analog I/O | ||
val=get_smart_di(idx) | val (bool): 0 or 1 idx (int): index of digital input channel |
- |
val=get_smart_dis() | val (list): list of 32 channel digital input | - |
set_smart_do(idx, val) | idx (int): 0-31 channel val (int): 0 or 1 |
- |
set_smart_dos(idx) | idx (list): 0-31 channel | - |
val=get_smart_do(idx) | idx (int): 0-31 channel val (int): 0 or 1 |
- |
val=get_smart_dos() | val (list): 32 channels | - |
val=get_smart_ai(idx) | val (int): analog input value 0-10000 (0-10V) idx (int): index of analog input channel |
- |
set_smart_ao(idx, val) | idx (int): index of analog output channel val (int): analog output value (0-10000) |
- |
val=get_smart_ao(idx) | idx (int): 0-1 channel val (int): 0-10000 |
- |
set_endtool_do(et_type, val) | et_type (int): type of end tool val (int): 0 or 1 |
0: NPN, 1: PNP, 2: Not use, 3: eModi |
val=get_endtool_do(et_type) | et_type (int): type of end tool val (int): 0 or 1 |
0: NPN, 1: PNP, 2: Not use, 3: eModi |
F/T sensor interface | ||
val=get_robot_ft_sensor_raw() | val (list): [Fx, Fy, Fz, Tx, Ty, Tz] | Raw value of F/T sensor connected to the end tool port |
val=get_robot_ft_sensor_process() | val (list): [Fx, Fy, Fz, Tx, Ty, Tz] | Coordinate transformation value for the base coordinate of the F/T sensor connected to the end tool port |
val=get_cb_ft_sensor_raw() | val (list): [Fx, Fy, Fz, Tx, Ty, Tz] | Raw value of F/T sensor connected to CB CAN port |
val=get_cb_ft_sensor_process() | val (list): [Fx, Fy, Fz, Tx, Ty, Tz] | Coordinate transformation value for base coordinate of F/T sensor connected to CB CAN port |
Direct variables | ||
val =read_direct_variable(dv_type, dv_addr) |
val (int): value of direct variable dv_type (int): type of direct variable dv_addr (int): address of direct variable |
- |
val=read_direct_variables(dv_type, dv_addr, dv_len) | val (list): value list to be assigned dv_type (int): type of direct variable dv_addr (int): address of direct variable dv_len (int): length of direct variables to be read |
- |
write_direct_variable(dv_type, dv_addr, val) |
addr (int): address of direct variable val (int): value of direct variable type (int): type of direct variable |
- |
write_direct_variables(dv_type, dv_addr, dv_len, val) | dv_type (int): type of direct variable dv_addr (int): address of direct variable dv_len (int): length of direct variables to be written val (list): value list to be assigned |
- |
Table 1. The list of Python IndyDCP client command functions
List of Extended IndyDCP Command Function
The Extended IndyDCP command list is shown in the table below. External trajectory move command sends the motion trajectory, users create, to the robot to execute the motion. Four command functions are provided for transferring external trajectories to the robot. Some methods transfer the trajectory data in memory by binary or text form (move_ext_traj_bin, move_ext_traj_txt), and others execute the command (move_ext_traj_bin_file, move_ext_traj_txt_file) after they read a file stored in binary or text form. When reading a file, the commands send the file name and the file must be in the STEP. But, when transferring data in memory, the client PC transmits the trajectory data by TCP/IP communication.
Function | Parameters | Remarks |
---|---|---|
move_ext_traj_bin(traj_type, traj_freq, dat_size, traj_data) | traj_type (int): type 1=joint move, type 2=task move traj_freq (int): control frequency of trajectory dat_size (int): size of data traj_data (list): binary data |
- |
move_ext_traj_txt(traj_type, traj_freq, dat_size, traj_data) | traj_type (int): type 1=joint move, type 2=task move traj_freq (int): control frequency of trajectory dat_size (int): size of data traj_data (list): binary data |
- |
move_ext_traj_bin_file(file_name) | file_name (string): name of file saved in STEP | - |
move_ext_traj_txt_file(file_name) | file_name (string): name of file saved in STEP | - |
Table 2. The list of Python Extended IndyDCP client 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 number of robot joints (Indy7=6, IndyRP2 redundant option=7) ↩