PDF
AUBO SDK  0.26.0
gripper_interface.h
浏览该文件的文档.
1/** @file gripper_interface.h
2 * @brief 通用夹爪接口
3 */
4#ifndef AUBO_SDK_GRIPPER_INTERFACE_H
5#define AUBO_SDK_GRIPPER_INTERFACE_H
6
7#include <aubo/sync_move.h>
8#include <aubo/trace.h>
9
10namespace arcs {
11namespace common_interface {
12
13/**
14 * \chinese
15 * @defgroup GripperInterface GripperInterface (夹爪)
16 * 通用夹爪API接口
17 * \endchinese
18 *
19 * \english
20 * @defgroup GripperInterface Gripper Interface
21 * Common Gripper API interface
22 * \endenglish
23 */
24class ARCS_ABI_EXPORT GripperInterface
25{
26public:
29
30 /**
31 * @ingroup GripperInterface
32 * \chinese
33 * 获取支持的所有夹爪
34 *
35 * @return
36 * \endchinese
37 */
38 std::vector<std::string> gripperGetSupportedModels();
39
40 /**
41 * @ingroup GripperInterface
42 * \chinese
43 * 扫描该型号下的所有设备
44 *
45 * @param model 夹爪品牌型号
46 * @param device_name 设备名
47 * @return 成功返回设备列表和0,失败返回错误码
48 * \endchinese
49 */
50 ResultWithErrno2 gripperScanDevices(const std::string &model,
51 const std::string &device_name);
52
53 /**
54 * @ingroup GripperInterface
55 * \chinese
56 * 获取已添加的夹爪
57 * @return
58 */
59 std::vector<std::string> gripperGetNames();
60
61 /**
62 * @ingroup GripperInterface
63 * \chinese
64 * 添加夹爪
65 *
66 * @param name 用户自定义名字,唯一
67 * @param model 夹爪品牌及型号
68 * @return 成功返回0,失败返回错误码
69 * \endchinese
70 */
71 int gripperAdd(const std::string &name, const std::string &model);
72
73 /**
74 * @ingroup GripperInterface
75 * \chinese
76 * 删除夹爪
77 *
78 * @param name 用户自定义名字
79 * @return 成功返回0,失败返回错误码
80 * \endchinese
81 */
82 int gripperDelete(const std::string &name);
83
84 /**
85 * @ingroup GripperInterface
86 * \chinese
87 * 修改夹爪名
88 *
89 * @param name
90 * @param new_name 新名字
91 * @return 成功返回0,失败返回错误码
92 * \endchinese
93 */
94 int gripperRename(const std::string &name, const std::string &new_name);
95
96 /**
97 * @ingroup GripperInterface
98 * \chinese
99 * 夹爪连接
100 *
101 * @param name
102 * @param device_name 设备名
103 * @return 成功返回0,失败返回错误码
104 * \endchinese
105 */
106 int gripperConnect(const std::string &name, const std::string &device_name);
107
108 /**
109 * @ingroup GripperInterface
110 * \chinese
111 * 夹爪断开连接
112 *
113 * @param name
114 * @return 成功返回0,失败返回错误码
115 * \endchinese
116 */
117 int gripperDisconnect(const std::string &name);
118
119 /**
120 * @ingroup GripperInterface
121 * \chinese
122 * 夹爪是否连接
123 *
124 * @param name
125 * @return 已连接返回true,未连接返回false
126 * \endchinese
127 */
128 bool gripperIsConnected(const std::string &name);
129
130 /**
131 * @ingroup GripperInterface
132 * \chinese
133 * 设置工作模式
134 *
135 * @param name
136 * @param work_mode 工作模式
137 * @return 成功返回0,失败返回错误码
138 * \endchinese
139 */
140 int gripperSetWorkMode(const std::string &name, int work_mode);
141
142 /**
143 * @ingroup GripperInterface
144 * \chinese
145 * 获取工作模式
146 *
147 * @param name
148 * @return 返回工作模式
149 * \endchinese
150 */
151 int gripperGetWorkMode(const std::string &name);
152
153 /**
154 * @ingroup GripperInterface
155 * \chinese
156 * 设置夹爪安装偏移
157 *
158 * @param name
159 * @param isVisibled 是否显示
160 * @param pose 末端(不包括手指)相对法兰的位姿
161 * @return 成功返回true,失败返回false
162 * \endchinese
163 */
164 int gripperSetMountPose(const std::string &name,
165 const std::vector<double> &pose,
166 bool enable_collision);
167
168 /**
169 * @brief 获取夹爪安装偏移
170 * @param name
171 * @return 返回夹爪安装偏移
172 */
173 std::vector<double> gripperGetMountPose(const std::string &name);
174
175 /**
176 * @ingroup GripperInterface
177 * \chinese
178 * 使能夹爪
179 *
180 * @param name
181 * @return
182 * \endchinese
183 */
184 int gripperEnable(const std::string &name, bool enable);
185
186 /**
187 * @ingroup GripperInterface
188 * \chinese
189 * 夹爪是否使能
190 *
191 * @param name
192 * @return
193 * \endchinese
194 */
195 bool gripperIsEnabled(const std::string &name);
196
197 /**
198 * @ingroup GripperInterface
199 * \chinese
200 * 设置运动参数
201 *
202 * @param name
203 * @param position 位置,单位:m/Pa
204 * @param velocity_percent 速度,单位:%,范围:[0, 1]
205 * @param force 夹持力,单位:N
206 * @param angle 旋转角度,单位:rad
207 * @param r_velocity_percent 旋转速度,单位:%,范围:[0, 1]
208 * @param torque_percent 旋转扭矩,单位:%,范围:[0, 1]
209 *
210 * @return
211 * \endchinese
212 */
213 int gripperSetPosition(const std::string &name, const double position);
214 int gripperSetVelocity(const std::string &name,
215 const double velocity_percent);
216 int gripperSetForce(const std::string &name, const double force);
217 int gripperSetAngle(const std::string &name, const double angle);
218 int gripperSetRVelocity(const std::string &name,
219 const double r_velocity_percent);
220 int gripperSetTorque(const std::string &name, const double torque_percent);
221
222 /**
223 * @ingroup GripperInterface
224 * \chinese
225 * 开始运动
226 *
227 * @param name
228 * @return
229 * \endchinese
230 */
231 int gripperMove(const std::string &name);
232
233 /**
234 * @ingroup GripperInterface
235 * \chinese
236 * 停止运动
237 *
238 * @param name
239 * @return
240 * \endchinese
241 */
242 int gripperStop(const std::string &name);
243
244 /**
245 * @ingroup GripperInterface
246 * \chinese
247 * 获取夹爪状态
248 *
249 * @param name
250 * @return
251 *
252 * @note 位置,速度,夹持力,旋转角度,旋转速度,旋转扭矩的单位与Set接口一致
253 *
254 * \endchinese
255 */
256 std::string gripperGetHardwareVersion(const std::string &name);
257 std::string gripperGetSoftwareVersion(const std::string &name);
258 double gripperGetPosition(const std::string &name);
259 double gripperGetVelocity(const std::string &name);
260 double gripperGetForce(const std::string &name);
261 double gripperGetAngle(const std::string &name);
262 double gripperGetRVelocity(const std::string &name);
263 double gripperGetTorque(const std::string &name);
264 bool gripperGetObjectDetection(const std::string &name);
265 bool gripperGetMotionState(const std::string &name);
266 double gripperGetVoltage(const std::string &name);
267 double gripperGetTemperature(const std::string &name);
268
269 /**
270 * @ingroup GripperInterface
271 * \chinese
272 * 重置modbus从站ID
273 *
274 * @param name
275 * @param slave_id 从站Id
276 * @return
277 * \endchinese
278 */
279 int gripperResetSlaveId(const std::string &name, const int slave_id);
280
281 /**
282 * @ingroup GripperInterface
283 * \chinese
284 * 获取夹爪状态
285 * @param name
286 * @return 状态
287 * \endchinese
288 */
289 int gripperGetStatusCode(const std::string &name);
290
291protected:
292 void *d_;
293};
294using GripperInterfacePtr = std::shared_ptr<GripperInterface>;
295
296} // namespace common_interface
297} // namespace arcs
298
299#endif // AUBO_SDK_GRIPPER_INTERFACE_H
double gripperGetVoltage(const std::string &name)
double gripperGetAngle(const std::string &name)
double gripperGetVelocity(const std::string &name)
int gripperSetRVelocity(const std::string &name, const double r_velocity_percent)
std::string gripperGetSoftwareVersion(const std::string &name)
std::vector< double > gripperGetMountPose(const std::string &name)
获取夹爪安装偏移
double gripperGetTorque(const std::string &name)
int gripperSetAngle(const std::string &name, const double angle)
bool gripperGetObjectDetection(const std::string &name)
double gripperGetForce(const std::string &name)
double gripperGetRVelocity(const std::string &name)
int gripperSetTorque(const std::string &name, const double torque_percent)
int gripperSetVelocity(const std::string &name, const double velocity_percent)
double gripperGetTemperature(const std::string &name)
int gripperSetForce(const std::string &name, const double force)
bool gripperGetMotionState(const std::string &name)
double gripperGetPosition(const std::string &name)
std::vector< std::string > gripperGetSupportedModels()
获取支持的所有夹爪
int gripperSetWorkMode(const std::string &name, int work_mode)
设置工作模式
int gripperEnable(const std::string &name, bool enable)
使能夹爪
int gripperResetSlaveId(const std::string &name, const int slave_id)
重置modbus从站ID
int gripperGetWorkMode(const std::string &name)
获取工作模式
int gripperStop(const std::string &name)
停止运动
int gripperSetMountPose(const std::string &name, const std::vector< double > &pose, bool enable_collision)
设置夹爪安装偏移
bool gripperIsConnected(const std::string &name)
夹爪是否连接
int gripperGetStatusCode(const std::string &name)
获取夹爪状态
int gripperAdd(const std::string &name, const std::string &model)
添加夹爪
int gripperMove(const std::string &name)
开始运动
std::vector< std::string > gripperGetNames()
获取已添加的夹爪
int gripperConnect(const std::string &name, const std::string &device_name)
夹爪连接
ResultWithErrno2 gripperScanDevices(const std::string &model, const std::string &device_name)
扫描该型号下的所有设备
int gripperRename(const std::string &name, const std::string &new_name)
修改夹爪名
int gripperSetPosition(const std::string &name, const double position)
设置运动参数
std::string gripperGetHardwareVersion(const std::string &name)
获取夹爪状态
int gripperDelete(const std::string &name)
删除夹爪
bool gripperIsEnabled(const std::string &name)
夹爪是否使能
int gripperDisconnect(const std::string &name)
夹爪断开连接
std::tuple< std::vector< std::string >, int > ResultWithErrno2
std::shared_ptr< GripperInterface > GripperInterfacePtr
同步运行
向控制器日志系统注入日志方面的接口