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