Python IndyDCP3 Client
To use the IndyDCP3 client with Python, you must first install the neuromeka
package.
You can find Jupyter notebook
examples in the Github repository.
Installation Requirements
- Requires Python version 3.6 or higher, but may not function with versions above 3.9.
- Installation is via
pip3
(orpip
).
Installation Instructions
You can install the package with the following command in a terminal or command prompt.
The package version can be updated with the following terminal command.
The current version of the installed package can be checked with the following terminal command (release version history).
Using IndyDCP3
To create a client object, you need to import the IndyDCP3
class from the neuromeka
package.
IndyDCP3
class object, you must specify the robot's IP address for communication as follows:
robot_ip
: IP address of the robot controllerindex
: Robot index, used in cases where multiple robots are connected to a controller, like dual-arm robots
Methods and Functions
Below is a list of protocol functions that can be called using the IndyDCP3 object. Please refer to the usage methods and input/output examples for each function.
Note
The output of all functions is returned as a Python dict type.
Real-Time Data Acquisition Functions
You can retrieve the robot's current motion status, control data and state, servo motor state, error information, and program status.
Function | Description |
---|---|
get_robot_data() |
Robot status data |
get_control_state() |
Control state |
get_motion_data() |
Motion data |
get_servo_data() |
Servo data |
get_violation_data() |
Error data |
get_program_data() |
Robot program data |
get_robot_data()
{
'running_mins': 6,
'running_secs': 11,
'op_state': 5,
'sim_mode': True,
'ref_frame': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
'tool_frame': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
'running_hours': 0
}
running_hours
: Robot operating time (hours)running_mins
: Robot operating time (minutes)running_secs
: Robot operating time (seconds)op_state
: Robot state as defined in theOpState
classOpState
:SYSTEM_OFF(0)
,SYSTEM_ON(1)
,VIOLATE(2)
,RECOVER_HARD(3)
,RECOVER_SOFT(4)
,IDLE(5)
,MOVING(6)
,TEACHING(7)
,COLLISION(8)
,STOP_AND_OFF(9)
,COMPLIANCE(10)
,BRAKE_CONTROL(11)
,SYSTEM_RESET(12)
,SYSTEM_SWITCH(13)
,VIOLATE_HARD(15)
,MANUAL_RECOVER(16)
,TELE_OP(17)
sim_mode
: Simulation mode enabled (True)ref_frame
: Reference frame ([0.0, 0.0, 0.0, 0.0, 0.0, 0.0])tool_frame
: Tool frame ([0.0, 0.0, 0.0, 0.0, 0.0, 0.0])
get_control_state()
{
'q': [...],
'qdot': [...],
'qddot': [...],
'qdes': [...],
'qdotdes': [...],
'qddotdes': [...],
'p': [...],
'pdot': [...],
'pddot': [...],
'pdes': [...],
'pdotdes': [...],
'pddotdes': [...],
'tau': [...],
'tau_act': [...],
'tau_ext': [...],
'tau_jts': [...],
'tau_jts_raw1': [...],
'tau_jts_raw2': [...],
}
q
,qdot
,qddot
: Current positions (deg), velocities (deg/s), and accelerations (deg/s²) of each jointqdes
,qdotdes
,qddotdes
: Target positions (deg), velocities (deg/s), and accelerations (deg/s²) of each jointp
,pdot
,pddot
: Current workspace pose positions (mm), velocities (mm/s), and accelerations (mm/s²)pdes
,pdotdes
,pddotdes
: Target workspace pose positions (mm), velocities (mm/s), and accelerations (mm/s²)tau
,tau_act
,tau_ext
: Current input torques, actual torques, and external torques (Nm) for each jointtau_jts
,tau_jts_raw1
,tau_jts_raw2
: joint torque sensor values.
For example, you can use the following to return the current angles of each joint as a list
type.
get_motion_data()
{
'traj_progress': 100,
'cur_traj_progress': 100,
'is_target_reached': True,
'is_in_motion': False,
'is_pausing': False,
'is_stopping': False,
'traj_state': 0,
'speed_ratio': 100,
'has_motion': False,
'motion_id': 0,
'remain_distance': 0.0,
'motion_queue_size': 0
}
traj_progress
: Overall motion progress (%)cur_traj_progress
: Current executing motion's progress (%)is_target_reached
: Whether the target position has been reached (True/False)is_in_motion
: Whether motion is in progress (True/False)is_pausing
: Whether motion is paused (True/False)is_stopping
: Whether motion is stopped (True/False)traj_state
: Motion progress state, with states defined in theTrajState
classTrajState
:NONE(0)
,INIT(1)
,CALC(2)
,STAND_BY(3)
,ACC(4)
,CRUISE(5)
,DEC(6)
,CANCELLING(7)
,FINISHED(8)
,ERROR(9)
speed_ratio
: Motion speed ratio, set byset_speed_ratio()
has_motion
: Whether motion exists (True/False)remain_distance
: Remaining distance (mm)motion_id
: Current motion IDmotion_queue_size
: Motion queue size
get_servo_data()
{
'status_codes': ['0x1237', '0x1237', '0x1237', '0x1237', '0x1237', '0x1237'],
'temperatures': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
'voltages': [48.0, 48.0, 48.0, 48.0, 48.0, 48.0],
'currents': [3.4812942e-18,
26.195215,
26.963966,
0.12320003,
0.55777645,
4.536144e-05],
'servo_actives': [True, True, True, True, True, True],
'brake_act
ives': [False, False, False, False, False, False]
}
status_codes
: Status codes (CiA402) for each joint servotemperatures
: Temperatures for each joint servovoltages
: Voltages for each joint servocurrents
: Currents for each joint servoservo_actives
: Activation state of each joint servo (True/False)brake_actives
: Activation state of the brakes for each joint servo (True/False)
get_violation_data()
{
'violation_code': '262144',
'j_index': 4,
'i_args': [2],
'f_args': [0.0012204262],
'violation_str': 'EMG Button Activated'
}
j_index
: Index of the joint where the violation occurredi_args
: Integer information about the violationf_args
: Float information about the violationviolation_str
: Error messageviolation_code
: Error code
violation_code (Binary) | violation_str |
---|---|
0b00 | None |
0b01 << 0 | Joint [axisIdx/DOF] Position Error Over Limit (Current: X deg, Desired: Y, Limit: Z) |
0b01 << 1 | Joint [axisIdx/DOF] Position Close To Limit (Current: X deg, Allowed: A ~ B) |
0b01 << 2 | Joint [axisIdx/DOF] Velocity Close To Limit (Current: X deg/s, Allowed: A ~ B) |
0b01 << 6 | TCP Singular Closed |
0b01 << 7 | Joint [axisIdx/DOF] Position Exceeded Limit (Current: X, Allowed: A ~ B) |
0b01 << 8 | Joint [axisIdx/DOF] Velocity Exceeded Limit (Current: X, Allowed: A ~ B) |
0b01 << 9 | Joint [axisIdx/DOF] Torque Exceeded Limit (Current: X, Allowed: A ~ B) |
0b01 << 10 | TCP Speed Limit: X m/s |
0b01 << 11 | TCP Force Limit: X N |
0b01 << 12 | Power Over Limit (Current: X, Allowed: Y) |
0b01 << 13 | Standstill Failed |
0b01 << 14 | Loss of Conty Communication |
0b01 << 15 | Loss of IndyKey Communication |
0b01 << 16 | Safety Guard Input 1 |
0b01 << 17 | Safety Guard Input 2 |
0b01 << 18 | EMG Button Activated |
0b01 << 19 | Robot Specs Reading Failed |
0b01 << 20 | Connection Lost - Master: masterState, Detected Joints Num: numSlavesDetected / DOF+2 |
0b01 << 21 | Motor Status Error: joint [axisIdx/DOF], Code = errorCode |
0b01 << 22 | Motor Over Current: joint [axisIdx/DOF], Code errorCode |
0b01 << 23 | Motor Over Heated: joint [axisIdx/DOF], Temperature X celsius |
0b01 << 24 | Motor Error Bit: joint [axisIdx/DOF], Code = errorCode |
0b01 << 25 | Motor Low Battery: joint [axisIdx/DOF], Code = errorCode |
0b01 << 26 | Motor Firmware Error |
0b01 << 27 | Task Time Over Limit (Current: X us, Allowed: Y us) |
0b01 << 28 | Soft Reset Failed |
0b01 << 29 | Auto Servo-Off Activated |
0b01 << 30 | TeleOp Starting Point Too Far |
get_program_data()
{
'program_name': 'ProgramScripts/',
'program_state': 0,
'cmd_id': 0,
'sub_cmd_id': 0,
'running_hours': 0,
'running_mins': 0,
'running_secs': 0,
'program_alarm': '',
'program_annotation': ''
}
program_name
: Name of the currently running program fileprogram_state
: Program execution stateProgramState
:IDLE(0)
,RUNNING(1)
,PAUSING(2)
,STOPPING(3)
running_hours
: Program operating time (hours)running_mins
: Program operating time (minutes)running_secs
: Program operating time (seconds)program_alarm
: Alarm of Conty Flow controlprogram_annotation
: Annotation of Conty Flow control
I/O Device Related Functions
Device-related functions provide methods to set and query various hardware states of the robot. These methods manage and query the activation state of digital I/O, analog I/O, end-tool I/O, specific device states, and basic information about devices.
Note
Some endtool functions may not be supported depending on the specifications of the robot you purchased.
Function | Description |
---|---|
get_di() |
IO board DI data |
get_do() |
IO board DO data |
set_do(do_signal_list) |
Set IO board DO data |
get_ai() |
IO board AI data |
get_ao() |
IO board AO data |
set_ao(ao_signal_list) |
Set IO board AO data |
get_endtool_di() |
End-tool DI data |
get_endtool_do() |
End-tool DO data |
set_endtool_do(end_do_signal_list) |
Set end-tool DO data |
get_endtool_ai() |
End-tool AI data |
get_endtool_ao() |
End-tool AO data |
set_endtool_ao(end_ao_signal_list) |
Set end-tool AO data |
get_device_info() |
Device information |
get_ft_sensor_data() |
End-tool F/T sensor data |
get_di()
Digital I/O states are represented as DigitalState
values: OFF(0)
, ON(1)
, UNUSED(2)
.
I/O data is returned as a dict
type with address
representing the IO channel address and state
representing the DigitalState
.
{
'signals': [
...
{'address': 7, 'state': 2},
{'address': 8, 'state': 2},
{'address': 9, 'state': 2},
{'address': 10, 'state': 2},
{'address': 11, 'state': 2},
...
]
}
get_do()
, set_do()
To apply an output value with set_do
, you must pass a dict
type as an argument, as shown in the example below.
{
'signals': [
...,
{'address': 1, 'state': 0},
...
{'address': 5, 'state': 1},
...
{'address': 9, 'state': 1},
...
]
}
get_ai()
{
'signals': [
{'address': 0, 'voltage': 0},
{'address': 1, 'voltage': 0},
{'address': 2, 'voltage': 0},
{'address': 3, 'voltage': 0},
{'address': 4, 'voltage': 0},
{'address': 5, 'voltage': 0},
{'address': 6, 'voltage': 0},
{'address': 7, 'voltage': 0}
]
}
- The control box's IO board has 2 AI channels assigned to
address
0 and 1. The remaining channels are spare.
get_ao()
, set_ao()
{
'signals': [{'voltage': 7, 'address': 0},
{'address': 1, 'voltage': 2},
{'address': 2, 'voltage': 0},
{'address': 3, 'voltage': 0},
{'address': 4, 'voltage': 0},
{'address': 5, 'voltage': 0},
{'address': 6, 'voltage': 0},
{'address': 7, 'voltage': 0}]
}
get_endtool_di()
Digital outputs of the end-tool port are defined as EndtoolState
class states:
UNUSED(0)
, HIGH_PNP(2)
, HIGH_NPN(1)
, LOW_NPN(-1)
, LOW_PNP(-2)
set_endtool_do()
, get_endtool_do()
For RevC end-tool boards, only one C port exists and can be used as follows:
For RevE end-tool boards, two end-tool ports, A and B, exist and can be used as follows:
get_endtool_ai()
This can only be used with the RevE endtool board.
The RevE endtool board has two AI channels, which are assigned to address
0 and 1, respectively. The remaining channels are reserved.
{'signals': [{'address': 0, 'voltage': 0},
{'address': 1, 'voltage': 0},
{'address': 2, 'voltage': 0},
{'address': 3, 'voltage': 0},
{'address': 4, 'voltage': 0},
{'address': 5, 'voltage': 0},
{'address': 6, 'voltage': 0},
{'address': 7, 'voltage': 0}]}
set_endtool_ao()
, get_endtool_ao()
This can only be used with the RevE endtool board.
The RevE endtool board has two AO channels, which are assigned to address
0 and 1, respectively. The remaining channels are reserved.
get_device_info()
get_ft_sensor_data()
Motion Command Functions
Motion command Functions perform various tasks related to robot motion control. For example, the stop_motion
function stops the robot's motion according to the specified stop category. The movej
, movel
, and movec
functions are used for joint movement, linear movement, and circular movement, respectively, and each function allows you to set the target position, speed ratio, acceleration ratio, movement time, and various movement conditions.
Function | Description |
---|---|
stop_motion(stop_category) |
Stop the motion according to the specified stop category |
move_home() |
Move the robot to the specified home position using joint movement |
movej(jtarget, blending_type, base_type, blending_radius, vel_ratio, acc_ratio, post_condition, teaching_mode) |
Move the robot to the specified joint target position |
movej_time(jtarget, blending_type, base_type, blending_radius, move_time, post_condition) |
Move the robot to the specified joint target position over a specified time |
movel(ttarget, blending_type, base_type, blending_radius, vel_ratio, acc_ratio, post_condition, teaching_mode) |
Move the robot to the specified workspace target position using linear movement |
movel_time(ttarget, blending_type, base_type, blending_radius, move_time, post_condition) |
Move the robot to the specified workspace target position using linear movement over a specified time |
movec(tpos0, tpos1, blending_type, base_type, angle, setting_type, move_type, blending_radius, vel_ratio, acc_ratio, post_condition, teaching_mode) |
Move the robot along a circular path passing through two specified workspace positions tpos0 and tpos2 |
movec_time(tpos0, tpos1, blending_type, base_type, angle , setting_type, move_type, blending_radius, move_time, post_condition) |
Move the robot along a circular path passing through two specified workspace positions tpos0 and tpos2 over a specified time |
move_gcode(gcode_file, is_smooth_mode, smooth_radius, vel_ratio, acc_ratio) |
Move the robot follows gcode file input |
add_joint_waypoint(jpos) get_joint_waypoint() clear_joint_waypoint() move_joint_waypoint(move_time) |
Move the robot through a set of joint waypoints |
add_task_waypoint(tpos) get_task_waypoint() clear_task_waypoint() move_task_waypoint(move_time) |
Move the robot through a set of task waypoints |
move_joint_traj(q_list, qdot_list, qddot_list) |
Move the robot along a joint position-velocity-acceleration trajectory of full control frequency |
move_task_traj(p_list, pdot_list, pddot_list) |
Move the robot along a workspace position-velocity-acceleration trajectory of full control frequency |
Warning
Be cautious when using motion commands, as the robot will move immediately if the command is successfully applied. While using the robot through the Conty allows movement only while the user is holding the touch button, using the API allows movement through program commands, so always ensure the area is clear of objects that could cause collisions. Especially, be mindful of safety if setting high speeds or accelerations, as the robot may move faster than expected.
stop_motion(stop_category)
You can choose from stop category 0, stop category 1, and stop category 2 depending on the value of stop_category
. The StopCategory
class defines the stop categories CAT0(0)
, CAT1(1)
, and CAT2(2)
.
StopCategory
CAT0
: Stop the robot immediately by cutting off power (emergency stop)CAT1
: Stop the robot by stopping motion then cutting off powerCAT2
: Stop the robot by stopping motion
move_home()
The move_home
command performs a joint movement to the specified home position.
movej(...)
The movej
command is a joint movement command. In the example below, target_pos
is a list
value in degrees, and the robot moves to the entered target joint position.
Velocity/Acceleration Settings
You can adjust the robot's velocity and acceleration with vel_ratio
and acc_ratio
.
vel_ratio
: Represents the velocity of the robot during constant velocity mode. You can enter a value from 0-100 (%), with 100% representing the robot's maximum joint velocity (e.g., 180deg/s for the Indy7).acc_ratio
: Represents the acceleration of the robot as a multiple ofvel_ratio
. You can enter a value from 0-900 (%), with 300% resulting in the robot moving at three times the acceleration of the setvel_ratio
.
Absolute/Relative Joint Movement
base_type
is the value for setting the target joint position jtarget
either in absolute coordinates or relative coordinates.
JointBaseType
ABSOLUTE(0)
: Move to the absolute positionjtarget
RELATIVE(1)
: Move to the relative positionjtarget
based on the current robot position
Jog Mode Joint Movement
Setting teaching_mode
to True
allows moving the robot in jog mode.
When executing jog motion movement, you must periodically apply the movej
command for the robot to move.
Time-based Movement
movej_time
is a command to perform joint movement over a specified move_time
(unit: sec).
movel(...)
movel
is a linear position movement command in the workspace. Below, target_pos
is a list
value in [mm, mm, mm, deg, deg, deg].
base_type
, vel_ratio
, acc_ratio
, teaching_mode
are applied the same as in the movej
arguments.
Absolute/Relative (Reference Frame, Tool Frame) Joint Movement
base_type
is the value for setting the target workspace position ttarget
either in absolute coordinates, relative coordinates, reference frame basis, or tool frame basis.
TaskBaseType
ABSOLUTE(0)
: Move to the absolute positionttarget
RELATIVE(1)
: Move linearly to the relative positionttarget
based on the current robot position in the reference frameTCP(2)
: Move linearly to the relative positionttarget
based on the current robot position in the tool frame
Time-based Movement
movel_time
is a command to perform linear position movement in the workspace over a specified move_time
.
movec(...)
movec
is a circular motion position movement command in the workspace. Here, tpos0
and tpos1
are list
values representing the via point and end point, respectively.
angle
: Angle setting for the arc (unit degree), setting to 360 will draw a circle, 180 will draw a semicircle, and 720 will draw two circles.
Time-based Movement
movec_time
is a command to perform circular movement in the workspace over a specified move_time
.
move_gcode(...)
The move_gcode
function interprets and executes movements based on a G-code file. G-code is widely used in CNC and robotic applications to define paths.
gcode_path = "/path/to/gcode/<gcode file>"
indy.move_gcode(
gcode_file=gcode_path,
is_smooth_mode=False,
smooth_radius=0.0,
vel_ratio=15,
acc_ratio=100
)
gcode_file
: The file path of the G-code file.is_smooth_mode
: IfTrue
, enables smooth mode for transitions (default:False
).smooth_radius
: Blending radius for smoothing corners, in millimeters.vel_ratio
: Velocity ratio, a percentage of the robot’s maximum velocity (default:JogVelRatioDefault
).-
acc_ratio
: Acceleration ratio, a percentage of the velocity ratio (default:JogAccRatioDefault
). -
Enables smooth transitions between G-code path segments.
- Use
smooth_radius
to set the transition radius.
Move joint waypoints and move task waypoints
Joint Waypoints
Joint waypoints are specific positions for each of the robot's joints that the robot will move through sequentially.
add_joint_waypoint(jpos)
adds a joint waypoint to the list of waypoints. The waypoint is a vector representing the target positions for each joint of the robot.
jpos
: a vector of floats, each representing a joint position in degrees.
get_joint_waypoint()
retrieves the current list of joint waypoints that have been added. This allows you to review or verify the waypoints before executing the movement.
clear_joint_waypoint()
clears the current list of joint waypoints. This function is useful if you need to reset the waypoints and start adding new ones.
move_joint_waypoint(move_time)
moves the robot through the sequence of joint waypoints that have been added. The robot will attempt to reach each waypoint sequentially.
move_time
: (optional) The time in seconds for the robot to move through the waypoints. If not provided, the robot will move normally.
Task Waypoints
Task waypoints refer to specific positions and orientations in space that the robot's endtool should move through.
add_task_waypoint(tpos)
adds a task waypoint to the list of waypoints. The waypoint is an array representing the target position and orientation in Cartesian space.
tpos
: an array of six floats representing the x, y, z position and the roll, pitch, yaw orientation of the endtool.
get_task_waypoint()
retrieves the current list of task waypoints that have been added. This allows you to review or verify the waypoints before executing the movement.
clear_task_waypoint()
clears the current list of task waypoints. This function is useful if you need to reset the waypoints and start adding new ones.
move_task_waypoint(move_time)
moves the robot's endtool through the sequence of task waypoints that have been added. The robot will attempt to reach each waypoint sequentially.
move_time
: (optional) The time in seconds for the robot to move through the waypoints. If not provided, the robot will move normally.
Asynchronous Motion
You can perform asynchronous motion by setting the blending_type
during robot motion commands. You can switch to the next motion (Override) or stack them (Duplicate).
BlendingType
NONE(0)
: No asynchronous motion specified (performs synchronous motion)OVERRIDE(1)
: Perform override asynchronous motionDUPLICATE(2)
: Perform duplicate asynchronous motion
Waiting Functions
Wait IO: Waits for specific digital or analog I/O signals to meet the given conditions.
Wait Time: Waits for a specified time, after starting the first motion command.
Wait Progress: Waits for progress status.
Wait Radius: Waits until movement within a specified radius is complete.
Wait Traj: Waits until trajectory movement is complete.
- WaitTraj conditions
- TRAJ_STARTED(0)
: trajectory has just started
- TRAJ_ACC_DONE(1)
: acceleration phase of the trajectory has been completed
- TRAJ_CRZ_DONE(2)
: cruising phase (constant speed phase) of the trajectory has been completed.
- TRAJ_DEC_DONE(3)
: deceleration phase of the trajectory has been completed.
Wait IO Usage Example
Trajectory Motion
move_joint_traj
is a joint-space trajectory movement movement command.
Below, q_list
, qdot_list
, qddot_list
are list
values of joint position, velocity and acceleration in radians.
The time step between trajectory is the control period, which is 250us by default.
move_task_traj
is a task-space trajectory movement movement command.
Below, p_list
, pdot_list
, pddot_list
are list
values of endtool position, velocity and acceleration in meters and radians.
The time step between trajectory is the control period, which is 250us by default.
Teleoperation Related Functions
Teleoperation-related functions provide the capability to remotely control the robot. These functions allow real-time adjustment of the robot's motion and control in various operation modes. You can start the teleoperation mode using the start_teleop
function and end the mode using the stop_teleop
function. Additionally, you can update robot movements in joint space and workspace using the movetelej_abs
/movetelej_rel
and movetelel_abs
/movetelel_rel
functions, respectively.
Note
When using teleoperation motion through IndyDCP3, continuously updating the target position in real-time allows the robot to stream and generate smooth and immediate motion. Traditional Motion commands (movej
, movel
) perform path generation smoothly but cannot respond immediately like remote control. This is a characteristic of teleoperation motion.
Function | Description |
---|---|
start_teleop(method) |
Start teleoperation mode |
stop_teleop() |
End the currently running teleoperation mode |
movetelej_abs(jpos, vel_ratio, acc_ratio) |
Remotely control the robot to a specified joint position (absolute coordinates) |
movetelej_rel(jpos, vel_ratio, acc_ratio) |
Remotely control the robot to a specified joint position (relative coordinates) |
movetelel_abs(tpos, vel_ratio, acc_ratio) |
Remotely control the robot to a specified workspace position (absolute coordinates) |
movetelel_rel(tpos, vel_ratio, acc_ratio) |
Remotely control the robot to a specified workspace position (relative coordinates) |
get_teleop_device() |
Retrieve information about the currently connected teleoperation device |
get_teleop_state() |
Retrieve the current teleoperation state |
connect_teleop_device(name, type, ip, port) |
Connect to a teleoperation device with specified parameters |
disconnect_teleop_device() |
Disconnect the currently connected teleoperation device |
read_teleop_input() |
Read the current input values from the teleoperation device |
get_tele_file_list() |
Retrieve a list of saved teleoperation motion files |
save_tele_motion(name) |
Save the current teleoperation motion with a specified name |
load_tele_motion(name) |
Load a saved teleoperation motion by name |
delete_tele_motion(name) |
Delete a saved teleoperation motion by name |
enable_tele_key(enable) |
Enable or disable teleoperation key input |
set_play_rate(rate) |
Set the play rate for teleoperation motion playback |
get_play_rate() |
Retrieve the current play rate for teleoperation motion playback |
start_teleop(method)
, stop_teleop()
-
JointTeleopType
ABSOLUTE
: Set to move the robot to an absolute joint position target. In this setting, only themovetelej_abs
function can be called.RELATIVE
: Set to move the robot to a relative joint position target (based on the robot's position at the timestart_teleop
was executed). In this setting, only themovetelej_rel
function can be called.
-
TaskTeleopType
ABSOLUTE
: Set to move the robot to an absolute workspace position target. In this setting, only themovetelel_abs
function can be called.RELATIVE
: Set to move the robot to a relative workspace position target (based on the robot's position at the timestart_teleop
was executed). In this setting, only themovetelel_rel
function can be called.
movetelej_rel(jpos, vel_ratio, acc_ratio)
- jpos: Target joint position
- vel_ratio: Velocity ratio (0 - 1)
- acc_ratio: Acceleration ratio (0 - 1)
movetelel_rel(tpos, vel_ratio, acc_ratio)
get_teleop_device()
Retrieve information about the currently connected teleoperation device.
get_teleop_state()
Retrieve the current teleoperation state.
connect_teleop_device(name, type, ip, port)
Connect to a teleoperation device with specified parameters.
name
: The name of the teleoperation device.type
: The type of the teleoperation device (e.g.,JOYSTICK
,VR_CONTROLLER
).ip
: The IP address of the teleoperation device.port
: The communication port for the device.
disconnect_teleop_device()
Disconnect the currently connected teleoperation device.
read_teleop_input()
Read the current input values from the teleoperation device.
get_tele_file_list()
Retrieve a list of saved teleoperation motion files.
save_tele_motion(name)
Save the current teleoperation motion with a specified name.
name
: The name to save the teleoperation motion under.
load_tele_motion(name)
Load a saved teleoperation motion by name.
name
: The name of the saved teleoperation motion to load.
delete_tele_motion(name)
Delete a saved teleoperation motion by name.
name
: The name of the saved teleoperation motion to delete.
enable_tele_key(enable)
Enable or disable teleoperation key input.
enable
: A boolean value:True
: Enables teleoperation key input.False
: Disables teleoperation key input.
set_play_rate(rate)
Set the play rate for teleoperation motion playback.
rate
: A float value specifying the playback rate.1.0
: Normal speed.- Greater than
1.0
: Faster playback. - Less than
1.0
: Slower playback.
get_play_rate()
Retrieve the current play rate for teleoperation motion playback.
Variables (Variable)
The Indy Framework provides five types of variables for integration with Conty and the API. These variables are accessible from both Conty and the IndyAPI, and they support both reading and writing operations. This functionality allows for integration through variable exchange between robots programmed in Conty and external devices using the Indy API. Utilizing these variables enables complex logic configurations with external devices.
The five types of provided variables are as follows:
- Bool type, Integer type, Float type, JPos type (joint space angle variables for each joint), TPos type (workspace coordinate variables in the workspace)
Function | Description |
---|---|
get_bool_variable() |
Address and value list for Bool type variables |
get_int_variable() |
Address and value list for Integer type variables |
get_float_variable() |
Address and value list for Float type variables |
get_jpos_variable() |
Address and value list for JPos type variables |
get_tpos_variable() |
Address and value list for TPos type variables |
set_bool_variable(bool_variables) |
Set address and value list for Bool type variables |
set_int_variable(int_variables) |
Set address and value list for Integer type variables |
set_float_variable(float_variables) |
Set address and value list for Float type variables |
set_jpos_variable(jpos_variables) |
Set address and value list for JPos type variables |
set_tpos_variable(tpos_variables) |
Set address and value list for TPos type variables |
get_bool_variable()
set_bool_variable(bool_variables)
get_int_variable()
{'variables': [{'addr': 300, 'value': '0'}, {'addr': 10, 'value': '20'}, {'addr': 15, 'value': '5'}]}
set_int_variable(int_variables)
get_float_variable()
set_float_variable()
get_jpos_variable()
[{'jpos': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], 'addr': 0},
{'addr': 200, 'jpos': [10.0, 10.0, 10.0, 10.0, 10.0, 10.0]}]
set_jpos_variable()
example
get_tpos_variable()
{
'variables': [
{'addr': 10, 'tpos': [100.0, 100.0, 200.0, 0.0, 180.0, 0.0]},
{'addr': 20, 'tpos': [100.0, 100.0, 350.0, 0.0, 180.0, 0.0]}
]
}
set_tpos_variable(tpos_variables)
Inverse Kinematics and Simulation Mode Related Functions
Function | Description |
---|---|
inverse_kin(tpos, init_jpos) |
Calculate the joint position that can reach a given workspace position tpos , based on the initial joint position init_jpos |
set_direct_teaching(enable) |
Enable/disable direct teaching mode via True/False |
set_simulation_mode(enable) |
Enable/disable simulation mode via True/False |
recover() |
Recover the robot from an error or collision state |
inverse_kin(tpos, init_jpos)
A function that calculates the joint position that can reach a given workspace position from the workspace coordinates. It finds the nearest solution based on the initial joint position. The example below shows whether the current joint angles result from the inverse kinematics operation when using the current robot's joint angles as init_jpos
and the current robot's workspace position as tpos
.
Current tpos [299.6449, -107.58244, 1002.9704, 2.3324265, 84.555115, 16.708658]
Current jpos [21.618074, 13.531353, -64.26601, -12.834319, -34.454514, 10.170495]
{'jpos': [21.618074, 13.531353, -64.26601, -12.834319, -34.454514, 10.170495],
'response': {'msg': 'InverseKinematics Success', 'code': '0'}}
tpos
: Target workspace position ([x, y, z, u, v, w] format)
- init_jpos
: Initial joint position
- jpos
: List of calculated joint positions
set_direct_teaching(enable)
- enable: True (enabled) | False (disabled)
set_simulation_mode(enable)
A function to set simulation mode. When this mode is enabled, a simulated robot operates instead of the actual robot.
- enable: True (enabled) | False (disabled)
recover()
A function to recover the robot from an error or collision state. When the robot falls into an abnormal state, you can call this function to return it to a normal state.
Program Control Functions
Using IndyDCP3, you can control the playback, pause, resume, and stop of robot programs. These features allow users to flexibly manage the execution flow of programs.
Function | Description |
---|---|
play_program(prog_name, prog_idx) |
Start a program, prog_name : Program file name, prog_idx : Program index |
pause_program() |
Pause the currently running program |
resume_program() |
Resume a paused program |
stop_program() |
Stop the currently running program |
play_program(prog_name, prog_idx)
Play a program by either specified name or index. You can select a specific program using either the program name or index.
Note
Programs must be pre-written and saved using Conty.
- When playing using the program file name, the program file path (STEP): ~/ProgramScripts
- When playing using the program index, the program file path (STEP): ~/ProgramScripts/index
pause_program()
Pause the currently running program.
resume_program()
Resume a paused program. Use this function when you need to pause and then restart a program.
stop_program()
Stop the currently running program.
Using IndySDK
This protocol is for activating the Indy SDK and setting the custom control mode.
Function | Description |
---|---|
activate_sdk() |
Activates IndySDK |
set_custom_control_mode() |
Enables/Disables user controller mode |
get_custom_control_mode() |
Checks user controller mode |
set_custom_control_gain() |
Sets control gain for the user controller |
get_custom_control_gain() |
Checks control gain for the user controller |
set_joint_control_gain(kp, kv, kl2) |
Set the control gains for joint-level control |
get_joint_control_gain() |
Retrieve the current joint-level control gains |
set_task_control_gain(kp, kv, kl2) |
Set the control gains for task-level control |
get_task_control_gain() |
Retrieve the current task-level control gains |
set_impedance_control_gain(mass, damping, stiffness, kl2) |
Set the impedance control gains |
get_impedance_control_gain() |
Retrieve the current impedance control gains |
set_force_control_gain(kp, kv, kl2, mass, damping, stiffness, kpf, kif) |
Set the force control gains |
get_force_control_gain() |
Retrieve the current force control gains |
activate_sdk()
This function activates the IndySDK. The parameters are as follows:
license_key
: The issued license key.expire_date
: The expiration date of the license inYYYY-MM-DD
format.
It returns an SDKLicenseResp
object, which includes the following information:
activated
: A boolean value indicating the activation status.response
: A tuple(code, msg)
that may include the following values:0, 'Activated'
: The SDK is activated.1, 'Invalid'
: Invalid key or expiration date.2, 'No Internet Connection'
: Internet connection is required for license verification.3, 'Expired'
: The license has expired.4, 'HW_FAILURE'
: Hardware ID verification failed.
set_custom_control_mode()
This function sets the custom control mode. The parameters are as follows:
mode
:False (0)
: The default controller of IndyFramework is used.True (1)
: The components built by the user through IndySDK are used.
get_custom_control_mode()
This function checks the currently set custom control mode. It returns an object indicating the currently set mode.
set_custom_control_gain()
This function is used to set the gain for the user controller.
gain0
: gain0 for each jointgain1
: gain1 for each jointgain2
: gain2 for each jointgain3
: gain3 for each jointgain4
: gain4 for each jointgain5
: gain5 for each joint
Control gain variables are defined from gain0
to gain9
.
Note
Here, the variables from gain0
to gain9
are gRPC variables that can be called in IndySDK. For practical examples, please refer to the examples in the IndySDK repository.
get_custom_control_gain()
This function checks the current custom control gain settings.
{'gain0': [100.0, 100.0, 100.0, 100.0, 100.0, 100.0],
'gain1': [20.0, 20.0, 20.0, 20.0, 20.0, 20.0],
'gain2': [800.0, 800.0, 600.0, 400.0, 400.0, 400.0],
'gain3': [100.0, 100.0, 100.0, 100.0, 100.0, 100.0],
'gain4': [20.0, 20.0, 20.0, 20.0, 20.0, 20.0],
'gain5': [800.0, 800.0, 600.0, 400.0, 400.0, 400.0],
'gain6': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
'gain7': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
'gain8': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
'gain9': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]}
set_joint_control_gain(kp, kv, kl2)
Set the control gains for joint-level control.
kp
: Proportional gains for each joint.kv
: Velocity gains for each joint.kl2
: Second-order gains for each joint.
get_joint_control_gain()
Retrieve the current joint-level control gains.
set_task_control_gain(kp, kv, kl2)
Set the control gains for task-level control.
kp
: Proportional gains for each task coordinate.kv
: Velocity gains for each task coordinate.kl2
: Second-order gains for each task coordinate.
get_task_control_gain()
Retrieve the current task-level control gains.
set_impedance_control_gain(mass, damping, stiffness, kl2)
Set the impedance control gains.
mass
: Inertial gains for each task coordinate.damping
: Damping gains for each task coordinate.stiffness
: Stiffness gains for each task coordinate.kl2
: Second-order gains for each task coordinate.
get_impedance_control_gain()
Retrieve the current impedance control gains.
set_force_control_gain(kp, kv, kl2, mass, damping, stiffness, kpf, kif)
Set the force control gains.
kp
: Proportional gains for each joint or task coordinate.kv
: Velocity gains for each joint or task coordinate.kl2
: Second-order gains for each joint or task coordinate.mass
: Inertial gains for each task coordinate.damping
: Damping gains for each task coordinate.stiffness
: Stiffness gains for each task coordinate.kpf
: Proportional gains for force control.kif
: Integral gains for force control.
get_force_control_gain()
Retrieve the current force control gains.
Utility Functions
This section outlines essential utility functions to enhance workflow efficiency.
Function | Description |
---|---|
start_log() |
Starts realtime data logging |
end_log() |
Ends and saves realtime data logging |
wait_for_operation_state(op_state) |
Allows you to wait until the robot reaches a specific operation state. |
wait_for_motion_state(motion_state) |
Allows you to wait until the robot reaches a specific motion state. |
set_friction_comp_state(enable) |
Enable or disable friction compensation |
get_friction_comp_state() |
Retrieve the current state of friction compensation |
set_mount_pos(rot_y, rot_z) |
Set the mounting angles for the robot base |
get_mount_pos() |
Retrieve the current mounting angles for the robot base |
set_brakes(brake_state_list) |
Set the brake states for each motor |
set_servo_all(enable) |
Enable or disable all servos |
set_servo(index, enable) |
Enable or disable a specific servo by index |
set_endtool_led_dim(led_dim) |
Set the LED brightness for the end-effector tool |
execute_tool(name) |
Execute a tool function by its name |
get_el5001() |
Retrieve data from the EL5001 device |
get_el5101() |
Retrieve data from the EL5101 device |
get_brake_control_style() |
Retrieve the current brake control style |
set_conveyor_name(name) |
Set the name of the conveyor |
set_conveyor_encoder(encoder_type, channel1, channel2, sample_num, mm_per_tick, vel_const_mmps, reversed) |
Configure the conveyor encoder settings |
set_conveyor_trigger(trigger_type, channel, detect_rise) |
Set the conveyor trigger settings |
set_conveyor_offset(offset_mm) |
Set the offset value for the conveyor (in millimeters) |
set_conveyor_starting_pose(jpos, tpos) |
Set the starting joint and task poses for the conveyor |
set_conveyor_terminal_pose(jpos, tpos) |
Set the terminal joint and task poses for the conveyor |
start_log()
, end_log()
These two functions are used for realtime data logging.
Upon calling start_log()
, the robot's data is stored in memory. After a certain period, calling end_log()
stops the memory logging and writes it to a file within STEP.
The realtime data logging file can be found at the following path:
/home/user/release/IndyDeployments/RTlog/RTLog.csv
wait_for_operation_state(op_state)
For example, if you want to wait until the robot is in the IDLE state (where IDLE is defined as 5), you can call:
wait_for_motion_state(motion_state)
motion_state
:is_target_reached
is_in_motion
is_pausing
is_stopping
has_motion
For instance, if you want to wait until the robot's motion is complete, indicated by the state 'is_target_reached', you can call:
set_friction_comp_state(enable)
Enable or disable friction compensation.
enable
: A boolean value:True
: Enables friction compensation.False
: Disables friction compensation.
get_friction_comp_state()
Retrieve the current state of friction compensation.
set_mount_pos(rot_y, rot_z)
Set the mounting angles for the robot base.
rot_y
: Rotation angle around the Y-axis (in degrees).rot_z
: Rotation angle around the Z-axis (in degrees).
get_mount_pos()
Retrieve the current mounting angles for the robot base.
set_brakes(brake_state_list)
Set the brake states for each motor.
brake_state_list
: A list of boolean values representing the brake state for each motor:True
: Engage the brake.False
: Release the brake.
set_servo_all(enable)
Enable or disable all servos.
enable
: A boolean value:True
: Enable all servos.False
: Disable all servos.
set_servo(index, enable)
Enable or disable a specific servo by index.
index
: The index of the servo to enable or disable (integer).enable
: A boolean value:True
: Enable the specified servo.False
: Disable the specified servo.
set_endtool_led_dim(led_dim)
Set the LED brightness for the end-effector tool.
led_dim
: An integer value representing the LED brightness (0-255).0
: LED off.255
: Maximum brightness.
execute_tool(name)
Execute a tool function by its name.
name
: A string representing the name of the tool function to execute.
get_el5001()
Retrieve data from the EL5001 device.
get_el5101()
Retrieve data from the EL5101 device.
get_brake_control_style()
Retrieve the current brake control style.
set_conveyor_name(name)
Set the name of the conveyor.
name
: A string representing the name of the conveyor.
set_conveyor_encoder(encoder_type, channel1, channel2, sample_num, mm_per_tick, vel_const_mmps, reversed)
Configure the conveyor encoder settings.
encoder_type
: The type of the encoder.channel1
: The first channel of the encoder.channel2
: The second channel of the encoder.sample_num
: The number of samples to average for position measurement.mm_per_tick
: The number of millimeters per encoder tick.vel_const_mmps
: The constant velocity in millimeters per second.reversed
: A boolean to reverse the encoder direction.
set_conveyor_trigger(trigger_type, channel, detect_rise)
Set the conveyor trigger settings.
trigger_type
: The type of the trigger.channel
: The channel used for the trigger.detect_rise
: A boolean to detect a rising edge (True
) or falling edge (False
).
set_conveyor_offset(offset_mm)
Set the offset value for the conveyor in millimeters.
offset_mm
: The offset value in millimeters.
set_conveyor_starting_pose(jpos, tpos)
Set the starting joint and task poses for the conveyor.
jpos
: A list of joint positions for the starting pose.tpos
: A list of task positions for the starting pose.
set_conveyor_terminal_pose(jpos, tpos)
Set the terminal joint and task poses for the conveyor.
jpos
: A list of joint positions for the terminal pose.tpos
: A list of task positions for the terminal pose.