C语言
大约 19 分钟
C语言
本文档将介绍JAKA SDK(C)中定义的数据类型和API,主要适用于使用C/C++创建与虚拟或真实控制器通信的机器人应用程序的软件开发人员。对于需要了解JAKA机器人控制器应用程序的用户也会有一定帮助。
接口列表
机器人基础操作
机械臂登录
errno_t create_handler(const char *ip, JKHD *handle, BOOL use_grpc)
机械臂注销
errno_t destory_handler(const JKHD *handle)
机械臂上电
errno_t power_on(const JKHD *handle)
机械臂下电
errno_t power_off(const JKHD *handle)
机械臂关机
errno_t shut_down(const JKHD *handle)
机械臂上使能
errno_t enable_robot(const JKHD *handle)
机械臂下使能
errno_t disable_robot(const JKHD *handle)
获取当前连接机械臂的dh参数
errno_t get_dh_param(const JKHD *handle, DHParam *dhParam)
设置机器人安装角度
errno_t set_installation_angle(const JKHD* handle, double angleX, double angleZ)
获取机器人安装角度
errno_t get_installation_angle(const JKHD* handle, Quaternion* quat, Rpy* appang)
获取机械臂状态
errno_t get_robot_state(const JKHD *handle, RobotState *state)
获取机械臂状态监测数据-唯一多线程安全接口
errno_t get_robot_status(const JKHD *handle, RobotStatus *status)
[获取机械臂状态监测数据]
errno_t get_robot_status_simple(const JKHD *handle, RobotStatus_simple *status)
SDK
注册机械臂出错时的回调函数
errno_t set_error_handler(const JKHD *handle, CallBackFuncType func)
获取sdk版本号
errno_t get_sdk_version(const JKHD *handle, char *version)
设置网络异常时机械臂自动终止运动类型
errno_t set_network_exception_handle(const JKHD *handle, float millisecond, ProcessType mnt)
获取控制器ip
errno_t get_controller_ip(char *controller_name, char *ip_list)
设置机械臂错误码文件存放路径
errno_t set_errorcode_file_path(const JKHD *handle, char *path)
设置机械臂错误码文件存放路径获取机械臂目前发生的最后一个错误码
errno_t get_last_error(const JKHD *handle, ErrorCode *code)
设置sdk是否开启调试模式
errno_t set_debug_mode(const JKHD *handle, BOOL mode)
设置sdk日志路径
errno_t set_SDK_filepath(const JKHD *handle, char *filepath)
获取sdk日志路径
errno_t get_SDK_filepath(const JKHD *handle, char *filepath, int size)
机器人运动相关
机械臂手动模式下运动
errno_t jog(const JKHD *handle, int aj_num, MoveMode move_mode, CoordType coord_type, double vel_cmd, double pos_cmd)
机械臂手动模式下运动停止
errno_t jog_stop(const JKHD *handle, int num)
机械臂关节运动
errno_t joint_move(const JKHD *handle, const JointValue *joint_pos, MoveMode move_mode, BOOL is_block, double speed)
机械臂关节运动
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)
机械臂末端直线运动
errno_t linear_move(const JKHD *handle, const CartesianPose *end_pos, MoveMode move_mode, BOOL is_block, double speed)
机械臂末端直线运动
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)
机械臂圆弧运动
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)
机械臂圆弧运动
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)
机械臂圆弧运动
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)
设置机械臂的运行倍率
errno_t set_rapidrate(const JKHD *handle, double rapid_rate)
获取机械臂的运行倍率
errno_t get_rapidrate(const JKHD *handle, double *rapid_rate)
设置工具信息
errno_t set_tool_data(const JKHD *handle, int id, const CartesianPose *tcp, const char *name)
获取工具信息
errno_t get_tool_data(const JKHD *handle, int id, CartesianPose *tcp)
设置当前使用的工具id
errno_t set_tool_id(const JKHD *handle, const int id)
查询当前使用的工具id
errno_t get_tool_id(const JKHD *handle, int *id)
设定用户坐标系信息
errno_t set_user_frame_data(const JKHD *handle, int id, const CartesianPose *user_frame, const char *name)
获取用户坐标系信息
errno_t get_user_frame_data(const JKHD *handle, int id, CartesianPose *user_frame)
设置当前使用的用户坐标系id
errno_t set_user_frame_id(const JKHD *handle, const int id)
查询当前使用的用户坐标系id
errno_t get_user_frame_id(const JKHD *handle, int *id)
控制机械臂进入或退出拖拽模式
errno_t drag_mode_enable(const JKHD *handle, BOOL enable)
查询机械臂是否处于拖拽模式
errno_t is_in_drag_mode(const JKHD *handle, BOOL *in_drag)
获取当前设置下工具末端的位姿
errno_t get_tcp_position(const JKHD *handle, CartesianPose *tcp_position)
查询机械臂是否超出限位
errno_t is_on_limit(const JKHD *handle, BOOL *on_limit)
查询机械臂运动是否停止
errno_t is_in_pos(const JKHD *handle, BOOL *in_pos)
[设置规划器类型]
errno_t set_motion_planner(const JKHD* handle, MotionPlannerType type)
机械臂运动终止
errno_t motion_abort(const JKHD *handle)
机械臂负载设置
errno_t set_payload(const JKHD *handle, const PayLoad *payload)
获取机械臂负载数据
errno_t get_payload(const JKHD *handle, PayLoad *payload)
IO
设置数字输出变量
errno_t set_digital_output(const JKHD *handle, IOType type, int index, BOOL value)
设置模拟输出变量
errno_t set_analog_output(const JKHD *handle, IOType type, int index, float value)
查询数字输入状态
errno_t get_digital_input(const JKHD *handle, IOType type, int index, BOOL *result)
查询数字输出状态
errno_t get_digital_output(const JKHD *handle, IOType type, int index, BOOL *result)
获取模拟量输入变量的值
errno_t get_analog_input(const JKHD *handle, IOType type, int index, float *result)
获取模拟量输出变量的值
errno_t get_analog_output(const JKHD *handle, IOType type, int index, float *result)
查询扩展io是否运行
errno_t is_extio_running(const JKHD *handle, BOOL *is_running)
TIO
设置tiov3电压参数
errno_t set_tio_vout_param(const JKHD* handle, int vout_enable, int vout_vol)
获取tiov3电压参数
errno_t get_tio_vout_param(const JKHD* handle, int* vout_enable, int* vout_vol)
TIO添加或修改信号量
errno_t add_tio_rs_signal(const JKHD* handle, SignInfo sign_info)
TIO删除信号量
errno_t del_tio_rs_signal(const JKHD* handle, const char* sig_name)
TIO RS485发送指令
errno_t send_tio_rs_command(const JKHD* handle, int chn_id, uint8_t* cmdbuf, int bufsize)
TIO 获取信号量信息
errno_t get_rs485_signal_info(const JKHD* handle, SignInfo* sign_info_array, int *array_len)
设置TIO模式
errno_t set_tio_pin_mode(const JKHD* handle, int pin_type, int pin_mode)
获取TIO模式
errno_t get_tio_pin_mode(const JKHD* handle, int pin_type, int* pin_mode)
TIO RS485通讯参数配置
errno_t set_rs485_chn_comm(const JKHD* handle, ModRtuComm mod_rtu_com)
TIO RS485通讯参数查询
errno_t get_rs485_chn_comm(const JKHD* handle, ModRtuComm* mod_rtu_com)
TIO RS485通讯模式配置
errno_t set_rs485_chn_mode(const JKHD* handle, int chn_id, int chn_mode)
TIO RS485通讯模式查询
errno_t get_rs485_chn_mode(const JKHD* handle, int chn_id, int* chn_mode)
Servo
机械臂伺服位置控制模式使能
errno_t servo_move_enable(const JKHD *handle, BOOL enable)
机械臂关节空间伺服模式运动
errno_t servo_j(const JKHD *handle, const JointValue *joint_pos, MoveMode move_mode)
机械臂笛卡尔空间伺服模式运动扩展
errno_t servo_p(const JKHD *handle, const CartesianPose *cartesian_pose, MoveMode move_mode)
机械臂servo模式下禁用滤波器
errno_t servo_move_use_none_filter(const JKHD *handle)
机械臂servo模式下关节空间一阶低通滤波
errno_t servo_move_use_joint_LPF(const JKHD *handle, double cutoffFreq)
机械臂servo模式下关节空间非线性滤波
errno_t servo_move_use_joint_NLF(const JKHD *handle, double max_vr, double max_ar, double max_jr)
机械臂servo模式下笛卡尔空间非线性滤波
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)
机械臂servo模式下关节空间多阶均值滤波
errno_t servo_move_use_joint_MMF(const JKHD *handle, int max_buf, double kp, double kv, double ka)
机械臂servo模式下速度前瞻参数设置
errno_t servo_speed_foresight(const JKHD *handle, int max_buf, double kp)
Trajectory
设置轨迹复现配置参数
errno_t set_traj_config(const JKHD *handle, const TrajTrackPara *para)
采集轨迹复现数据控制开关
errno_t set_traj_sample_mode(const JKHD *handle, const BOOL mode, char *filename)
获取轨迹复现配置参数
errno_t get_traj_config(const JKHD *handle, TrajTrackPara *para)
采集轨迹复现数据状态查询
errno_t get_traj_sample_status(const JKHD *handle, BOOL *sample_status)
查询控制器中已经存在的轨迹复现数据的文件名
errno_t get_exist_traj_file_name(const JKHD *handle, MultStrStorType *filename)
重命名轨迹复现数据的文件名
errno_t rename_traj_file_name(const JKHD *handle, const char *src, const char *dest)
删除控制器中轨迹复现数据文件
errno_t remove_traj_file(const JKHD *handle, const char *filename)
控制器中轨迹复现数据文件生成控制器执行脚本
errno_t generate_traj_exe_file(const JKHD *handle, const char *filename)
Program
运行当前加载的作业程序
errno_t program_run(const JKHD *handle)
暂停当前运行的作业程序
errno_t program_pause(const JKHD *handle)
继续运行当前暂停的作业程序
errno_t program_resume(const JKHD *handle)
终止当前执行的作业程序
errno_t program_abort(const JKHD *handle)
加载指定的作业程序
errno_t program_load(const JKHD *handle, const char *file)
获取机械臂作业程序的执行状态
errno_t get_program_state(const JKHD *handle, ProgramState *status)
[获取机械臂作业程序的执行信息]
errno_t get_program_info(const JKHD *handle, ProgramInfo* info)
获取已加载的作业程序的名字
errno_t get_loaded_program(const JKHD *handle, char *file)
获取当前机械臂作业程序的执行行号
errno_t get_current_line(const JKHD *handle, int *curr_line)
获取系统变量
errno_t get_user_var(const JKHD *handle, UserVariableList* vlist)
设置系统变量
errno_t set_user_var(const JKHD *handle, UserVariable v)
FTP
初始化ftp客户端
errno_t init_ftp_client(const JKHD *handle)
关闭ftp客户端
errno_t close_ftp_client(const JKHD *handle)
ftp下载
errno_t download_file(const JKHD *handle, char *local, char *remote, int opt)
ftp上传
errno_t upload_file(const JKHD *handle, char *local, char *remote, int opt)
ftp删除
errno_t del_ftp_file(const JKHD *handle, char *remote, int opt)
ftp重命名
errno_t rename_ftp_file(const JKHD *handle, char *remote, char *des, int opt)
ftp目录查询
errno_t get_ftp_dir(const JKHD *handle, const char *remotedir, int type, char *ret)
力控相关
开启或关闭力矩传感器
errno_t set_torque_sensor_mode(const JKHD *handle, int sensor_mode)
设置力控传感器通信参数
errno_t set_torque_sensor_comm(const JKHD *handle, const int type, const char *ip_addr, const int port)
获取力控传感器通信参数
errno_t get_torque_sensor_comm(const JKHD *handle, int *type, char *ip_addr, int *port)
设置力控的低通滤波器参数
errno_t set_torque_sensor_filter(const JKHD *handle, const float torque_sensor_filter)
获取力控的低通滤波器参数
errno_t get_torque_sensor_filter(const JKHD *handle, float *torque_sensor_filter)
设置力传感器的传感器限位参数配置
errno_t set_torque_sensor_soft_limit(const JKHD *handle, const FTxyz torque_sensor_soft_limit)
获取力传感器的传感器限位参数配置
errno_t get_torque_sensor_soft_limit(const JKHD *handle, FTxyz *torque_sensor_soft_limit)
[获取力传感器的反馈值]
errno_t get_torque_sensor_data(const JKHD *handle, int type, TorqSensorData* data)
传感器校零
errno_t zero_end_sensor(const JKHD *handle)
设置力控限速
errno_t set_compliant_speed_limit(const JKHD *handle, double speed_limit, double angular_speed_limit)
获取力控限速
errno_t get_compliant_speed_limit(const JKHD *handle, double* speed_limit, double* angular_speed_limitangularVel)
设置力控类型和传感器初始化状态
errno_t set_compliant_type(const JKHD *handle, int sensor_compensation, int compliance_type)
获取力控类型和传感器初始化状态
errno_t get_compliant_type(const JKHD *handle, int *sensor_compensation, int *compliance_type)
设置速度柔顺控制参数
errno_t set_vel_compliant_ctrl(const JKHD *handle, const VelCom *vel)
设置力矩参考中心
errno_t set_torque_ref_point(const JKHD *handle, int ref_point)
获取力矩参考中心
errno_t get_torque_ref_point(const JKHD *handle, int *ref_point)
设置传感器灵敏度
errno_t set_end_sensor_sensitivity_threshold(const JKHD *handle, FTxyz threshold)
获取传感器灵敏度
errno_t get_end_sensor_sensitivity_threshold(const JKHD *handle, FTxyz *threshold)
设置力控终止条件
errno_t set_force_stop_condition(const JKHD *handle, ForceStopConditionList condition)
开始辨识工具末端负载
errno_t start_torq_sensor_payload_identify(const JKHD *handle, const JointValue *joint_pos)
获取末端负载辨识状态
errno_t get_torq_sensor_identify_staus(const JKHD *handle, int *identify_status)
获取末端负载辨识结果
errno_t get_torq_sensor_payload_identify_result(const JKHD *handle, PayLoad *payload)
设置传感器末端负载
errno_t set_torq_sensor_tool_payload(const JKHD *handle, const PayLoad *payload)
获取传感器末端负载
errno_t get_torq_sensor_tool_payload(const JKHD *handle, PayLoad *payload)
工具拖拽
获取力控柔顺控制参数
errno_t get_admit_ctrl_config(const JKHD *handle, RobotAdmitCtrl *admit_ctrl_cfg)
力控导纳使能
errno_t enable_admittance_ctrl(const JKHD *handle, const int enable_flag)
力控工具拖拽使能
errno_t enable_tool_drive(const JKHD *handle, const int enable_flag)
获取力控工具拖拽开启状态
errno_t get_tool_drive_state(const JKHD *handle, int* enable, int *state)
获取工具拖拽参数
errno_t get_tool_drive_config(const JKHD *handle, RobotToolDriveCtrl* cfg)
设置力控拖拽手感参数
errno_t set_tool_drive_config(const JKHD *handle, ToolDriveConfig cfg)
获取工具拖拽坐标系
errno_t get_tool_drive_frame(const JKHD *handle, FTFrameType *ftFrame)
设置工具拖拽坐标系
errno_t set_tool_drive_frame(const JKHD *handle, FTFrameType ftFrame)
获取融合拖拽灵敏度
errno_t get_fusion_drive_sensitivity_level(const JKHD *handle, int *level)
设置融合拖拽灵敏度
errno_t set_fusion_drive_sensitivity_level(const JKHD *handle, int level)
获取运动限制-奇异点和关节限位-预警范围
errno_t get_motion_limit_warning_range(const JKHD *handle, int *warning_range)
设置运动限制-奇异点和关节限位-预警范围
errno_t set_motion_limit_warning_range(const JKHD *handle, int warning_range)
力控
设置导纳控制运动坐标系
errno_t set_ft_ctrl_frame(const JKHD *handle, const int ftFrame)
获取导纳控制运动坐标系
errno_t get_ft_ctrl_frame(const JKHD *handle, int *ftFrame)
[设置恒力控制容差]
errno_t set_ft_tolerance(const JKHD *handle, double force, double torque)
[获取恒力控制容差]
errno_t get_ft_tolerance(const JKHD *handle, double* force, double* torque)
[设置恒力柔顺是否开启]
errno_t set_ft_ctrl_mode(const JKHD *handle, BOOL mode)
[获取恒力柔顺控制状态]
errno_t get_ft_ctrl_mode(const JKHD *handle, BOOL* mode)
[设置导纳控制运动配置参数]
errno_t set_ft_ctrl_config(const JKHD *handle, AdmitCtrlType cfg)
[获取导纳控制运动配置参数]
errno_t get_ft_ctrl_config(const JKHD *handle, RobotAdmitCtrl* cfg)
设置力控类型和传感器初始化状态
errno_t set_compliant_type(const JKHD *handle, int sensor_compensation, int compliance_type)
获取力控类型和传感器初始化状态
errno_t get_compliant_type(const JKHD *handle, int *sensor_compensation, int *compliance_type)
设置柔顺控制力矩条件
errno_t set_compliance_condition(const JKHD *handle, const FTxyz *ft)
设置进近限速
errno_t set_approach_speed_limit(const JKHD *handle, double vel, double angularVel)
获取进近限速
errno_t get_approach_speed_limit(const JKHD *handle, double* vel, double* angularVel)
碰撞
查询机械臂是否处于碰撞保护模式
errno_t is_in_collision(const JKHD *handle, BOOL *in_collision)
设置机械臂碰撞等级
errno_t set_collision_level(const JKHD *handle, const int level)
获取机器设置的碰撞等级
errno_t get_collision_level(const JKHD *handle, int *level)
碰撞之后从碰撞保护模式恢复
errno_t collision_recover(const JKHD *handle)
运动学
机械臂求解逆解
errno_t kine_inverse(const JKHD *handle, const JointValue *ref_pos, const CartesianPose *cartesian_pose, JointValue *joint_pos)
机械臂求解正解
errno_t kine_forward(const JKHD *handle, const JointValue *joint_pos, CartesianPose *cartesian_pose)
欧拉角到旋转矩阵的转换
errno_t rpy_to_rot_matrix(const JKHD *handle, const Rpy *rpy, RotMatrix *rot_matrix)
旋转矩阵到欧拉角的转换
errno_t rot_matrix_to_rpy(const JKHD *handle, const RotMatrix *rot_matrix, Rpy *rpy)
旋转矩阵到四元数的转换
errno_t rot_matrix_to_quaternion(const JKHD *handle, const RotMatrix *rot_matrix, Quaternion *quaternion)
四元数到旋转矩阵的转换
errno_t quaternion_to_rot_matrix(const JKHD *handle, const Quaternion *quaternion, RotMatrix *rot_matrix)
接口调用返回值列表及问题排查
错误代码 | 描述 | 处理建议 |
---|---|---|
0 | success | null |
2 | interface error or controller not support | 核对控制器和SDK版本信息,进行升级或换用其他接口 |
-1 | invalid handler | 请检查调用接口前是否login |
-2 | invalid parameter | 请检查参数是否正确 |
-3 | fail to connect | 请检查网络连接状态,或机器人IP是否正确 |
-4 | kine_inverse error | 逆解失败,请检查当前的坐标系,或参考关节角是否合理 |
-5 | e-stop | 急停状态,保留状态 |
-6 | not power on | 未上电 |
-7 | not enable | 未使能 |
-8 | not in servo mode | 不处于伺服模式,在执行servoJP 的时候,必须先进入伺服模式,请检查是否调用对应接口 |
-9 | must turn off enable before power off | 下电前必须下使能 |
-10 | cannot operate, program is running | 无法操作,程序正在执行中,请先关闭程序 |
-11 | cannot open file, or file doesn't exist | 无法打开文件,或者文件不存在 |
-12 | motion abnormal | 运动异常,可能处于奇异点附近,或者超出机器人运动限制 |
-14 | ftp error | ftp异常 |
-15 | socket msg or value oversize | 超出限制异常 |
-16 | kine_forward error | 正解失败 |
-17 | not support empty folder | 不支持空文件夹 |
-20 | protective stop | 保护性停止 |
-21 | emergency stop | 急停 |
-22 | on soft limit | 处于软限位,此时无法手动拖动机器人,需要用APP上的示教功能接触软限位 |
-30 | fail to encode cmd string | 命令编码失败,一般是解析控制器返回的消息时出错 |
-31 | fail to decode cmd string | 命令解码失败,一般是解析控制器返回的消息时出错 |
-32 | fail to uncompress port 10004 string | 解压缩10004端口数据失败,可能受网络波动影响,或数据量太大的原因 |
-40 | move linear error | 直线运动失败,请检查是否路径中是否有奇异区域 |
-41 | move joint error | 关节运动失败,请检查设置的关节角度 |
-42 | move circular error | 圆弧运动失败,请检查设置的参数 |
-50 | block_wait timeout | 阻塞等待超时 |
-51 | power on timeout | 上电超时 |
-52 | power off timeout | 下电超时 |
-53 | enable timeoff | 使能超时 |
-54 | disable timeout | 下使能超时 |
-55 | set userframe timeout | 设置用户坐标系超时 |
-56 | set tool timeout | 设置工具坐标系超时 |
-60 | set io timeout | 设置IO超时 |
问题反馈
文档中若出现不准确的描述或者错误,恳请读者见谅指正。如果您在阅读过程中发现任何问题或者有想提出的意见,可以发送邮件到 support@jaka.com ,我们将尽快给您回复。