跳到主要内容

上位机库功能介绍

库结构说明

interface.h 头文件接口说明

1.连接控制器

bool connect_robot(char *ip);

ip,要连接的控制器的 ip。

2.伺服使能

bool servo_power_on();

示教模式下,伺服使能后,可以通过控制点动等操作来移动机器人的位置。

3.伺服下使能

void servo_power_off();

伺服下使能后,就无法对机器人进行位置移动。

4.关节运动

void robot_movj(double *pos,int vel,int coord);

pos[],点位数组,长度最大为 7,几轴就用长度为几的数组。

vel,机器人进行关节运动时的速度,参数范围在 0<vel≤100,参数越大机器人移动的越快。

coord,坐标系,参数范围:0≤coord≤3,

0:关节坐标系; 1:直角坐标系; 2:工具坐标系; 3:用户坐标系。

示例:

    double pos[6];
pos[0] = 10;
pos[1] = 10;
pos[2] = 10;
pos[3] = 10;
pos[4] = 10;
pos[5] = 10;
robot_movj(pos,50,0);

表示将机器人以 50%的关节最大速度(在全局速度为 100%时)按照关节插补的方式移动到关节坐标系(10,10,10,10,10,10)的位置。

5.直线运动

void robot_movl(double *pos,int vel,int coord);

pos[],点位数组,长度最大为 7,几轴就用长度为几的数组。

vel,机器人进行关节运动时的速度,参数范围在 0<vel≤1000,参数越大机器人移动的越快。

coord,坐标系,参数范围:0≤coord≤3,

0:关节坐标系;1:直角坐标系;2:工具坐标系;3:用户坐标系。

示例:

    double pos[6];
pos[0] = 10;
pos[1] = 10;
pos[2] = 10;
pos[3] = 10;
pos[4] = 10;
pos[5] = 10;
robot_movl(pos,50,1);

表示将机器人以 50mm/s(在全局速度为 100%时)的速度按照直线插补的方式移动到直角坐标系(10,10,10,10,10,10)的位置。

6.圆弧运动

void robot_movc(double *pos1,double *pos2,double *pos3,int vel,int coord);

pos1[],点位数组,长度为 7,pos2[],点位数组,长度为 7,pos3[],点位数组,长度为 7。

vel,机器人进行关节运动时的速度,参数范围在 0<vel≤1000,参数越大机器人移动的越快。

coord,坐标系,参数范围:0≤coord≤3,

0:关节坐标系;1:直角坐标系;2:工具坐标系;3:用户坐标系。

示例:

    double pos1[6];
pos[0] = 10;
pos[1] = 10;
pos[2] = 10;
pos[3] = 10;
pos[4] = 10;
pos[5] = 10;
double pos2[6];
pos[0] = 0;
pos[1] = 0;
pos[2] = 0;
pos[3] = 10;
pos[4] = 10;
pos[5] = 10;
double pos3[6];
pos[0] = 10;
pos[1] = 10;
pos[2] = 10;
pos[3] = 0;
pos[4] = 0;
pos[5] = 0;
robot_movc(pos1,pos2,pos3,50,1);

表示将机器人以 50mm/s(在全局速度为 100%时)的速度画弧线经过直角坐标系(10,10,10,10,10,10)(0,0,0,10,10,10)(10,10,10,0,0,0)的位置。

7.整圆运动

void robot_movca(double *pos1,double *pos2,double *pos3,int vel,int coord);

pos1[],点位数组,长度为 7,pos2[],点位数组,长度为 7,pos3[],点位数组,长度为 7。

vel,机器人进行关节运动时的速度,参数范围在 0<vel≤1000,参数越大机器人移动的越快。

coord,坐标系,参数范围:0≤coord≤3,

0:关节坐标系;1:直角坐标系;2:工具坐标系;3:用户坐标系。

示例:

    double pos1[6];
pos[0] = 10;
pos[1] = 10;
pos[2] = 10;
pos[3] = 10;
pos[4] = 10;
pos[5] = 10;
double pos2[6];
pos[0] = 0;
pos[1] = 0;
pos[2] = 0;
pos[3] = 10;
pos[4] = 10;
pos[5] = 10;
double pos3[6];
pos[0] = 10;
pos[1] = 10;
pos[2] = 10;
pos[3] = 0;
pos[4] = 0;
pos[5] = 0;
robot_movca(pos1,pos2,pos3,50,1);

表示将机器人以 50mm/s(在全局速度为 100%时)的速度画整圆经过直角坐标系(10,10,10,10,10,10)(0,0,0,10,10,10)(10,10,10,0,0,0)的位置。

8.外部轴关节运动

void robot_extra_movj(double *pos,int vel,int coord);

9.外部轴直线运动

void robot_extra_movl(double *pos,int vel,int coord);

10.外部轴圆弧运动

void robot_extra_movc(double *pos1,double *pos2,double *pos3,int vel,int coord);

11.获取机器人运行状态 0: 停止 1: 暂停 2: 运行

int get_robot_running_state();

12.继续运行机器人

int get_robot_running_state();

13.开始点动

void start_jogging(int axis,bool dir);

axis,轴号,机器人各轴。1-7,机器人 ;8-12,外部轴。

dir,方向,true:机器人模型正方向;false,机器人模型负方向。

此函数需连续发送才可以使机器人移动。

14.停止点动

void stop_jogging(int axis);

axis,轴号,机器人各轴。

15.设置数字输出

void set_dout(int port,int value);

port, 端口号。

value,数值,参数范围:0 或 1。

16.设置模拟输出

void set_aout(int port,double value);

port,端口号。

value,数值,参数范围:0≤value≤10。

17.查询数字输出

void get_dout(double *dout);

dout,数字输出数组。

18.查询数字输入

void get_din(double *din);

din,数字输入数组。

19.查询模拟输出

void get_aout(double *aout);

aout,模拟输出数组。

20.查询模拟输入

void get_ain(double *ain);

ain,模拟输入数组。

21.设置点动速度

void set_jogging_speed(int speed);

speed ,百分比速度,参数范围:0<speed≤100。

22.获取机器人当前位置

void get_current_position(double *pos);

pos[], 点位数组,长度为 7。

23.获取机器人外部轴当前位置

void get_current_sync_position(double *pos);

pos[], 点位数组,长度为 5。

24.设置点动速度

int get_jogging_speed();

25.获取当前点动速度

int get_jogging_speed();

25.获取机器人当前模式

int get_current_mode();

当前模式 0:示教 1:远程 2:运行

26.设置机器人当前模式

void set_current_mode(int mode);

mode,当前模式 0:示教 1:远程 2:运行

27.获取机器人当前坐标系

int get_current_coord();

坐标系 0:关节 1:直角 2:工具 3:用户

28.设置机器人当前坐标系

void set_current_coord(int coord);

coord,坐标系 0:关节 1:直角 2:工具 3:用户

29.查询全局位置

void get_GPosition(char *posName,double *pos);

posName, 全局位置名 例如 "GP001" pos, 全局点位数组 长度 14 前 7 位为机器人位置 后 7 位为外部轴位置

30.设置全局位置

void set_GPosition(char *posName, int coord ,double pos[7], double syncPos[7]);

posName, 全局位置名 例如 "GP001" coord, 坐标系 0:关节 1:直角 2:工具 3:用户 pos, 机器人坐标 syncPos, 机器人外部轴坐标

31.查询全局变量

double get_global_variant(char *varName);

varName, 全局变量名 例如 "GI001" "GD001" "GB001"

32.设置全局变量

void set_global_variant(char *varName,double varValue);

varName, 全局变量名 例如 "GI001" "GD001" "GB001" varValue, 变量值

33.查询 4 点标定

void ask_four_point(double *result);

reseult,标定参数,9 位数组

34.进行 4 点标记

void four_point_mark(int point,int status);

point, 标记点位编号 取值范围 0 - 3 status, 标记状态 0:取消标记 1:标记

34.4 点标定计算

void four_point_calculation(double L1,double L2,double *result);

L1, 四点标记时 A 点与 B 点的 x 坐标之差 L2, 四点标记时 A 点与 D 点的 y 坐标之差 result,返回的计算 DH 参数结果

35.将四点标定计算的结果写入机器人 DH 参数

bool result_for_DH();

36.获取伺服状态

int get_servo_state();

伺服状态,0:停止 1:就绪 2:错误 3:运行

37.设置伺服状态

void set_servo_state(int state);

state,伺服状态 0:停止;1:暂停;2:运行;

38.打印最后一条消息

std::string show_log();

39.上传作业文件

void upload_job(char * job);

将作业文件上传到控制器。 job, 作业文件名,多个用“,”分隔,路径在编译文件路径下的 RobotJob

40.下载作业文件

void download_job();

41 删除作业文件

void delete_job(char *job);

job,作业文件名称

42.打开作业文件

void open_job(char *job);

job,作业文件名称

43.单步运行作业文件

void step_job(char *job,int line);

job,作业文件名称 line, 运行指令所在的行数

44.运行作业文件

void run_job(char *job);

job:作业文件名称

45.暂停作业文件或运动指令

void pause_job();

暂停运行当前作业文件

46.停止作业文件或运动指令

void stop_job();

停止运行当前作业文件

47.继续运行作业文件

void continue_job();

继续运行当前作业文件,需在运行模式下使用

48.设置机器人作业文件循环次数

void set_runs(int num);

num, 循环次数 0 为无限循环

49.连续运动模式

void continuous_motion_mode(int on);

on,0 关闭;- 1 开启。

50.发送连续运动指令队列

void send_continuous_motion_queue(cmdPara cmd[],unsigned int size);

发送完成后,机器人将开始运动 param cmd,指令数组 size,指令数组长度

51.开始连续运动

void continuous_motion_start();

52.暂停连续运动

void continuous_motion_start();

53.停止连续运动

void continuous_motion_start();

54.设置零点位置

bool set_axis_zero_position(int axis);

axis, 轴号

55.设置零点偏移

void set_zero_pos_shift(int axis, double shift);

axis, 需要偏移的轴数 shift, 偏移量 -360° < shift < 360°

56.伺服错误信息

void setErrorHandle(void (*Callback)(char*));

Callback, 回调函数

57.切换用户坐标系

void set_user_coord_number(int num);

num, 用户坐标系编号

58.获取单圈值

get_single_cycle(double *single_cycle);

single_cycle,单圈值数组 长度为 7

59.切换工具手

void switch_tool_hand(int tagetTool);

tagetTool, 要切换的工具手 0 为无工具手状态

60.获取当前工具手

int get_current_tool_hand();

61.设置工具手参数

void set_tool_hand_param(int toolNum, double *toolparam);

toolNum, 要修改的工具手编号 toolparam, 要修改的参数 长度 6 X 轴偏移量 Y 轴偏移量 Z 轴偏移量 绕 A 轴旋转量 绕 B 轴旋转量 绕 C 轴旋转量

62.查询工具手参数

void query_tool_hand_param(int tagetTool,double *param);

toolNum, 要查询的工具手编号 toolparam, 工具手参数 长度 6 数组

指令结构体

typedef struct cmdPara
{
// MOVJ 关节运动
// MOVL 直线运动
// MOVC 圆弧运动
// MOVCA 整圆运动
enum Type{MOVJ=1, MOVL, MOVC, MOVCA, MOVJEXT, MOVLEXT, MOVCEXT};
double m_velocity; // 速度
double m_acc; // 加速度
double m_dec; // 减速度
double m_pl; // 平滑
int m_spin; //< 姿态(仅MOVCA需要这个参数) 0:姿态不变 1:六轴不转 2:六轴旋转
double m_coord[7];//m_coord[0]和 m_coord[1]代表坐标系,m_coord[2]代表左右手 0-无 1-左 2-右,其余给0即可
double m_position[7];// m_position[0]到 m_position[6]代表机器人位置坐标
double m_syncPosition[5];// m_position[0]到 m_position[4]代表机器人外部轴位置坐标
Type cmdType; // 指令类型
}cmdPara;
    //以下点位为测试点位,谨慎使用!
cmdPara cmd[5];
cmd[0].cmdType = cmdPara::MOVL;
cmd[0].m_velocity = 300;
cmd[0].m_acc = 30;
cmd[0].m_dec = 30;
cmd[0].m_pl = 0;
cmd[0].m_coord[0] = 0;
cmd[0].m_coord[1] = 0;
cmd[0].m_coord[2] = 0;
cmd[0].m_coord[3] = 0;
cmd[0].m_coord[4] = 0;
cmd[0].m_coord[5] = 0;
cmd[0].m_coord[6] = 0;


cmd[0].m_position[0] = -0.0026;
cmd[0].m_position[1] = -0.0006;
cmd[0].m_position[2] = -0.0016;
cmd[0].m_position[3] = 0;
cmd[0].m_position[4] = 0.0015;
cmd[0].m_position[5] = -0.0019;

cmd[1].cmdType = cmdPara::MOVL;
cmd[1].m_velocity = 300;
cmd[1].m_acc = 30;
cmd[1].m_dec = 30;
cmd[1].m_pl = 0;

cmd[1].m_coord[0] = 0;
cmd[1].m_coord[1] = 0;
cmd[1].m_coord[2] = 0;
cmd[1].m_coord[3] = 0;
cmd[1].m_coord[4] = 0;
cmd[1].m_coord[5] = 0;
cmd[1].m_coord[6] = 0;

cmd[1].m_position[0] = -25.236;
cmd[1].m_position[1] = -9.7905;
cmd[1].m_position[2] = 10.4452;
cmd[1].m_position[3] = -0.0027;
cmd[1].m_position[4] = 0.6566;
cmd[1].m_position[5] = -25.2679;

cmd[2].cmdType = cmdPara::MOVL;
cmd[2].m_velocity = 300;
cmd[2].m_acc = 30;
cmd[2].m_dec = 30;
cmd[2].m_pl = 0;

cmd[2].m_coord[0] = 0;
cmd[2].m_coord[1] = 0;
cmd[2].m_coord[2] = 0;
cmd[2].m_coord[3] = 0;
cmd[2].m_coord[4] = 0;
cmd[2].m_coord[5] = 0;
cmd[2].m_coord[6] = 0;

cmd[2].m_position[0] = 2.4911;
cmd[2].m_position[1] = 9.9985;
cmd[2].m_position[2] = -9.3233;
cmd[2].m_position[3] = 0.0009;
cmd[2].m_position[4] = 0.6828;
cmd[2].m_position[5] = 2.5016;

cmd[3].cmdType = cmdPara::MOVCA;
cmd[3].m_velocity = 300;
cmd[3].m_acc = 30;
cmd[3].m_dec = 30;
cmd[3].m_pl = 0;
cmd[3].m_spin = 0;

cmd[3].m_coord[0] = 0;
cmd[3].m_coord[1] = 0;
cmd[3].m_coord[2] = 0;
cmd[3].m_coord[3] = 0;
cmd[3].m_coord[4] = 0;
cmd[3].m_coord[5] = 0;
cmd[3].m_coord[6] = 0;

cmd[3].m_position[0] = 8.1872;
cmd[3].m_position[1] = -6.7851;
cmd[3].m_position[2] = 7.0914;
cmd[3].m_position[3] = 0.0018;
cmd[3].m_position[4] = 0.315;
cmd[3].m_position[5] = 8.1897;

cmd[4].cmdType = cmdPara::MOVCA;
cmd[4].m_velocity = 300;
cmd[4].m_acc = 30;
cmd[4].m_dec = 30;
cmd[4].m_pl = 0;
cmd[4].m_spin = 0;

cmd[4].m_coord[0] = 0;
cmd[4].m_coord[1] = 0;
cmd[4].m_coord[2] = 0;
cmd[4].m_coord[3] = 0;
cmd[4].m_coord[4] = 0;
cmd[4].m_coord[5] = 0;
cmd[4].m_coord[6] = 0;

cmd[4].m_position[0] = 21.6441;
cmd[4].m_position[1] = 12.2746;
cmd[4].m_position[2] = -11.2552;
cmd[4].m_position[3] = 0.0042;
cmd[4].m_position[4] = 1.0277;
cmd[4].m_position[5] = 21.6226;

send_continuous_motion_queue(cmd,5);