指令控制机械臂及相关接口调用说明#
方案二:在终端中使用指令对机械臂进行控制#
我们可以通过RobotControl,RobotIoControl和RobotMove的指令,分别对机械臂的电源使能,输入输出和移动进行控制。
注意:
以下指令中的‘:’后都需要有空格
指令中的参数可以从src/duco_msg/srv中寻找相关的srv文件查看所需参数和参数类型
我们使用指令前,需要完成之前章节的配置过程及功能包的编译。
完成之前准备工作后,我们来到src资源包的目录下,打开目录下终端,将所需指令输入终端进行运行。
下面我们将详细介绍可用指令:
RobotControl#
对于机器的电源和使能进行控制。
输入参数:
string command: 指令
int8 arm_num: 机械臂编号,设置为0
bool block: 指令是否阻塞型指令,如果为false表示非阻塞指令,指令会立即返回,默认为阻塞
string response: 返回值为String
command列表:
poweron(上电)
enable(使能)
disable(断使能)
poweroff(断电)
指令模版:
1ros2 service call /duco_robot/robot_control duco_msg/srv/RobotControl "{command: "", arm_num: , block: }"
指令示例:
1ros2 service call /duco_robot/robot_control duco_msg/srv/RobotControl "{command: "poweron", arm_num: 0, block: true}"

RobotIoControl#
对于通用输出和输入分别进行设置和获取。
输入参数:
string command: 指令
int8 arm_num: 机械臂编号,设置为0
int8 type: IO 类型, 0 为 gen io, 1 为 tool io
int8 port: IO 端口,GEN IO 范围 1-16 TOOL IO 范围 0-1
bool value: SetIO 值
bool block: 指令是否阻塞型指令,如果为false表示非阻塞指令,指令会立即返回,默认为阻塞
string response: 返回值为String
command列表:
setIo(设置通用输出)
getIo(获取通用输入)
指令模版:
1ros2 service call /duco_robot/robot_io_control duco_msg/srv/RobotIoControl "{command: "", arm_num: , type: , port: , value: , block: }"
指令示例:
1ros2 service call /duco_robot/robot_io_control duco_msg/srv/RobotIoControl "{command: "setIo", arm_num: 0, type: 0, port: 1, value: true, block: true}"![]()
RobotMove#
控制机械臂的移动。
输入参数:
string command: 指令
int8 arm_num: 机械臂编号,设置为0
float32[] p: 笛卡尔目标位置
float32[] q: 目标机器人关节角位置,单位(rad)
float32 v: 最大末端线速度,范围[0.01, 5],单位m/s,当x、y、z均为0时,线速度按比例换算成角速度
float32 a: 最大末端线加速度,范围[0.01, ∞],单位(m/s2)
float32 r: 轨迹融合半径,单位m,默认值为 0,表示无融合。当数值大于0时表示与下一条运动融合
string tool: 设置使用的工具的名称,默认为当前使用的工具("default")
string wobj: 设置使用的工件坐标系的名称,默认为当前使用的工件坐标系("default")
bool block: 指令是否阻塞型指令,如果为false表示非阻塞指令,指令会立即返回,默认为阻塞
string response: 返回值为String
command列表:
movej(控制机械臂从当前状态, 按照关节运动的方式移动到目标关节角状态)
movej2(控制机械臂从当前状态,按照各关节相位同步运动的方式移动到目标关节角状态)
movejpose(控制机械臂从当前状态, 按照关节运动的方式移动到末端目标位置)
movejpose2(控制机械臂从当前状态,按照各关节相位同步运动的方式移动到末端目标位置)
movel(控制机械臂末端从当前状态按照直线路径移动到目标位姿)
movetcp(控制机械臂沿工具坐标系直线移动一个增量)
指令模版:
1ros2 service call /duco_robot/robot_move duco_msg/srv/RobotMove "{command: "", arm_num: , v: , a: , r: , tool: "", wobj: "", block: , q: [,,,,,], p: [,,,,,]}"
指令示例:
1ros2 service call /duco_robot/robot_move duco_msg/srv/RobotMove "{command: "movejpose",arm_num: 0,v: 1,a: 1,r: 0,tool: "default", wobj: "default", block: true, q: [1,1,1,1,1,1], p: [0.49,0.14,0.44,-1.14,0,-1.57]}"

API说明#
RobotControl#
1/**
2 * @brief 机器人上电
3 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
4 * @return 阻塞执行代表任务结束时状态, 非阻塞执行代表任务的ID
5 */
6int32_t power_on(bool block)
7// 例子:
8power_on(true)
9
10/**
11 * @brief 机器人下电
12 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
13 * @return 阻塞执行代表任务结束时状态, 非阻塞执行代表任务的ID
14 */
15int32_t power_off(bool block)
16// 例子:
17power_off(true)
18
19/**
20 * @brief 机器人上使能
21 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
22 * @return 阻塞执行代表任务结束时状态, 非阻塞执行代表任务的ID
23 */
24int32_t enable(bool block) ;
25// 例子:
26enable(true)
27
28/**
29 * @brief 机器人下使能
30 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
31 * @return 阻塞执行代表任务结束时状态, 非阻塞执行代表任务的ID
32 */
33int32_t disable(bool block) ;
34// 例子:
35disable(true)
RobotIoControl#
1 /**
2 * @brief 读取机械臂末端的IO输入口的高低电平, 返回true为高电平, false为低电平
3 * @param num 机械臂末端的IO输出口序号, 范围从1-2
4 * @return true为高电平, false为低电平
5 */
6bool get_tool_digital_in(int16_t num) ;
7//例子:
8get_tool_digital_in(1)
9
10/**
11 * @brief 读取控制柜上的用户IO输入口的高低电平, 返回true为高电平, false为低电平
12 * @param num 控制柜上的IO输入口序号, 范围从1-16
13 * @return true为高电平, false为低电平
14 */
15bool get_standard_digital_in(int16_t num) ;
16// 例子:
17get_standard_digital_in(1)
18
19 /**
20 * @brief set_tool_digital_out
21 * @param num 机械臂末端的IO输出口序号, 范围从1-2
22 * @param value true为高电平, false为低电平
23 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
24 * @return 阻塞执行代表任务结束时状态, 非阻塞执行代表任务的ID
25 */
26int32_t set_tool_digital_out(int16_t num, bool value, bool block) ;
27//例子:
28set_tool_digital_out(1, true, true)
29
30/**
31 * @brief 该函数可控制控制柜上的IO输出口的高低电平
32 * @param num 控制柜上的IO输出口序号, 范围从1-16
33 * @param value true为高电平, false为低电平
34 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
35 * @return 阻塞执行代表任务结束时状态, 非阻塞执行代表任务的ID
36 */
37int32_t set_standard_digital_out(int16_t num, bool value, bool block) ;
38// 例子:
39set_standard_digital_out(1, true, true)
RobotMove#
1 /**
2 * @brief 控制机械臂从当前状态, 按照关节运动的方式移动到目标关节角状态
3 * @param joints_list 1-6关节的目标关节角度, 单位: rad
4 * @param v 关节角速度, 单位: 系统设定速度的百分比%, 取值范围(0,100]
5 * @param a 关节角加速度, 单位: 系统设定加速度的百分比%, 取值范围(0,100]
6 * @param r 融合半径, 单位: 系统设定最大融合半径的百分比%, 默认值为 0, 表示无融合, 取值范围[0,50)
7 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
8 * @param op 可缺省参数
9 * @param def_acc 是否使用系统默认加速度, false表示使用自定义的加速度值, true表示使用系统自动规划的加速度值, 可缺省, 默认为false
10 * @return 当配置为阻塞执行, 返回值代表当前任务结束时的状态, 若无融合为Finished, 若有融合为Interrupt.
11 * 当配置为非阻塞执行, 返回值代表当前任务的id, 用户可以调用get_noneblock_taskstate(id)函数查询当前任务的执行状态
12 */
13int32_t movej(const std::vector<double> & joints_list, double v, double a, double r, bool block, const OP &op = _op, bool def_acc = false) ;
14// 例子:
15movej([1,1,1,1,1,1], 1, 1, 0, true)
16
17/**
18 * @brief 控制机械臂从当前状态, 按照关节运动的方式移动到目标关节角状态
19 * @param joints_list 1-6关节的目标关节角度, 单位: rad
20 * @param v 关节角速度, 范围[0.01*PI/180, 1.25*PI],单位: rad/s
21 * @param a 关节角加速度, 范围[0.01*PI/180, 12.5*PI],单位: rad/s^2
22 * @param r 融合半径, 单位: m, 默认值为 0, 表示无融合.当数值大于0时表示与下一条运动融合
23 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
24 * @param op 可缺省参数
25 * @param def_acc 是否使用系统默认加速度, false表示使用自定义的加速度值, true表示使用系统自动规划的加速度值, 可缺省, 默认为false
26 * @return 当配置为阻塞执行, 返回值代表当前任务结束时的状态, 若无融合为Finished, 若有融合为Interrupt.
27 * 当配置为非阻塞执行, 返回值代表当前任务的id, 用户可以调用get_noneblock_taskstate(id)函数查询当前任务的执行状态
28 */
29int32_t movej2(const std::vector<double> & joints_list, double v, double a, double r, bool block, const OP &op = _op, bool def_acc = false) ;
30// 例子:
31 movej2([1,1,1,1,1,1], 1, 1, 0, true)
32
33 /**
34 * @brief 控制机械臂从当前状态, 按照关节运动的方式移动到末端目标位置
35 * @param p 对应末端的位姿, 位置单位: m, 姿态以Rx、Ry、Rz表示, 单位: rad
36 * @param v 关节角速度, 单位: 系统设定速度的百分比%, 取值范围(0,100]
37 * @param a 关节加速度, 单位: 系统设定加速度的百分比%, 取值范围(0,100]
38 * @param r 融合半径, 单位: 系统设定最大融合半径的百分比%, 默认值为 0, 表示无融合, 取值范围[0,50)
39 * @param q_near 目标点附近位置对应的关节角度, 用于确定逆运动学选解, 为空时使用当前位置
40 * @param tool 设置使用的工具的名称, 为空时默认为当前使用的工具
41 * @param wobj 设置使用的工件坐标系的名称, 为空时默认为当前使用的工件坐标系
42 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
43 * @param op 可缺省参数
44 * @param def_acc 是否使用系统默认加速度, false表示使用自定义的加速度值, true表示使用系统自动规划的加速度值, 可缺省, 默认为false
45 * @return 当配置为阻塞执行, 返回值代表当前任务结束时的状态, 若无融合为Finished, 若有融合为Interrupt.
46 * 当配置为非阻塞执行, 返回值代表当前任务的id, 用户可以调用get_noneblock_taskstate(id)函数查询当前任务的执行状态
47 */
48int32_t movej_pose(const std::vector<double> & p, double v, double a, double r, const std::vector<double> & q_near, const std::string& tool, const std::string& wobj, bool block, const OP &op = _op, bool def_acc = false) ;
49// 例子:
50movej_pose([0.49,0.14,0.44,-1.14,0,-1.57], 1, 1, 0, [1,1,1,1,1,1], "default", "default", true)
51
52/**
53 * @brief 控制机械臂从当前状态, 按照关节运动的方式移动到末端目标位置
54 * @param p 对应末端的位姿, 位置单位: m, 姿态以Rx、Ry、Rz表示, 单位: rad
55 * @param v 关节角速度, 范围[0.01*PI/180, 1.25*PI],单位: rad/s
56 * @param a 关节加速度, 范围[0.01*PI/180, 12.5*PI],单位: rad/s^2
57 * @param r 融合半径, 单位: m, 默认值为 0, 表示无融合.当数值大于0时表示与下一条运动融合
58 * @param q_near 目标点附近位置对应的关节角度, 用于确定逆运动学选解, 为空时使用当前位置
59 * @param tool 设置使用的工具的名称, 为空时默认为当前使用的工具
60 * @param wobj 设置使用的工件坐标系的名称, 为空时默认为当前使用的工件坐标系
61 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
62 * @param op 可缺省参数
63 * @param def_acc 是否使用系统默认加速度, false表示使用自定义的加速度值, true表示使用系统自动规划的加速度值, 可缺省, 默认为false
64 * @return 当配置为阻塞执行, 返回值代表当前任务结束时的状态, 若无融合为Finished, 若有融合为Interrupt.
65 * 当配置为非阻塞执行, 返回值代表当前任务的id, 用户可以调用get_noneblock_taskstate(id)函数查询当前任务的执行状态
66 */
67int32_t movej_pose2(const std::vector<double> & p, double v, double a, double r, const std::vector<double> & q_near, const std::string& tool, const std::string& wobj, bool block, const OP &op = _op, bool def_acc = false) ;
68// 例子:
69movej_pose2([0.49,0.14,0.44,-1.14,0,-1.57], 1, 1, 0, [1,1,1,1,1,1], "default", "default", true)
70
71/**
72 * @brief 控制机械臂末端从当前状态按照直线路径移动到目标状态
73 * @param p 对应末端的位姿, 位置单位: m, 姿态以Rx、Ry、Rz表示, 单位: rad
74 * @param v 末端速度, 范围[0.00001, 5],单位: m/s
75 * @param a 末端加速度, 范围[0.00001, ∞],单位: m/s^2
76 * @param r 融合半径, 单位: m, 默认值为 0, 表示无融合.当数值大于0时表示与下一条运动融合
77 * @param q_near 目标点附近位置对应的关节角度, 用于确定逆运动学选解, 为空时使用当前位置
78 * @param tool 设置使用的工具的名称, 为空时默认为当前使用的工具
79 * @param wobj 设置使用的工件坐标系的名称, 为空时默认为当前使用的工件坐标系
80 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
81 * @param op 可缺省参数
82 * @param def_acc 是否使用系统默认加速度, false表示使用自定义的加速度值, true表示使用系统自动规划的加速度值, 可缺省, 默认为false
83 * @return 当配置为阻塞执行, 返回值代表当前任务结束时的状态, 若无融合为Finished, 若有融合为Interrupt.
84 * 当配置为非阻塞执行, 返回值代表当前任务的id, 用户可以调用get_noneblock_taskstate(id)函数查询当前任务的执行状态
85 */
86int32_t movel(const std::vector<double> & p, double v, double a, double r, const std::vector<double> & q_near, const std::string& tool = "default", const std::string& wobj = "default", bool block = true, const OP &op = _op, bool def_acc = false) ;
87// 例子:
88movel([0.49,0.14,0.44,-1.14,0,-1.57], 1, 1, 0, [1,1,1,1,1,1])
89
90/**
91 * @brief 控制机械臂沿工具坐标系直线移动一个增量
92 * @param pose_offset 工具坐标系下的位姿偏移量
93 * @param v 直线移动的速度, 范围[0.00001, 5],单位: m/s, 当x、y、z均为0时, 线速度按比例换算成角速度
94 * @param a 加速度, 范围[0.00001, ∞],单位: m/s^2
95 * @param r 融合半径, 单位: m, 默认值为 0, 表示无融合.当数值大于0时表示与下一条运动融合
96 * @param tool 设置使用的工具坐标系的名称, 为空时默认为当前使用的工具坐标系
97 * @param block 是否阻塞, 如果为false表示非阻塞指令, 指令会立即返回
98 * @param op 可缺省参数
99 * @param def_acc 是否使用系统默认加速度, false表示使用自定义的加速度值, true表示使用系统自动规划的加速度值, 可缺省, 默认为false
100 * @return 当配置为阻塞执行, 返回值代表当前任务结束时的状态, 若无融合为Finished, 若有融合为Interrupt.
101 * 当配置为非阻塞执行, 返回值代表当前任务的id, 用户可以调用get_noneblock_taskstate(id)函数查询当前任务的执行状态
102 */
103int32_t tcp_move(const std::vector<double> & pose_offset, double v, double a, double r, const std::string& tool, bool block, const OP &op = _op, bool def_acc = false) ;
104// 例子:
105movetcp([0.49,0.14,0.44,-1.14,0,-1.57], 1, 1, 0, "default", "default")