1+ #include < stdint.h>
2+
3+ #include " protocol_logic.hpp"
4+
5+ /* *
6+ * @brief This class contains high level gripper commands and status
7+ */
8+
9+ namespace hande_driver
10+ {
11+ struct {
12+ bool isReset;
13+ bool isReady;
14+ bool isMoving;
15+ bool isStopped;
16+ bool isOpened;
17+ bool isClosed;
18+ bool objectDetected;
19+ } Status;
20+
21+ struct { // Structure declaration
22+ int myNum; // Member (int variable)
23+ string myString; // Member (string variable)
24+ } FaultStatus;
25+
26+ class ApplicationLayer {
27+ public:
28+ ApplicationLayer ();
29+
30+ ~ApplicationLayer ();
31+
32+ /* *
33+ * @brief Stops movement of the gripper
34+ *
35+ * @param none
36+ * @return none
37+ * @note see status on success, exception thrown if communicatoin issues
38+ */
39+ void stop ();
40+
41+ /* *
42+ * @brief Resets the gripper: deactivate and activate again
43+ *
44+ * @param none
45+ * @return none
46+ * @note see status on success, exception thrown if communicatoin issues
47+ */
48+ void reset ();
49+
50+ /* *
51+ * Emergency auto-release, gripper fingers are slowly opened, reactivation necessary
52+ *
53+ * @param none
54+ * @return none
55+ * @note see status on success, exception thrown if communicatoin issues
56+ */
57+ void auto_release ();
58+
59+ /* *
60+ * @brief Activates the gripper, after that it can be used
61+ *
62+ * @param none
63+ * @return none
64+ * @note see status on success, exception thrown if communicatoin issues
65+ */
66+ void activate ();
67+
68+ /* *
69+ * @brief Opens the gripper
70+ *
71+ * @param none
72+ * @return none
73+ * @note see status on success, exception thrown if communicatoin issues
74+ */
75+ void open ();
76+
77+ /* *
78+ * @brief Closes the gripper
79+ *
80+ * @param none
81+ * @return none
82+ * @note see status on success, exception thrown if communicatoin issues
83+ */
84+ void close ();
85+
86+ /* *
87+ * @brief Updates gripper status
88+ *
89+ * @param none
90+ * @return none
91+ * @note see status on success, exception thrown if communicatoin issues
92+ */
93+ void update_status ()
94+
95+ /* *
96+ * @brief Returns the gripper status
97+ *
98+ * @param none
99+ * @return Gripper status
100+ * @note see status on success, exception thrown if communicatoin issues
101+ */
102+ Status status();
103+
104+ /* *
105+ * @brief Returns the gripper fault status
106+ *
107+ * @param none
108+ * @return Fault Status
109+ * @note see status on success, exception thrown if communicatoin issues
110+ */
111+ FaultStatus fault_status ();
112+
113+ /* *
114+ * @brief Returns the gripper requsted position
115+ *
116+ * @param none
117+ * @return Gripper requested position
118+ * @note see status on success, exception thrown if communicatoin issues
119+ */
120+ uint8_t requested_position ();
121+
122+ /* *
123+ * @brief Returns the gripper position
124+ *
125+ * @param none
126+ * @return Gripper position in
127+ * @note see status on success, exception thrown if communicatoin issues
128+ */
129+ uint8_t position ();
130+
131+ /* *
132+ * @brief Moves the gripper to requested position
133+ *
134+ * @param position to which the gripper has to move
135+ * @return none
136+ * @note see status on success, exception thrown if communicatoin issues
137+ */
138+ void ApplicationLayer::set_position (uint8_t position)
139+
140+ /* *
141+ * @brief Returns the gripper current
142+ *
143+ * @param none
144+ * @return Gripper current in mA (range: 0-2550mA)
145+ * @note see status on success, exception thrown if communicatoin issues
146+ */
147+ uint16_t current();
148+
149+ private:
150+ /* *
151+ * Protocol logic, used for middle level abstraction
152+ */
153+ ProtocolLogic protocol_logic_;
154+
155+ /* *
156+ * Struct with status bits
157+ */
158+ Status status_;
159+
160+ /* *
161+ * Struct with fault status bits
162+ */
163+ FaultStatus fault_status_;
164+
165+ /* *
166+ * Requested position of the gripper, in [m]
167+ */
168+ uint8_t requested_position_;
169+
170+ /* *
171+ * POsition of the gripper, in [m]
172+ */
173+ uint8_t position_;
174+
175+ /* *
176+ * Current flowin through the gripper, in [mA]
177+ */
178+ uint16_t current_;
179+
180+ };
181+ } // namespace hande_driver
0 commit comments