ARCS SDK API  0.24.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>
11 #include <aubo/robot/io_control.h>
13 #include <aubo/robot/robot_state.h>
16 #include <aubo/global_config.h>
17 
18 namespace arcs {
19 namespace common_interface {
20 
21 class ARCS_ABI_EXPORT RobotInterface
22 {
23 public:
25  virtual ~RobotInterface();
26 
27  /**
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  */
44  RobotConfigPtr getRobotConfig();
45 
46  /**
47  * 获取运动规划接口
48  *
49  * @return MotionControlPtr对象的指针
50  *
51  * @par Python函数原型
52  * getMotionControl(self: pyaubo_sdk.RobotInterface) ->
53  * arcs::common_interface::MotionControl
54  *
55  * @par C++示例
56  * @code
57  * auto rpc_cli = std::make_shared<RpcClient>();
58  * auto robot_name = rpc_cli->getRobotNames().front();
59  * MotionControlPtr ptr =
60  * rpc_cli->getRobotInterface(robot_name)->getMotionControl();
61  * @endcode
62  *
63  */
64  MotionControlPtr getMotionControl();
65 
66  /**
67  * 获取力控接口
68  *
69  * @return ForceControlPtr对象的指针
70  *
71  * @par Python函数原型
72  * getForceControl(self: pyaubo_sdk.RobotInterface) ->
73  * arcs::common_interface::ForceControl
74  *
75  * @par C++示例
76  * @code
77  * auto rpc_cli = std::make_shared<RpcClient>();
78  * auto robot_name = rpc_cli->getRobotNames().front();
79  * ForceControlPtr ptr =
80  * rpc_cli->getRobotInterface(robot_name)->getForceControl();
81  * @endcode
82  *
83  */
84  ForceControlPtr getForceControl();
85 
86  /**
87  * 获取IO控制的接口
88  *
89  * @return IoControlPtr对象的指针
90  *
91  * @par Python函数原型
92  * getIoControl(self: pyaubo_sdk.RobotInterface) ->
93  * arcs::common_interface::IoControl
94  *
95  * @par C++示例
96  * @code
97  * auto rpc_cli = std::make_shared<RpcClient>();
98  * auto robot_name = rpc_cli->getRobotNames().front();
99  * IoControlPtr ptr =
100  * rpc_cli->getRobotInterface(robot_name)->getIoControl();
101  * @endcode
102  *
103  */
104  IoControlPtr getIoControl();
105 
106  /**
107  * 获取同步运动接口
108  *
109  * @return SyncMovePtr对象的指针
110  *
111  * @par Python函数原型
112  * getSyncMove(self: pyaubo_sdk.RobotInterface) ->
113  * arcs::common_interface::SyncMove
114  *
115  * @par C++示例
116  * @code
117  * auto rpc_cli = std::make_shared<RpcClient>();
118  * auto robot_name = rpc_cli->getRobotNames().front();
119  * SyncMovePtr ptr = rpc_cli->getRobotInterface(robot_name)->getSyncMove();
120  * @endcode
121  *
122  */
123  SyncMovePtr getSyncMove();
124 
125  /**
126  * 获取机器人实用算法接口
127  *
128  * @return RobotAlgorithmPtr对象的指针
129  *
130  * @par Python函数原型
131  * getRobotAlgorithm(self: pyaubo_sdk.RobotInterface) ->
132  * arcs::common_interface::RobotAlgorithm
133  *
134  * @par C++示例
135  * @code
136  * auto rpc_cli = std::make_shared<RpcClient>();
137  * auto robot_name = rpc_cli->getRobotNames().front();
138  * RobotAlgorithmPtr ptr =
139  * rpc_cli->getRobotInterface(robot_name)->getRobotAlgorithm();
140  * @endcode
141  *
142  */
143  RobotAlgorithmPtr getRobotAlgorithm();
144 
145  /**
146  * 获取机器人管理接口(上电、启动、停止等)
147  *
148  * @return RobotManagePtr对象的指针
149  *
150  * @par Python函数原型
151  * getRobotManage(self: pyaubo_sdk.RobotInterface) ->
152  * arcs::common_interface::RobotManage
153  *
154  * @par C++示例
155  * @code
156  * auto rpc_cli = std::make_shared<RpcClient>();
157  * auto robot_name = rpc_cli->getRobotNames().front();
158  * RobotManagePtr ptr =
159  * rpc_cli->getRobotInterface(robot_name)->getRobotManage();
160  * @endcode
161  *
162  */
163  RobotManagePtr getRobotManage();
164 
165  /**
166  * 获取机器人状态接口
167  *
168  * @return RobotStatePtr对象的指针
169  *
170  * @par Python函数原型
171  * getRobotState(self: pyaubo_sdk.RobotInterface) ->
172  * arcs::common_interface::RobotState
173  *
174  * @par C++示例
175  * @code
176  * auto rpc_cli = std::make_shared<RpcClient>();
177  * auto robot_name = rpc_cli->getRobotNames().front();
178  * RobotStatePtr ptr =
179  * rpc_cli->getRobotInterface(robot_name)->getRobotState();
180  * @endcode
181  *
182  */
183  RobotStatePtr getRobotState();
184 
185  /**
186  * 获取告警信息接口
187  *
188  * @return TracePtr对象的指针
189  *
190  * @par Python函数原型
191  * getTrace(self: pyaubo_sdk.RobotInterface) ->
192  * arcs::common_interface::Trace
193  *
194  * @par C++示例
195  * @code
196  * auto rpc_cli = std::make_shared<RpcClient>();
197  * auto robot_name = rpc_cli->getRobotNames().front();
198  * TracePtr ptr = rpc_cli->getRobotInterface(robot_name)->getTrace();
199  * @endcode
200  *
201  */
202  TracePtr getTrace();
203 
204 protected:
205  void *d_;
206 };
207 using RobotInterfacePtr = std::shared_ptr<RobotInterface>;
208 
209 // clang-format off
210 #define RobotInterface_DECLARES \
211  _FUNC(RobotInterface, 0, getRobotConfig) \
212  _FUNC(RobotInterface, 0, getMotionControl) \
213  _FUNC(RobotInterface, 0, getForceControl) \
214  _FUNC(RobotInterface, 0, getIoControl) \
215  _FUNC(RobotInterface, 0, getSyncMove) \
216  _FUNC(RobotInterface, 0, getRobotAlgorithm) \
217  _FUNC(RobotInterface, 0, getRobotManage) \
218  _FUNC(RobotInterface, 0, getRobotState) \
219  _FUNC(RobotInterface, 0, getTrace)
220 // clang-format on
221 
222 } // namespace common_interface
223 } // namespace arcs
224 
225 #endif // AUBO_SDK_ROBOT_INTERFACE_H
机器人管理接口,如上电、启动、拖动示教模式等
运动控制接口
向控制器日志系统注入日志方面的接口
std::shared_ptr< RobotInterface > RobotInterfacePtr
力控接口
IO控制接口
std::shared_ptr< MotionControl > MotionControlPtr
std::shared_ptr< RobotState > RobotStatePtr
Definition: robot_state.h:1291
std::shared_ptr< Trace > TracePtr
Definition: trace.h:154
std::shared_ptr< ForceControl > ForceControlPtr
std::shared_ptr< SyncMove > SyncMovePtr
Definition: sync_move.h:213
std::shared_ptr< RobotConfig > RobotConfigPtr
机器人算法相关的对外接口
获取机器人状态接口,如关节速度、关节角度、固件/硬件版本
std::shared_ptr< RobotManage > RobotManagePtr
Definition: robot_manage.h:660
获取机器人配置接口,如获取DH参数、碰撞等级、安装位姿等等
std::shared_ptr< IoControl > IoControlPtr
Definition: io_control.h:2085
Definition: aubo_api.h:17
std::shared_ptr< RobotAlgorithm > RobotAlgorithmPtr
同步运行