Skip to main content

C

JAKAAbout 12 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++/C. It can also be helpful for users who want to understand JAKA robot controller applications.

API

Basic Operations of the Robot

errno_t create_handler(const char *ip, JKHD *handle, BOOL use_grpc)

errno_t destory_handler(const JKHD *handle)

power on robot

errno_t power_on(const JKHD *handle)

power off robot

errno_t power_off(const JKHD *handle)

shutdown the control cabinet

errno_t shut_down(const JKHD *handle)

enable robot

errno_t enable_robot(const JKHD *handle)

disable robot

errno_t disable_robot(const JKHD *handle)

get robot dh parameters

errno_t get_dh_param(const JKHD *handle, DHParam *dhParam)

set robot mounting angle

errno_t set_installation_angle(const JKHD* handle, double angleX, double angleZ)

get robot mounting angle

errno_t get_installation_angle(const JKHD* handle, Quaternion* quat, Rpy* appang)

get robot state

errno_t get_robot_state(const JKHD *handle, RobotState *state)

get robot status

errno_t get_robot_status(const JKHD *handle, RobotStatus *status)

get robot status simple

errno_t get_robot_status_simple(const JKHD *handle, RobotStatus_simple *status)

SDK

set error handler

errno_t set_error_handler(const JKHD *handle, CallBackFuncType func)

get SDK version

errno_t get_sdk_version(const JKHD *handle, char *version)

Robot terminates automatically due to abnormal network

errno_t set_network_exception_handle(const JKHD *handle, float millisecond, ProcessType mnt)

get controller IP

errno_t get_controller_ip(char *controller_name, char *ip_list)

set errorcode file path

errno_t set_errorcode_file_path(const JKHD *handle, char *path)

get the last error code

errno_t get_last_error(const JKHD *handle, ErrorCode *code)

set debug mode

errno_t set_debug_mode(const JKHD *handle, BOOL mode)

set SDK filepath

errno_t set_SDK_filepath(const JKHD *handle, char *filepath)

get SDK filepath

errno_t get_SDK_filepath(const JKHD *handle, char *filepath, int size)

Robot Motions

JOG

errno_t jog(const JKHD *handle, int aj_num, MoveMode move_mode, CoordType coord_type, double vel_cmd, double pos_cmd)

JOG stop

errno_t jog_stop(const JKHD *handle, int num)

robot joint move

errno_t joint_move(const JKHD *handle, const JointValue *joint_pos, MoveMode move_mode, BOOL is_block, double speed)

robot joint move

errno_t joint_move_extend(const JKHD *handle, const JointValue *joint_pos, MoveMode move_mode, BOOL is_block, double speed, double acc, double tol, const OptionalCond *option_cond)

robot end linear move

errno_t linear_move(const JKHD *handle, const CartesianPose *end_pos, MoveMode move_mode, BOOL is_block, double speed)

robot end linear move

errno_t linear_move_extend_ori(const JKHD *handle, const CartesianPose *end_pos, MoveMode move_mode, BOOL is_block, double speed, double accel, double tol, const OptionalCond *option_cond, double ori_vel, double ori_acc)

robot circular move

errno_t circular_move(const JKHD *handle, const CartesianPose *end_pos, const CartesianPose *mid_pos, MoveMode move_mode, BOOL is_block, double speed, double accel, double tol, const OptionalCond *option_cond)

robot circular move

errno_t circular_move_extend(const JKHD *handle, const CartesianPose *end_pos, const CartesianPose *mid_pos, MoveMode move_mode, BOOL is_block, double speed, double accel, double tol, const OptionalCond *option_cond, double circle_cnt)

robot circular move

errno_t circular_move_extend_mode(const JKHD *handle, const CartesianPose *end_pos, const CartesianPose *mid_pos, MoveMode move_mode, BOOL is_block, double speed, double accel, double tol, const OptionalCond *option_cond, double circle_cnt, int circle_mode)

set rapid rate

errno_t set_rapidrate(const JKHD *handle, double rapid_rate)

get rapid rate

errno_t get_rapidrate(const JKHD *handle, double *rapid_rate)

set tool data

errno_t set_tool_data(const JKHD *handle, int id, const CartesianPose *tcp, const char *name)

get tool data

errno_t get_tool_data(const JKHD *handle, int id, CartesianPose *tcp)

set tool ID

errno_t set_tool_id(const JKHD *handle, const int id)

get tool ID

errno_t get_tool_id(const JKHD *handle, int *id)

set user coordinate system parameter

errno_t set_user_frame_data(const JKHD *handle, int id, const CartesianPose *user_frame, const char *name)

get user coordinate system parameter

errno_t get_user_frame_data(const JKHD *handle, int id, CartesianPose *user_frame)

set user coordinate system ID

errno_t set_user_frame_id(const JKHD *handle, const int id)

get user coordinate system ID

errno_t get_user_frame_id(const JKHD *handle, int *id)

enable or disable drag mode

errno_t drag_mode_enable(const JKHD *handle, BOOL enable)

interrogate whether in drag mode

errno_t is_in_drag_mode(const JKHD *handle, BOOL *in_drag)

get TCP position

errno_t get_tcp_position(const JKHD *handle, CartesianPose *tcp_position)

Whether on limit

errno_t is_on_limit(const JKHD *handle, BOOL *on_limit)

Whether in position

errno_t is_in_pos(const JKHD *handle, BOOL *in_pos)

[set planner type]

errno_t set_motion_planner(const JKHD* handle, MotionPlannerType type)

motion abort

errno_t motion_abort(const JKHD *handle)

set payload

errno_t set_payload(const JKHD *handle, const PayLoad *payload)

get payload

errno_t get_payload(const JKHD *handle, PayLoad *payload)

IO

set digital output variables

errno_t set_digital_output(const JKHD *handle, IOType type, int index, BOOL value)

set analog output variables

errno_t set_analog_output(const JKHD *handle, IOType type, int index, float value)

get digital input status

errno_t get_digital_input(const JKHD *handle, IOType type, int index, BOOL *result)

get digital output status

errno_t get_digital_output(const JKHD *handle, IOType type, int index, BOOL *result)

get analog input variables

errno_t get_analog_input(const JKHD *handle, IOType type, int index, float *result)

get analog output variables

errno_t get_analog_output(const JKHD *handle, IOType type, int index, float *result)

interrogate whether extension IO in running status

errno_t is_extio_running(const JKHD *handle, BOOL *is_running)

TIO

set TIO V3 voltage parameters

errno_t set_tio_vout_param(const JKHD* handle, int vout_enable, int vout_vol)

get TIO V3 voltage parameters

errno_t get_tio_vout_param(const JKHD* handle, int* vout_enable, int* vout_vol)

TIO add or modify semaphore

errno_t add_tio_rs_signal(const JKHD* handle, SignInfo sign_info)

TIO delete semaphore

errno_t del_tio_rs_signal(const JKHD* handle, const char* sig_name)

TIO RS485 send command

errno_t send_tio_rs_command(const JKHD* handle, int chn_id, uint8_t* cmdbuf, int bufsize)

TIO get semaphore information

errno_t get_rs485_signal_info(const JKHD* handle, SignInfo* sign_info_array, int *array_len)

TIO set mode

errno_t set_tio_pin_mode(const JKHD* handle, int pin_type, int pin_mode)

TIO get mode

errno_t get_tio_pin_mode(const JKHD* handle, int pin_type, int* pin_mode)

TIO RS485 communication parameter configuration

errno_t set_rs485_chn_comm(const JKHD* handle, ModRtuComm mod_rtu_com)

TIO RS485 communication parameter query

errno_t get_rs485_chn_comm(const JKHD* handle, ModRtuComm* mod_rtu_com)

TIO RS485 communication mode configuration

errno_t set_rs485_chn_mode(const JKHD* handle, int chn_id, int chn_mode)

TIO RS485 communication mode query

errno_t get_rs485_chn_mode(const JKHD* handle, int chn_id, int* chn_mode)

Servo

robot servo move control mode

errno_t servo_move_enable(const JKHD *handle, BOOL enable)

robot joint servo move

errno_t servo_j(const JKHD *handle, const JointValue *joint_pos, MoveMode move_mode)

robot Cartesian servo move

errno_t servo_p(const JKHD *handle, const CartesianPose *cartesian_pose, MoveMode move_mode)

none filters in SERVO mode

errno_t servo_move_use_none_filter(const JKHD *handle)

use joint first-order low pass filter in SERVO mode

errno_t servo_move_use_joint_LPF(const JKHD *handle, double cutoffFreq)

use joint nonlinear filter in SERVO mode

errno_t servo_move_use_joint_NLF(const JKHD *handle, double max_vr, double max_ar, double max_jr)

use Cartesian nonlinear filter in SERVO mode

errno_t servo_move_use_carte_NLF(const JKHD *handle, 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

errno_t servo_move_use_joint_MMF(const JKHD *handle, int max_buf, double kp, double kv, double ka)

set speed foresight parameter under robot servo mode

errno_t servo_speed_foresight(const JKHD *handle, int max_buf, double kp)

Trajectory

set trajectory track configuration parameters

errno_t set_traj_config(const JKHD *handle, const TrajTrackPara *para)

set trajectory sample mode

errno_t set_traj_sample_mode(const JKHD *handle, const BOOL mode, char *filename)

get trajectory track configuration parameters

errno_t get_traj_config(const JKHD *handle, TrajTrackPara *para)

get trajectory sample status

errno_t get_traj_sample_status(const JKHD *handle, BOOL *sample_status)

get exist trajectory file name

errno_t get_exist_traj_file_name(const JKHD *handle, MultStrStorType *filename)

rename exist trajectory file name

errno_t rename_traj_file_name(const JKHD *handle, const char *src, const char *dest)

remove the trajectory file in the controller

errno_t remove_traj_file(const JKHD *handle, const char *filename)

generate the trajectory execution script

errno_t generate_traj_exe_file(const JKHD *handle, const char *filename)

Program

run the loaded program

errno_t program_run(const JKHD *handle)

pause the running program

errno_t program_pause(const JKHD *handle)

resume program

errno_t program_resume(const JKHD *handle)

abort program

errno_t program_abort(const JKHD *handle)

load the specified program

errno_t program_load(const JKHD *handle, const char *file)

[get program state]

errno_t get_program_state(const JKHD *handle, ProgramState *status)

[get program info]

errno_t get_program_info(const JKHD *handle, ProgramInfo* info)

get the loaded program

errno_t get_loaded_program(const JKHD *handle, char *file)

get current line

errno_t get_current_line(const JKHD *handle, int *curr_line)

get user variables

errno_t get_user_var(const JKHD *handle, UserVariableList* vlist)

set user variables

errno_t set_user_var(const JKHD *handle, UserVariable v)

FTP

initialize FTP client

errno_t init_ftp_client(const JKHD *handle)

close FTP client

errno_t close_ftp_client(const JKHD *handle)

FTP download

errno_t download_file(const JKHD *handle, char *local, char *remote, int opt)

FTP upload

errno_t upload_file(const JKHD *handle, char *local, char *remote, int opt)

delete FTP

errno_t del_ftp_file(const JKHD *handle, char *remote, int opt)

rename FTP

errno_t rename_ftp_file(const JKHD *handle, char *remote, char *des, int opt)

interrogate FTP directory

errno_t get_ftp_dir(const JKHD *handle, const char *remotedir, int type, char *ret)

Torque Sensor

turn on/off force torque sensor

errno_t set_torque_sensor_mode(const JKHD *handle, int sensor_mode)

set sensor communication parameter

errno_t set_torque_sensor_comm(const JKHD *handle, const int type, const char *ip_addr, const int port)

get sensor communication parameter

errno_t get_torque_sensor_comm(const JKHD *handle, int *type, char *ip_addr, int *port)

set low-pass filter parameters for force control

errno_t set_torque_sensor_filter(const JKHD *handle, const float torque_sensor_filter)

obtain low-pass filter parameters for force control

errno_t get_torque_sensor_filter(const JKHD *handle, float *torque_sensor_filter)

set the sensor limit parameter configuration for force sensors

errno_t set_torque_sensor_soft_limit(const JKHD *handle, const FTxyz torque_sensor_soft_limit)

get the sensor limit parameter configuration for force sensors

errno_t get_torque_sensor_soft_limit(const JKHD *handle, FTxyz *torque_sensor_soft_limit)

[get torque sensor feedback data]

errno_t get_torque_sensor_data(const JKHD *handle, int type, TorqSensorData* data)

zero calibration of force sensors

errno_t zero_end_sensor(const JKHD *handle)

set force control speed limit

errno_t set_compliant_speed_limit(const JKHD *handle, double speed_limit, double angular_speed_limit)

get force control speed limit

errno_t get_compliant_speed_limit(const JKHD *handle, double* speed_limit, double* angular_speed_limitangularVel)

set force control type and sensor initial state

errno_t set_compliant_type(const JKHD *handle, int sensor_compensation, int compliance_type)

get force control type and sensor initial state

errno_t get_compliant_type(const JKHD *handle, int *sensor_compensation, int *compliance_type)

set velocity compliance control parameter

errno_t set_vel_compliant_ctrl(const JKHD *handle, const VelCom *vel)

set torque reference center

errno_t set_torque_ref_point(const JKHD *handle, int ref_point)

get torque reference center

errno_t get_torque_ref_point(const JKHD *handle, int *ref_point)

set end sensor sensitivity

errno_t set_end_sensor_sensitivity_threshold(const JKHD *handle, FTxyz threshold)

get end sensor sensitivity

errno_t get_end_sensor_sensitivity_threshold(const JKHD *handle, FTxyz *threshold)

[set force stop condition for motion commands]

errno_t set_force_stop_condition(const JKHD *handle, ForceStopConditionList condition)

Payload

identify tool end payload

errno_t start_torq_sensor_payload_identify(const JKHD *handle, const JointValue *joint_pos)

get end payload identification state

errno_t get_torq_sensor_identify_staus(const JKHD *handle, int *identify_status)

get end payload identification result

errno_t get_torq_sensor_payload_identify_result(const JKHD *handle, PayLoad *payload)

set sensor end payload

errno_t set_torq_sensor_tool_payload(const JKHD *handle, const PayLoad *payload)

get sensor end payload

errno_t get_torq_sensor_tool_payload(const JKHD *handle, PayLoad *payload)

Tool Drive

get force control compliance parameter

errno_t get_admit_ctrl_config(const JKHD *handle, RobotAdmitCtrl *admit_ctrl_cfg)

enable force-control admittance control

errno_t enable_admittance_ctrl(const JKHD *handle, const int enable_flag)

[enable tool drive(force sensor’s drag)]

errno_t enable_tool_drive(const JKHD *handle, const int enable_flag)

get the force sensor’s drag state

errno_t get_tool_drive_state(const JKHD *handle, int* enable, int *state)

[get tool drive config]

errno_t get_tool_drive_config(const JKHD *handle, RobotToolDriveCtrl* cfg)

[set tool drive config]

errno_t set_tool_drive_config(const JKHD *handle, ToolDriveConfig cfg)

get the force sensor’s coordinate system in drag mode

errno_t get_tool_drive_frame(const JKHD *handle, FTFrameType *ftFrame)

set the force sensor’s coordinate system in drag mode

errno_t set_tool_drive_frame(const JKHD *handle, FTFrameType ftFrame)

get fusion drive sensitivity

errno_t get_fusion_drive_sensitivity_level(const JKHD *handle, int *level)

set fusion drive sensitivity

errno_t set_fusion_drive_sensitivity_level(const JKHD *handle, int level)

get motion limit (singularity and joint limit) warning range

errno_t get_motion_limit_warning_range(const JKHD *handle, int *warning_range)

set motion limit (singularity and joint limit) warning range

errno_t set_motion_limit_warning_range(const JKHD *handle, int warning_range)

Force Control

set coordinate frame of admittance control

errno_t set_ft_ctrl_frame(const JKHD *handle, const int ftFrame)

get coordinate frame of admittance control

errno_t get_ft_ctrl_frame(const JKHD *handle, int *ftFrame)

[set admittance control tolerance]

errno_t set_ft_tolerance(const JKHD *handle, double force, double torque)

[get admittance control tolerance]

errno_t get_ft_tolerance(const JKHD *handle, double* force, double* torque)

[set admittance control mode]

errno_t set_ft_ctrl_mode(const JKHD *handle, BOOL mode)

[get admittance control mode]

errno_t get_ft_ctrl_mode(const JKHD *handle, BOOL* mode)

[get admittance control config]

errno_t set_ft_ctrl_config(const JKHD *handle, AdmitCtrlType cfg)

[get admittance control config]

errno_t get_ft_ctrl_config(const JKHD *handle, RobotAdmitCtrl* cfg)

set force control type and sensor initial state

errno_t set_compliant_type(const JKHD *handle, int sensor_compensation, int compliance_type)

get force control type and sensor initial state

errno_t get_compliant_type(const JKHD *handle, int *sensor_compensation, int *compliance_type)

set compliance control torque condition

errno_t set_compliance_condition(const JKHD *handle, const FTxyz *ft)

[set approach speed limit]

errno_t set_approach_speed_limit(const JKHD *handle, double vel, double angularVel)

[get approach speed limit]

errno_t get_approach_speed_limit(const JKHD *handle, double* vel, double* angularVel)

Collision

interrogate whether in collision protection mode

errno_t is_in_collision(const JKHD *handle, BOOL *in_collision)

set collision level

errno_t set_collision_level(const JKHD *handle, const int level)

get collision level

errno_t get_collision_level(const JKHD *handle, int *level)

collision recover

errno_t collision_recover(const JKHD *handle)

Kinematics

kine inverse

errno_t kine_inverse(const JKHD *handle, const JointValue *ref_pos, const CartesianPose *cartesian_pose, JointValue *joint_pos)

kine forward

errno_t kine_forward(const JKHD *handle, const JointValue *joint_pos, CartesianPose *cartesian_pose)

rpy to rotation matrix

errno_t rpy_to_rot_matrix(const JKHD *handle, const Rpy *rpy, RotMatrix *rot_matrix)

rotation matrix to rpy

errno_t rot_matrix_to_rpy(const JKHD *handle, const RotMatrix *rot_matrix, Rpy *rpy)

rotation matrix to quaternion

errno_t rot_matrix_to_quaternion(const JKHD *handle, const RotMatrix *rot_matrix, Quaternion *quaternion)

quaternion to rotation matrix

errno_t quaternion_to_rot_matrix(const JKHD *handle, const Quaternion *quaternion, RotMatrix *rot_matrix)

List of Interface Call Return Values and Troubleshooting

Error CodeDescriptionSuggested Action
0successNo action needed.
2Interface error or controller not supportedVerify controller and SDK versions; consider upgrading or using another interface.
-1Invalid handlerEnsure you call the login interface before using it.
-2Invalid parameterCheck if the parameters are correct.
-3Fail to connectVerify network status or ensure the robot IP is correct.
-4Kinematic inverse errorCheck the current coordinate system or reference joint angles for validity.
-5Emergency stopE-stop status; reserved state.
-6Not powered onPower the robot.
-7Not enabledEnable the robot.
-8Not in servo modeEnsure servo mode is enabled before calling servoJP.
-9Must turn off enable before power offDisable before powering off.
-10Cannot operate, program is runningStop the running program first.
-11Cannot open file, or file doesn't existCheck if the file exists or can be accessed.
-12Motion abnormalCheck for singularities or movements exceeding robot limits.
-14FTP errorInvestigate FTP connection issues.
-15Socket message or value oversizeEnsure parameters are within acceptable limits.
-16Kinematic forward errorVerify inputs for forward kinematics.
-17Not support empty folderAvoid using empty folders.
-20Protective stopInvestigate and address protective stop conditions.
-21Emergency stopCheck and reset the emergency stop.
-22On soft limitUse the teaching feature in the robot app to exit soft limits.
-30Fail to encode command stringLikely an error in parsing controller messages.
-31Fail to decode command stringCheck for errors in controller message parsing.
-32Fail to uncompress port 10004 stringPossible network fluctuation or data overflow.
-40Move linear errorVerify the path avoids singularity regions.
-41Move joint errorEnsure joint angles are valid.
-42Move circular errorCheck the circular motion parameters.
-50Block wait timeoutVerify and increase wait timeout if needed.
-51Power on timeoutCheck the power-on process.
-52Power off timeoutCheck the power-off process.
-53Enable timeoutReview the enabling process.
-54Disable timeoutReview the disabling process.
-55Set user frame timeoutCheck the user frame settings.
-56Set tool timeoutVerify the tool coordinate settings.
-60Set IO timeoutEnsure 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.

Last update: