PDF
AUBO SDK  0.26.0
robot_interface.h
浏览该文件的文档.
1/** @file robot_interface.h
2 * @brief 机器人API 接口
3 */
4#ifndef AUBO_SDK_ROBOT_INTERFACE_H
5#define AUBO_SDK_ROBOT_INTERFACE_H
6
7#include <aubo/sync_move.h>
8#include <aubo/trace.h>
16#include <aubo/global_config.h>
17
18namespace arcs {
19namespace common_interface {
20
21/**
22 * \chinese
23 * @defgroup RobotInterface RobotInterface(机器人模块)
24 * 机器人模块
25 * \endchinese
26 *
27 * \english
28 * @defgroup RobotInterface Robot Module
29 * Robot Module
30 * \endenglish
31 */
32class ARCS_ABI_EXPORT RobotInterface
33{
34public:
36 virtual ~RobotInterface();
37
38 /**
39 * @ingroup RobotInterface
40 * @ref RobotConfig
41 * \chinese
42 * 获取RobotConfig接口
43 *
44 * @return RobotConfigPtr对象的指针
45 *
46 * @par Python函数原型
47 * getRobotConfig(self: pyaubo_sdk.RobotInterface) ->
48 * arcs::common_interface::RobotConfig
49 *
50 * @par C++示例
51 * @code
52 * auto rpc_cli = std::make_shared<RpcClient>();
53 * auto robot_name = rpc_cli->getRobotNames().front();
54 * RobotConfigPtr ptr =
55 * rpc_cli->getRobotInterface(robot_name)->getRobotConfig();
56 * @endcode
57 * \endchinese
58 * \english
59 * Get RobotConfig interface
60 *
61 * @return Pointer to RobotConfig object
62 *
63 * @par Python function prototype
64 * getRobotConfig(self: pyaubo_sdk.RobotInterface) ->
65 * arcs::common_interface::RobotConfig
66 *
67 * @par C++ example
68 * @code
69 * auto rpc_cli = std::make_shared<RpcClient>();
70 * auto robot_name = rpc_cli->getRobotNames().front();
71 * RobotConfigPtr ptr =
72 * rpc_cli->getRobotInterface(robot_name)->getRobotConfig();
73 * @endcode
74 * \endenglish
75 */
76
78
79 /**
80 * @ingroup RobotInterface
81 * @ref MotionControl
82 * \chinese
83 * 获取运动规划接口
84 *
85 * @return MotionControlPtr对象的指针
86 *
87 * @par Python函数原型
88 * getMotionControl(self: pyaubo_sdk.RobotInterface) ->
89 * arcs::common_interface::MotionControl
90 *
91 * @par C++示例
92 * @code
93 * auto rpc_cli = std::make_shared<RpcClient>();
94 * auto robot_name = rpc_cli->getRobotNames().front();
95 * MotionControlPtr ptr =
96 * rpc_cli->getRobotInterface(robot_name)->getMotionControl();
97 * @endcode
98 * \endchinese
99 * \english
100 * Get motion planning interface
101 *
102 * @return Pointer to MotionControl object
103 *
104 * @par Python function prototype
105 * getMotionControl(self: pyaubo_sdk.RobotInterface) ->
106 * arcs::common_interface::MotionControl
107 *
108 * @par C++ example
109 * @code
110 * auto rpc_cli = std::make_shared<RpcClient>();
111 * auto robot_name = rpc_cli->getRobotNames().front();
112 * MotionControlPtr ptr =
113 * rpc_cli->getRobotInterface(robot_name)->getMotionControl();
114 * @endcode
115 * \endenglish
116 */
118
119 /**
120 * @ingroup RobotInterface
121 * @ref ForceControl
122 * \chinese
123 * 获取力控接口
124 *
125 * @return ForceControlPtr对象的指针
126 *
127 * @par Python函数原型
128 * getForceControl(self: pyaubo_sdk.RobotInterface) ->
129 * arcs::common_interface::ForceControl
130 *
131 * @par C++示例
132 * @code
133 * auto rpc_cli = std::make_shared<RpcClient>();
134 * auto robot_name = rpc_cli->getRobotNames().front();
135 * ForceControlPtr ptr =
136 * rpc_cli->getRobotInterface(robot_name)->getForceControl();
137 * @endcode
138 * \endchinese
139 * \english
140 * Get force control interface
141 *
142 * @return Pointer to ForceControl object
143 *
144 * @par Python function prototype
145 * getForceControl(self: pyaubo_sdk.RobotInterface) ->
146 * arcs::common_interface::ForceControl
147 *
148 * @par C++ example
149 * @code
150 * auto rpc_cli = std::make_shared<RpcClient>();
151 * auto robot_name = rpc_cli->getRobotNames().front();
152 * ForceControlPtr ptr =
153 * rpc_cli->getRobotInterface(robot_name)->getForceControl();
154 * @endcode
155 * \endenglish
156 */
158
159 /**
160 * @ingroup RobotInterface
161 * @ref IoControl
162 * \chinese
163 * 获取IO控制的接口
164 *
165 * @return IoControlPtr对象的指针
166 *
167 * @par Python函数原型
168 * getIoControl(self: pyaubo_sdk.RobotInterface) ->
169 * arcs::common_interface::IoControl
170 *
171 * @par C++示例
172 * @code
173 * auto rpc_cli = std::make_shared<RpcClient>();
174 * auto robot_name = rpc_cli->getRobotNames().front();
175 * IoControlPtr ptr =
176 * rpc_cli->getRobotInterface(robot_name)->getIoControl();
177 * @endcode
178 * \endchinese
179 * \english
180 * Get IO control interface
181 *
182 * @return Pointer to IoControl object
183 *
184 * @par Python function prototype
185 * getIoControl(self: pyaubo_sdk.RobotInterface) ->
186 * arcs::common_interface::IoControl
187 *
188 * @par C++ example
189 * @code
190 * auto rpc_cli = std::make_shared<RpcClient>();
191 * auto robot_name = rpc_cli->getRobotNames().front();
192 * IoControlPtr ptr =
193 * rpc_cli->getRobotInterface(robot_name)->getIoControl();
194 * @endcode
195 * \endenglish
196 */
198
199 /**
200 * @ingroup RobotInterface
201 * @ref SyncMove
202 * \chinese
203 * 获取同步运动接口
204 *
205 * @return SyncMovePtr对象的指针
206 *
207 * @par Python函数原型
208 * getSyncMove(self: pyaubo_sdk.RobotInterface) ->
209 * arcs::common_interface::SyncMove
210 *
211 * @par C++示例
212 * @code
213 * auto rpc_cli = std::make_shared<RpcClient>();
214 * auto robot_name = rpc_cli->getRobotNames().front();
215 * SyncMovePtr ptr = rpc_cli->getRobotInterface(robot_name)->getSyncMove();
216 * @endcode
217 * \endchinese
218 * \english
219 * Get synchronized motion interface
220 *
221 * @return Pointer to SyncMove object
222 *
223 * @par Python function prototype
224 * getSyncMove(self: pyaubo_sdk.RobotInterface) ->
225 * arcs::common_interface::SyncMove
226 *
227 * @par C++ example
228 * @code
229 * auto rpc_cli = std::make_shared<RpcClient>();
230 * auto robot_name = rpc_cli->getRobotNames().front();
231 * SyncMovePtr ptr = rpc_cli->getRobotInterface(robot_name)->getSyncMove();
232 * @endcode
233 * \endenglish
234 */
236
237 /**
238 * @ingroup RobotInterface
239 * @ref RobotAlgorithm
240 * \chinese
241 * 获取机器人实用算法接口
242 *
243 * @return RobotAlgorithmPtr对象的指针
244 *
245 * @par Python函数原型
246 * getRobotAlgorithm(self: pyaubo_sdk.RobotInterface) ->
247 * arcs::common_interface::RobotAlgorithm
248 *
249 * @par C++示例
250 * @code
251 * auto rpc_cli = std::make_shared<RpcClient>();
252 * auto robot_name = rpc_cli->getRobotNames().front();
253 * RobotAlgorithmPtr ptr =
254 * rpc_cli->getRobotInterface(robot_name)->getRobotAlgorithm();
255 * @endcode
256 * \endchinese
257 * \english
258 * Get robot utility algorithm interface
259 *
260 * @return Pointer to RobotAlgorithm object
261 *
262 * @par Python function prototype
263 * getRobotAlgorithm(self: pyaubo_sdk.RobotInterface) ->
264 * arcs::common_interface::RobotAlgorithm
265 *
266 * @par C++ example
267 * @code
268 * auto rpc_cli = std::make_shared<RpcClient>();
269 * auto robot_name = rpc_cli->getRobotNames().front();
270 * RobotAlgorithmPtr ptr =
271 * rpc_cli->getRobotInterface(robot_name)->getRobotAlgorithm();
272 * @endcode
273 * \endenglish
274 */
276
277 /**
278 * @ingroup RobotInterface
279 * @ref RobotManage
280 * \chinese
281 * 获取机器人管理接口(上电、启动、停止等)
282 *
283 * @return RobotManagePtr对象的指针
284 *
285 * @par Python函数原型
286 * getRobotManage(self: pyaubo_sdk.RobotInterface) ->
287 * arcs::common_interface::RobotManage
288 *
289 * @par C++示例
290 * @code
291 * auto rpc_cli = std::make_shared<RpcClient>();
292 * auto robot_name = rpc_cli->getRobotNames().front();
293 * RobotManagePtr ptr =
294 * rpc_cli->getRobotInterface(robot_name)->getRobotManage();
295 * @endcode
296 * \endchinese
297 * \english
298 * Get robot management interface (power on, start, stop, etc.)
299 *
300 * @return Pointer to RobotManage object
301 *
302 * @par Python function prototype
303 * getRobotManage(self: pyaubo_sdk.RobotInterface) ->
304 * arcs::common_interface::RobotManage
305 *
306 * @par C++ example
307 * @code
308 * auto rpc_cli = std::make_shared<RpcClient>();
309 * auto robot_name = rpc_cli->getRobotNames().front();
310 * RobotManagePtr ptr =
311 * rpc_cli->getRobotInterface(robot_name)->getRobotManage();
312 * @endcode
313 * \endenglish
314 */
316
317 /**
318 * @ingroup RobotInterface
319 * @ref RobotState
320 * \chinese
321 * 获取机器人状态接口
322 *
323 * @return RobotStatePtr对象的指针
324 *
325 * @par Python函数原型
326 * getRobotState(self: pyaubo_sdk.RobotInterface) ->
327 * arcs::common_interface::RobotState
328 *
329 * @par C++示例
330 * @code
331 * auto rpc_cli = std::make_shared<RpcClient>();
332 * auto robot_name = rpc_cli->getRobotNames().front();
333 * RobotStatePtr ptr =
334 * rpc_cli->getRobotInterface(robot_name)->getRobotState();
335 * @endcode
336 * \endchinese
337 * \english
338 * Get robot state interface
339 *
340 * @return Pointer to RobotState object
341 *
342 * @par Python function prototype
343 * getRobotState(self: pyaubo_sdk.RobotInterface) ->
344 * arcs::common_interface::RobotState
345 *
346 * @par C++ example
347 * @code
348 * auto rpc_cli = std::make_shared<RpcClient>();
349 * auto robot_name = rpc_cli->getRobotNames().front();
350 * RobotStatePtr ptr =
351 * rpc_cli->getRobotInterface(robot_name)->getRobotState();
352 * @endcode
353 * \endenglish
354 */
356
357 /**
358 * @ingroup RobotInterface
359 * @ref Trace
360 * \chinese
361 * 获取告警信息接口
362 *
363 * @return TracePtr对象的指针
364 *
365 * @par Python函数原型
366 * getTrace(self: pyaubo_sdk.RobotInterface) ->
367 * arcs::common_interface::Trace
368 *
369 * @par C++示例
370 * @code
371 * auto rpc_cli = std::make_shared<RpcClient>();
372 * auto robot_name = rpc_cli->getRobotNames().front();
373 * TracePtr ptr = rpc_cli->getRobotInterface(robot_name)->getTrace();
374 * @endcode
375 * \endchinese
376 * \english
377 * Get alarm information interface
378 *
379 * @return Pointer to Trace object
380 *
381 * @par Python function prototype
382 * getTrace(self: pyaubo_sdk.RobotInterface) ->
383 * arcs::common_interface::Trace
384 *
385 * @par C++ example
386 * @code
387 * auto rpc_cli = std::make_shared<RpcClient>();
388 * auto robot_name = rpc_cli->getRobotNames().front();
389 * TracePtr ptr = rpc_cli->getRobotInterface(robot_name)->getTrace();
390 * @endcode
391 * \endenglish
392 */
394
395protected:
396 void *d_;
397};
398using RobotInterfacePtr = std::shared_ptr<RobotInterface>;
399
400} // namespace common_interface
401} // namespace arcs
402
403#endif // AUBO_SDK_ROBOT_INTERFACE_H
RobotStatePtr getRobotState()
RobotState (机器人状态查询) 获取机器人状态接口
RobotConfigPtr getRobotConfig()
RobotConfig (机器人配置管理) 获取RobotConfig接口
IoControlPtr getIoControl()
IoControl (IO输入输出控制) 获取IO控制的接口
TracePtr getTrace()
Trace (日志与弹窗) 获取告警信息接口
ForceControlPtr getForceControl()
ForceControl(力控模块) 获取力控接口
MotionControlPtr getMotionControl()
MotionControl (运动规划与控制) 获取运动规划接口
RobotManagePtr getRobotManage()
RobotManage (机器人生命周期管理) 获取机器人管理接口(上电、启动、停止等)
RobotAlgorithmPtr getRobotAlgorithm()
RobotAlgorithm (机器人算法工具) 获取机器人实用算法接口
SyncMovePtr getSyncMove()
SyncMove (同步运动控制和轴组管理) 获取同步运动接口
IO控制接口
运动控制接口
std::shared_ptr< RobotManage > RobotManagePtr
std::shared_ptr< RobotInterface > RobotInterfacePtr
std::shared_ptr< Trace > TracePtr
std::shared_ptr< MotionControl > MotionControlPtr
std::shared_ptr< ForceControl > ForceControlPtr
std::shared_ptr< IoControl > IoControlPtr
std::shared_ptr< SyncMove > SyncMovePtr
std::shared_ptr< RobotConfig > RobotConfigPtr
std::shared_ptr< RobotAlgorithm > RobotAlgorithmPtr
std::shared_ptr< RobotState > RobotStatePtr
机器人算法相关的对外接口
获取机器人配置接口,如获取DH参数、碰撞等级、安装位姿等等
机器人管理接口,如上电、启动、拖动示教模式等
获取机器人状态接口,如关节速度、关节角度、固件/硬件版本
同步运行
向控制器日志系统注入日志方面的接口