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