C#
November 4, 2024About 13 min
C#
This document introduces the data types and APIs defined in the JAKA SDK (C#). It is primarily intended for software developers creating robotic applications that communicate with virtual or real controllers using C#. It can also be helpful for users who want to understand JAKA robot controller applications.
API
Basic Operations of the Robot
int create_handler(char[] ip, ref int handle, bool use_grpc = false)
int create_handler([MarshalAs(UnmanagedType.LPStr)] string ip, ref int handle, bool use_grpc = false)
int destory_handler(ref int handle)
power on robot
int power_on(ref int handle)
power off robot
int power_off(ref int handle)
shutdown the control cabinet
int shut_down(ref int handle)
enable robot
int enable_robot(ref int handle)
disable robot
int disable_robot(ref int handle)
get robot dh parameters
int get_dh_param(ref int i,ref JKTYPE.DHParam offset)
set robot mounting angle
int set_installation_angle(ref int i, double angleX, double angleZ)
get robot mounting angle
int get_installation_angle(ref int i, ref JKTYPE.Quaternion quat, ref JKTYPE.Rpy appang)
get robot state
int get_robot_state(ref int handle, ref JKTYPE.RobotState state)
get robot status
int get_robot_status(ref int i, ref JKTYPE.RobotStatus status)
[get robot status]
int get_robot_status_simple(ref int i, ref JKTYPE.get_robot_status_simple status)
SDK
[set error handler]
int set_error_handler(ref int i, CallBackFuncType func)
get SDK version
int get_sdk_version(ref int i, StringBuilder version, int size)
Robot terminates automatically due to abnormal network
int set_network_exception_handle(ref int i, float millisecond, JKTYPE.ProcessType mnt)
get controller IP
int get_controller_ip(char[] controller_name, StringBuilder ip);
int get_controller_ip([MarshalAs(UnmanagedType.LPStr)] string controller_name, StringBuilder ip)
set errorcode file path
int set_errorcode_file_path(ref int i, StringBuilder path)
get the last error code
int get_last_error(ref int i, ref JKTYPE.ErrorCode code)
set debug mode
int set_debug_mode(ref int i, bool mode)
set SDK filepath
int set_SDK_filepath(ref int i, ref char[] filepath);
int set_SDK_filepath(ref int i, [MarshalAs(UnmanagedType.LPStr)] string filepath)
get SDK filepath
int get_SDK_filepath(char[] path, int size);
int get_SDK_filepath(StringBuilder path, int size)
Robot Motions
JOG
int jog(ref int handle, int aj_num, JKTYPE.MoveMode move_mode, JKTYPE.CoordType coord_type, double vel_cmd, double pos_cmd)
JOG stop
int jog_stop(ref int handle, int num)
robot joint move
int joint_move(ref int handle, ref JKTYPE.JointValue joint_pos, JKTYPE.MoveMode move_mode, bool is_block, double speed)
robot joint move
int joint_move_extend(ref int i, ref JKTYPE.JointValue joint_pos, JKTYPE.MoveMode move_mode, bool is_block, double speed, double acc, double tol, ref JKTYPE.OptionalCond option_cond)
robot end linear move
int linear_move(ref int handle, ref JKTYPE.CartesianPose end_pos, JKTYPE.MoveMode move_mode, bool is_block, double speed)
robot end linear move
int linear_move_extend(ref int i, ref JKTYPE.CartesianPose cart_pos, JKTYPE.MoveMode move_mode, bool is_block, double speed, double acc, double tol, ref JKTYPE.OptionalCond option_cond)
robot end linear move
int linear_move_extend_ori(ref int i, ref JKTYPE.CartesianPose cart_pos, JKTYPE.MoveMode move_mode, bool is_block, double speed, double acc, double tol, ref JKTYPE.OptionalCond option_cond, double ori_vel, double ori_acc)
robot circular move
int circular_move(ref int i, ref JKTYPE.CartesianPose end_pos, ref JKTYPE.CartesianPose mid_pos, JKTYPE.MoveMode move_mode, bool is_block, double speed, double acc, double tol, ref JKTYPE.OptionalCond option_cond)
robot circular move
int circular_move_extend(ref int i, ref JKTYPE.CartesianPose end_pos, ref JKTYPE.CartesianPose mid_pos, JKTYPE.MoveMode move_mode, bool is_block, double speed, double acc, double tol, ref JKTYPE.OptionalCond option_cond, double circle_cnt)
robot circular move
int circular_move_extend_mode(ref int i, ref JKTYPE.CartesianPose end_pos, ref JKTYPE.CartesianPose mid_pos, JKTYPE.MoveMode move_mode, bool is_block, double speed, double acc, double tol, ref JKTYPE.OptionalCond option_cond, double circle_cnt, int circle_mode)
set rapid rate
int set_rapidrate(ref int handle, double rapid_rate)
get rapid rate
int get_rapidrate(ref int handle, ref double rapid_rate)
set tool data
int set_tool_data(ref int handle, int id, ref JKTYPE.CartesianPose tcp, char[] name);
int set_tool_data(ref int handle, int id, ref JKTYPE.CartesianPose tcp, [MarshalAs(UnmanagedType.LPStr)] string name)
get tool data
int get_tool_data(ref int handle, int id, ref JKTYPE.CartesianPose tcp)
set tool ID
int set_tool_id(ref int handle, int id)
get tool ID
int get_tool_id(ref int handle, ref int id)
set user coordinate system parameter
int set_user_frame_data(ref int handle, int id, ref JKTYPE.CartesianPose user_frame, char[] name);
int set_user_frame_data(ref int handle, int id, ref JKTYPE.CartesianPose user_frame, [MarshalAs(UnmanagedType.LPStr)] string name)
get user coordinate system parameter
int get_user_frame_data(ref int handle, int id, ref JKTYPE.CartesianPose user_frame)
set user coordinate system ID
int set_user_frame_id(ref int handle, int id)
get user coordinate system ID
int get_user_frame_id(ref int handle, ref int id)
enable or disable drag mode
int drag_mode_enable(ref int handle, bool enable)
interrogate whether in drag mode
int is_in_drag_mode(ref int handle, ref bool in_drag)
get TCP position
int get_tcp_position(ref int handle, ref JKTYPE.CartesianPose tcp_position)
[get joint position]
int get_joint_position(ref int handle, ref JKTYPE.JointValue joint_position)
Whether on limit
int is_on_limit(ref int handle, ref bool on_limit)
Whether in position
int is_in_pos(ref int handle, ref bool in_pos)
[set motion planner]
int set_motion_planner(ref int i, int type)
motion abort
int motion_abort()
set payload
int set_payload(ref int handle, ref JKTYPE.PayLoad payload)
get payload
int get_payload(ref int handle, ref JKTYPE.PayLoad payload)
IO
set digital output variables
int set_digital_output(ref int handle, JKTYPE.IOType type, int index, bool value)
set analog output variables
int set_analog_output(ref int handle, JKTYPE.IOType type, int index, float value)
get digital input status
int get_digital_input(ref int handle, JKTYPE.IOType type, int index, ref bool result)
get digital output status
int get_digital_output(ref int handle, JKTYPE.IOType type, int index, ref bool result)
get analog input variables
int get_analog_input(ref int handle, JKTYPE.IOType type, int index, ref float result)
get analog output variables
int get_analog_output(ref int handle, JKTYPE.IOType type, int index, ref float result)
interrogate whether extension IO in running status
int is_extio_running(ref int handle, ref bool is_running)
TIO
set TIO V3 voltage parameters
int set_tio_vout_param(ref int i, int vout_enable,int vout_vol)
get TIO V3 voltage parameters
int get_tio_vout_param(ref int i,ref int vout_enable,ref int vout_vol)
TIO add or modify semaphore
int add_tio_rs_signal(ref int i, JKTYPE.SignInfo sign_info)
TIO delete semaphore
int del_tio_rs_signal(ref int i, char[] sig_name);
int del_tio_rs_signal(ref int i, [MarshalAs(UnmanagedType.LPStr)] string sig_name)
TIO RS485 send command
int send_tio_rs_command(ref int i, int chn_id, byte[] data, int buffsize)
TIO get semaphore information
int get_rs485_signal_info(ref int i, [In, Out] JKTYPE.SignInfo[] sign_info, ref int size)
TIO set mode
int set_tio_pin_mode(ref int i, int pin_type, int pin_mode)
TIO get mode
int get_tio_pin_mode(ref int i, int pin_type, ref int pin_mode)
TIO RS485 communication parameter configuration
int set_rs485_chn_comm(ref int i, JKTYPE.ModRtuComm mod_rtu_com)
TIO RS485 communication parameter query
int get_rs485_chn_comm(ref int i, ref JKTYPE.ModRtuComm mod_rtu_com)
TIO RS485 communication mode configuration
int set_rs485_chn_mode(ref int i, int chn_id, int chn_mode)
TIO RS485 communication mode query
int get_rs485_chn_mode(ref int handle, int chn_id, ref int chn_mode)
Servo
robot servo move control mode
int servo_move_enable(ref int handle, bool enable)
robot joint servo move
int servo_j(ref int handle, ref JKTYPE.JointValue joint_pos, JKTYPE.MoveMode move_mode, int step_num)
robot Cartesian servo move
int servo_p(ref int handle, ref JKTYPE.CartesianPose cartesian_pose, JKTYPE.MoveMode move_mode, int step_num)
none filters in SERVO mode
int servo_move_use_none_filter(ref int i)
use joint first-order low pass filter in SERVO mode
int servo_move_use_joint_LPF(ref int i, double cutoffFreq)
use joint nonlinear filter in SERVO mode
int servo_move_use_joint_NLF(ref int i, double max_vr, double max_ar, double max_jr)
use Cartesian nonlinear filter in SERVO mode
int servo_move_use_carte_NLF(ref int i, double max_vp, double max_ap, double max_jp, double max_vr, double max_ar, double max_jr)
use joint multi-order mean filter in SERVO mode
int servo_move_use_joint_MMF(ref int i, int max_buf, double kp, double kv, double ka)
set speed foresight parameter under robot servo mode
int servo_speed_foresight(ref int i, int max_buf, double kp)
Trajectory
set trajectory track configuration parameters
int set_traj_config(ref int i, ref JKTYPE.TrajTrackPara para)
get trajectory track configuration parameters
int get_traj_config(ref int i, ref JKTYPE.TrajTrackPara para)
set trajectory sample mode
int set_traj_sample_mode(ref int i, bool mode, char[] filename);
int set_traj_sample_mode(ref int i, bool mode, [MarshalAs(UnmanagedType.LPStr)] string filename)
get trajectory sample status
int get_traj_sample_status(ref int i, ref bool sample_statuse)
get exist trajectory file name
int get_exist_traj_file_name(ref int i, ref JKTYPE.MultStrStorType filename)
rename exist trajectory file name
int rename_traj_file_name(ref int i, ref char[] src, ref char[] dest);
int rename_traj_file_name(ref int i, [MarshalAs(UnmanagedType.LPStr)] string src, [MarshalAs(UnmanagedType.LPStr)] string dest)
remove the trajectory file in the controller
int remove_traj_file(ref int i, ref char[] filename);
int remove_traj_file(ref int i, [MarshalAs(UnmanagedType.LPStr)] string filename)
generate the trajectory execution script
int generate_traj_exe_file(ref int i, char[] filename);
int generate_traj_exe_file(ref int i, [MarshalAs(UnmanagedType.LPStr)] string filename)
Program
run the loaded program
int program_run(ref int handle)
pause the running program
int program_pause(ref int handle)
resume program
int program_resume(ref int handle)
abort program
int program_abort(ref int handle)
load the specified program
int program_load(ref int handle, char[] file);
int program_load(ref int handle, [MarshalAs(UnmanagedType.LPStr)] string file)
get the loaded program
int get_loaded_program(ref int handle, StringBuilder file, 100)
get current line
int get_current_line(ref int handle, ref int curr_line)
[get program state]
int get_program_state(ref int handle, ref JKTYPE.ProgramState status)
[get program info]
int get_program_info(ref int handle, ref JKTYPE.ProgramInfo info)
get user variables
int get_user_var(ref int handle, ref JKTYPE.UserVariableList vlist)
set user variables
int set_user_var(ref int handle, ref JKTYPE.UserVariable v)
FTP
initialize FTP client
int init_ftp_client(ref int i)
close FTP client
int close_ftp_client(ref int i)
FTP download
int download_file(ref int i, char[] local, char[] remote, int opt);
int download_file(ref int i, [MarshalAs(UnmanagedType.LPStr)] string local, [MarshalAs(UnmanagedType.LPStr)] string remote, int opt)
FTP upload
int upload_file(ref int i, char[] local, char[] remote, int opt);
int upload_file(ref int i, [MarshalAs(UnmanagedType.LPStr)] string local, [MarshalAs(UnmanagedType.LPStr)] string remote, int opt)
delete FTP
int del_ftp_file(ref int i, char[] remote, int opt);
int del_ftp_file(ref int i, [MarshalAs(UnmanagedType.LPStr)] string remote, int opt)
rename FTP
int rename_ftp_file(ref int i, char[] remote, char[] des, int opt);
int rename_ftp_file(ref int i, [MarshalAs(UnmanagedType.LPStr)] string remote, [MarshalAs(UnmanagedType.LPStr)] string des, int opt)
interrogate FTP directory
int get_ftp_dir(ref int i, char[] remote, int type, StringBuilder ret );
int get_ftp_dir(ref int i, [MarshalAs(UnmanagedType.LPStr)] string remote, int type, StringBuilder ret )
Torque Sensor
[set torque sensor brand]
int set_torsenosr_brand(ref int handle, int sensor_brand)
[get torque sensor brand]
int get_torsenosr_brand(ref int handle, ref int sensor_brand)
turn on/off force torque sensor
int set_torque_sensor_mode(ref int handle, int sensor_mode)
[get torque sensor mode]
int get_torque_sensor_mode(ref int handle, ref int sensor_mode)
set sensor communication parameter
int set_torque_sensor_comm(ref int handle, int type, ref char[] ip_addr, int port);
int set_torque_sensor_comm(ref int handle, int type, [MarshalAs(UnmanagedType.LPStr)] string ip_addr, int port)
get sensor communication parameter
int get_torque_sensor_comm(ref int handle, ref int type, [MarshalAs(UnmanagedType.LPStr)] StringBuilder ip_addr, ref int port)
set low-pass filter parameters for force control
int set_torque_sensor_filter(ref int handle, float torque_sensor_filter)
obtain low-pass filter parameters for force control
int get_torque_sensor_filter(ref int handle, ref float torque_sensor_filter)
set the sensor limit parameter configuration for force sensors
int set_torque_sensor_soft_limit(ref int handle, JKTYPE.FTxyz torque_sensor_soft_limit)
get the sensor limit parameter configuration for force sensors
int get_torque_sensor_soft_limit(ref int handle, ref JKTYPE.FTxyz torque_sensor_soft_limit)
[get torque sensor data]
int get_torque_sensor_data(ref int handle, int type, ref JKTYPE.TorqSensorData)
zero calibration of force sensors
int zero_end_sensor(ref int handle)
set force control speed limit
int set_compliant_speed_limit(ref int handle, double vel, double angular_vel)
get force control speed limit
int get_compliant_speed_limit(ref int handle, ref double vel, ref double angular_vel)
set torque reference center
int set_torque_ref_point(ref int handle, int refPoint)
get torque reference center
int get_torque_ref_point(ref int handle, ref int refPoint)
set end sensor sensitivity
int set_end_sensor_sensitivity_threshold(ref int handle, JKTYPE.FTxyz)
get end sensor sensitivity
int get_end_sensor_sensitivity_threshold(ref int handle, ref JKTYPE.FTxyz)
[set force stop condition for motion commands]
int set_force_stop_condition(ref int handle, ref JKTYPE.ForceStopConditionList)
Payload
identify tool end payload
int start_torq_sensor_payload_identify(ref int i, ref JKTYPE.JointValue joint_pos)
get end payload identification state
int get_torq_sensor_identify_status(ref int i, ref int identify_status)
get end payload identification result
int get_torq_sensor_payload_identify_result(ref int i, ref JKTYPE.PayLoad payload)
set sensor end payload
int set_torq_sensor_tool_payload(ref int i, ref JKTYPE.PayLoad payload)
get sensor end payload
int get_torq_sensor_tool_payload(ref int i, ref JKTYPE.PayLoad payload)
Tool Drive
get force control compliance parameter
int get_admit_ctrl_config(ref int handle, ref JKTYPE.RobotAdmitCtrl admit_ctrl_cfg)
[set force control compliance parameter]
int set_admit_ctrl_config(ref int handle, int axis, int opt, double ftUser, double ftConstant, int ftNnormalTrack, double ftReboundFK)
enable force-control admittance control
int enable_admittance_ctrl(ref int handle, int enable_flag)
[set the force sensor’s drag state]
int enable_tool_drive(ref int handle, int enable_flag)
get the force sensor’s drag state
int get_tool_drive_state(ref int handle, ref int enable_flag, ref int state)
[get the force sensor’s drag config]
int get_tool_drive_config(ref int handle, ref JKTYPE.RobotToolDriveCtrl)
[set the force sensor’s drag config]
int set_tool_drive_config(ref int handle, JKTYPE.ToolDriveConfig)
get the force sensor’s coordinate system in drag mode
int get_tool_drive_frame(ref int handle, ref JKTYPE.FTFrameType)
set the force sensor’s coordinate system in drag mode
int set_tool_drive_frame(ref int handle, JKTYPE.FTFrameType)
get fusion drive sensitivity
int get_fusion_drive_sensitivity_level(ref int handle, ref int level)
set fusion drive sensitivity
int set_fusion_drive_sensitivity_level(ref int handle, int level)
get motion limit (singularity and joint limit) warning range
int get_motion_limit_warning_range(ref int handle, ref int warning_range)
set motion limit (singularity and joint limit) warning range
int set_motion_limit_warning_range(ref int handle, int warning_range)
Force Control
set coordinate frame of admittance control
int set_ft_ctrl_frame(ref int i, int ftFrame)
get coordinate frame of admittance control
int get_ft_ctrl_frame(ref int i,ref int ftFrame)
set force control type and sensor initial state
int set_compliant_type(ref int i, int sensor_compensation, int compliance_type)
get force control type and sensor initial state
int get_compliant_type(ref int i, ref int sensor_compensation, ref int compliance_type)
set compliance control torque condition
int set_compliance_condition(ref int i, ref JKTYPE.FTxyz ft)
[set approach speed limit]
int set_approach_speed_limit(ref int i, double vel, double angularVel)
[get approach speed limit]
int get_approach_speed_limit(ref int i, ref double vel, ref double angularVel)
[set force control tolerance]
int set_ft_tolerance(ref int i, double force, double torque)
[get force control tolerance]
int get_ft_tolerance(ref int i, ref double force, ref double torque)
[set force control mode]
int set_ft_ctrl_mode(ref int i, int mode)
[get force control mode]
int get_ft_ctrl_mode(ref int i,ref int mode)
[set force control config]
int set_ft_ctrl_config(ref int i, AdmitCtrlType cfg)
[get force control config]
int get_ft_ctrl_config(ref int i,ref RobotAdmitCtrl cfg)
Collision
interrogate whether in collision protection mode
int is_in_collision(ref int handle, ref bool in_collision)
collision recover
int collision_recover(ref int handle)
set collision level
int set_collision_level(ref int handle, int level)
get collision level
int get_collision_level(ref int handle, ref int level)
Kinematics
kine inverse
int kine_inverse(ref int handle, ref JKTYPE.JointValue ref_pos, ref JKTYPE.CartesianPose cartesian_pose, ref JKTYPE.JointValue joint_pos)
kine forward
int kine_forward(ref int handle, ref JKTYPE.JointValue joint_pos, ref JKTYPE.CartesianPose cartesian_pose)
rpy to rotation matrix
int rpy_to_rot_matrix(ref int handle, ref JKTYPE.Rpy rpy, ref JKTYPE.RotMatrix rot_matrix)
rotation matrix to rpy
int rot_matrix_to_rpy(ref int handle, ref JKTYPE.RotMatrix rot_matrix, ref JKTYPE.Rpy rpy)
quaternion to rotation matrix
int quaternion_to_rot_matrix(ref int handle, ref JKTYPE.Quaternion quaternion, ref JKTYPE.RotMatrix rot_matrix)
rotation matrix to quaternion
int rot_matrix_to_quaternion(ref int handle, ref JKTYPE.RotMatrix rot_matrix, ref JKTYPE.Quaternion quaternion)
List of Interface Call Return Values and Troubleshooting
Error Code | Description | Suggested Action |
---|---|---|
0 | success | No action needed. |
2 | Interface error or controller not supported | Verify controller and SDK versions; consider upgrading or using another interface. |
-1 | Invalid handler | Ensure you call the login interface before using it. |
-2 | Invalid parameter | Check if the parameters are correct. |
-3 | Fail to connect | Verify network status or ensure the robot IP is correct. |
-4 | Kinematic inverse error | Check the current coordinate system or reference joint angles for validity. |
-5 | Emergency stop | E-stop status; reserved state. |
-6 | Not powered on | Power the robot. |
-7 | Not enabled | Enable the robot. |
-8 | Not in servo mode | Ensure servo mode is enabled before calling servoJP . |
-9 | Must turn off enable before power off | Disable before powering off. |
-10 | Cannot operate, program is running | Stop the running program first. |
-11 | Cannot open file, or file doesn't exist | Check if the file exists or can be accessed. |
-12 | Motion abnormal | Check for singularities or movements exceeding robot limits. |
-14 | FTP error | Investigate FTP connection issues. |
-15 | Socket message or value oversize | Ensure parameters are within acceptable limits. |
-16 | Kinematic forward error | Verify inputs for forward kinematics. |
-17 | Not support empty folder | Avoid using empty folders. |
-20 | Protective stop | Investigate and address protective stop conditions. |
-21 | Emergency stop | Check and reset the emergency stop. |
-22 | On soft limit | Use the teaching feature in the robot app to exit soft limits. |
-30 | Fail to encode command string | Likely an error in parsing controller messages. |
-31 | Fail to decode command string | Check for errors in controller message parsing. |
-32 | Fail to uncompress port 10004 string | Possible network fluctuation or data overflow. |
-40 | Move linear error | Verify the path avoids singularity regions. |
-41 | Move joint error | Ensure joint angles are valid. |
-42 | Move circular error | Check the circular motion parameters. |
-50 | Block wait timeout | Verify and increase wait timeout if needed. |
-51 | Power on timeout | Check the power-on process. |
-52 | Power off timeout | Check the power-off process. |
-53 | Enable timeout | Review the enabling process. |
-54 | Disable timeout | Review the disabling process. |
-55 | Set user frame timeout | Check the user frame settings. |
-56 | Set tool timeout | Verify the tool coordinate settings. |
-60 | Set IO timeout | Ensure IO configurations are correct. |
Feedback
For any inaccurate descriptions or errors in the document, we would like to invite the readers to correct and criticize. In case of any questions during your reading or any comments you want to make, please send an email to <support@jaka.com,> and our colleagues will reply.