Browse Source

passage au tout objet en cours

Sébastien DI MERCURIO 5 years ago
parent
commit
34d1cb6bd8
24 changed files with 2212 additions and 370 deletions
  1. 0
    189
      software/raspberry/superviseur-robot/lib/comgui.cpp
  2. 336
    0
      software/raspberry/superviseur-robot/lib/commonitor.cpp
  3. 40
    12
      software/raspberry/superviseur-robot/lib/commonitor.h
  4. 334
    0
      software/raspberry/superviseur-robot/lib/comrobot.cpp
  5. 143
    0
      software/raspberry/superviseur-robot/lib/comrobot.h
  6. 16
    1
      software/raspberry/superviseur-robot/lib/img.cpp
  7. 14
    5
      software/raspberry/superviseur-robot/lib/img.h
  8. 427
    42
      software/raspberry/superviseur-robot/lib/messages.cpp
  9. 29
    113
      software/raspberry/superviseur-robot/lib/messages.h
  10. 19
    1
      software/raspberry/superviseur-robot/nbproject/Makefile-Debug.mk
  11. 131
    0
      software/raspberry/superviseur-robot/nbproject/Makefile-Debug__Pthread_.mk
  12. 19
    1
      software/raspberry/superviseur-robot/nbproject/Makefile-Debug__RPI_.mk
  13. 19
    1
      software/raspberry/superviseur-robot/nbproject/Makefile-Release.mk
  14. 1
    1
      software/raspberry/superviseur-robot/nbproject/Makefile-impl.mk
  15. 8
    0
      software/raspberry/superviseur-robot/nbproject/Makefile-variables.mk
  16. 76
    0
      software/raspberry/superviseur-robot/nbproject/Package-Debug__Pthread_.bash
  17. 179
    0
      software/raspberry/superviseur-robot/nbproject/configurations.xml
  18. 1
    0
      software/raspberry/superviseur-robot/nbproject/private/Makefile-variables.mk
  19. 37
    0
      software/raspberry/superviseur-robot/nbproject/private/configurations.xml
  20. 7
    1
      software/raspberry/superviseur-robot/nbproject/private/private.xml
  21. 7
    1
      software/raspberry/superviseur-robot/nbproject/project.xml
  22. 2
    2
      software/raspberry/superviseur-robot/tasks.h
  23. 263
    0
      software/raspberry/superviseur-robot/tasks_pthread.cpp
  24. 104
    0
      software/raspberry/superviseur-robot/tasks_pthread.h

+ 0
- 189
software/raspberry/superviseur-robot/lib/comgui.cpp View File

@@ -1,189 +0,0 @@
1
-/*
2
- * Copyright (C) 2018 dimercur
3
- *
4
- * This program is free software: you can redistribute it and/or modify
5
- * it under the terms of the GNU General Public License as published by
6
- * the Free Software Foundation, either version 3 of the License, or
7
- * (at your option) any later version.
8
- *
9
- * This program is distributed in the hope that it will be useful,
10
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
11
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
12
- * GNU General Public License for more details.
13
- *
14
- * You should have received a copy of the GNU General Public License
15
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
16
- */
17
-
18
-#include "comgui.h"
19
-#include <iostream>
20
-#include <sys/socket.h>
21
-
22
-#include <netdb.h>
23
-#include <unistd.h>
24
-#include <arpa/inet.h>
25
-#include <netinet/in.h>
26
-
27
-#include <algorithm>
28
-#include <stdexcept>
29
-#include <string>
30
-
31
-/*
32
- * Constants used for sending commands to gui
33
- */
34
-const string LABEL_GUI_ANGULAR_POSITION = "AngularPosition";
35
-const string LABEL_GUI_ANGULAR_SPEED = "AngularSpeed";
36
-const string LABEL_GUI_BATTERY_LEVEL = "Battery";
37
-const string LABEL_GUI_LINEAR_SPEED = "LinearSpeed";
38
-const string LABEL_GUI_USER_PRESENCE = "User";
39
-const string LABEL_GUI_BETA_ANGLE = "Beta";
40
-const string LABEL_GUI_TORQUE = "Torque";
41
-const string LABEL_GUI_EMERGENCY_STOP = "Emergency";
42
-const string LABEL_GUI_LOG = "Log";
43
-
44
-/**
45
- * Create a server and open a socket over TCP
46
- * 
47
- * @param port Port used for communication
48
- * @return Socket number
49
- * @throw std::runtime_error if it fails
50
- */
51
-int ComGui::Open(int port) {
52
-    struct sockaddr_in server;
53
-
54
-    socketFD = socket(AF_INET, SOCK_STREAM, 0);
55
-    if (socketFD < 0) {
56
-        throw std::runtime_error{"ComGui::Open : Can not create socket"};
57
-    }
58
-
59
-    server.sin_addr.s_addr = INADDR_ANY;
60
-    server.sin_family = AF_INET;
61
-    server.sin_port = htons(port);
62
-
63
-    if (bind(socketFD, (struct sockaddr *) &server, sizeof (server)) < 0) {
64
-        throw std::runtime_error{"ComGui::Open : Can not bind socket on port " + std::to_string(port)};
65
-    }
66
-
67
-    listen(socketFD, 1);
68
-
69
-    return socketFD;
70
-}
71
-
72
-/**
73
- * Close socket and server
74
- */
75
-void ComGui::Close() {
76
-    close(socketFD);
77
-
78
-    socketFD = -1;
79
-}
80
-
81
-/**
82
- * Wait for a client to connect
83
- * @return Client number 
84
- * @throw std::runtime_error if it fails
85
- */
86
-int ComGui::AcceptClient() {
87
-    struct sockaddr_in client;
88
-    int c = sizeof (struct sockaddr_in);
89
-
90
-    clientID = accept(socketFD, (struct sockaddr *) &client, (socklen_t*) & c);
91
-
92
-    if (clientID < 0)
93
-        throw std::runtime_error {
94
-        "ComGui::AcceptClient : Accept failed"
95
-    };
96
-
97
-    return clientID;
98
-}
99
-
100
-/**
101
- * Send a message to GUI
102
- * 
103
- * @param msg Message to send to GUI
104
- * @attention Message given in parameter will be destroyed (delete) after being sent. No need for user to delete message after that.
105
- * @warning Write is not thread safe : check that multiple tasks can't access this method simultaneously  
106
- */
107
-void ComGui::Write(Message* msg) {
108
-    string *str;
109
-
110
-    // Call user method before Write
111
-    Write_Pre();
112
-
113
-    /* Convert message to string to send to GUI */
114
-    str = MessageToString(msg);
115
-
116
-    //cout << "Message sent to GUI: " << str->c_str() << endl;
117
-    write(clientID, str->c_str(), str->length());
118
-
119
-    delete(str);
120
-
121
-    // Call user method after write
122
-    Write_Post();
123
-}
124
-
125
-/**
126
- * Method used internally to convert a message content to a string that can be sent over TCP
127
- * @param msg Message to be converted
128
- * @return A string, image of the message
129
- */
130
-string *ComGui::MessageToString(Message *msg) {
131
-    int id;
132
-    string *str;
133
-
134
-    if (msg != NULL) {
135
-        id = msg->GetID();
136
-
137
-        switch (id) {
138
-            case MESSAGE_ANGLE_POSITION:
139
-                str = new string(LABEL_GUI_ANGULAR_POSITION + "=" + to_string(((MessageFloat*) msg)->GetValue()) + "\n");
140
-                replace(str->begin(), str->end(), '.', ','); // Mono C# require float to have a , instead of a .
141
-                break;
142
-            case MESSAGE_ANGULAR_SPEED:
143
-                str = new string(LABEL_GUI_ANGULAR_SPEED + "=" + to_string(((MessageFloat*) msg)->GetValue()) + "\n");
144
-                replace(str->begin(), str->end(), '.', ','); // Mono C# require float to have a , instead of a .
145
-                break;
146
-            case MESSAGE_BATTERY:
147
-                str = new string(LABEL_GUI_BATTERY_LEVEL + "=" + to_string(((MessageFloat*) msg)->GetValue()) + "\n");
148
-                replace(str->begin(), str->end(), '.', ','); // Mono C# require float to have a , instead of a .
149
-                break;
150
-            case MESSAGE_BETA:
151
-                str = new string(LABEL_GUI_BETA_ANGLE + "=" + to_string(((MessageFloat*) msg)->GetValue()) + "\n");
152
-                replace(str->begin(), str->end(), '.', ','); // Mono C# require float to have a , instead of a .
153
-                break;
154
-            case MESSAGE_LINEAR_SPEED:
155
-                str = new string(LABEL_GUI_LINEAR_SPEED + "=" + to_string(((MessageFloat*) msg)->GetValue()) + "\n");
156
-                replace(str->begin(), str->end(), '.', ','); // Mono C# require float to have a , instead of a .
157
-                break;
158
-            case MESSAGE_TORQUE:
159
-                str = new string(LABEL_GUI_TORQUE + "=" + to_string(((MessageFloat*) msg)->GetValue()) + "\n");
160
-                replace(str->begin(), str->end(), '.', ','); // Mono C# require float to have a , instead of a .
161
-                break;
162
-            case MESSAGE_EMERGENCY_STOP:
163
-                str = new string(LABEL_GUI_EMERGENCY_STOP + "=");
164
-                if (((MessageBool*) msg)->GetState())
165
-                    str->append("True\n");
166
-                else
167
-                    str->append("False\n");
168
-                break;
169
-            case MESSAGE_USER_PRESENCE:
170
-                str = new string(LABEL_GUI_USER_PRESENCE + "=");
171
-                if (((MessageBool*) msg)->GetState())
172
-                    str->append("True\n");
173
-                else
174
-                    str->append("False\n");
175
-                break;
176
-            case MESSAGE_EMPTY:
177
-                str = new string(""); //empty string
178
-                break;
179
-            case MESSAGE_LOG:
180
-                str = new string(LABEL_GUI_LOG + "=" + ((MessageString*) msg)->GetString() + "\n");
181
-                break;
182
-            default:
183
-                str = new string(""); //empty string
184
-                break;
185
-        }
186
-    }
187
-
188
-    return str;
189
-}

+ 336
- 0
software/raspberry/superviseur-robot/lib/commonitor.cpp View File

@@ -0,0 +1,336 @@
1
+/*
2
+ * Copyright (C) 2018 dimercur
3
+ *
4
+ * This program is free software: you can redistribute it and/or modify
5
+ * it under the terms of the GNU General Public License as published by
6
+ * the Free Software Foundation, either version 3 of the License, or
7
+ * (at your option) any later version.
8
+ *
9
+ * This program is distributed in the hope that it will be useful,
10
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
11
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
12
+ * GNU General Public License for more details.
13
+ *
14
+ * You should have received a copy of the GNU General Public License
15
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
16
+ */
17
+
18
+#include "commonitor.h"
19
+#include <iostream>
20
+#include <sys/socket.h>
21
+
22
+#include <netdb.h>
23
+#include <unistd.h>
24
+#include <arpa/inet.h>
25
+#include <netinet/in.h>
26
+
27
+#include <algorithm>
28
+#include <stdexcept>
29
+#include <string>
30
+
31
+/*
32
+ * @brief Constants used for sending commands to monitor
33
+ */
34
+const string LABEL_MONITOR_ANSWER_ACK = "AACK";
35
+const string LABEL_MONITOR_ANSWER_NACK = "ANAK";
36
+const string LABEL_MONITOR_ANSWER_LOST_DMB= "ATIM";
37
+const string LABEL_MONITOR_ANSWER_TIMEOUT= "ATIM";
38
+const string LABEL_MONITOR_ANSWER_CMD_REJECTED= "ACRJ";
39
+const string LABEL_MONITOR_MESSAGE = "MSSG";
40
+const string LABEL_MONITOR_CAMERA_OPEN= "COPN";
41
+const string LABEL_MONITOR_CAMERA_CLOSE= "CCLS";
42
+const string LABEL_MONITOR_CAMERA_IMAGE = "CIMG";
43
+const string LABEL_MONITOR_CAMERA_ARENA_ASK = "CASA";
44
+const string LABEL_MONITOR_CAMERA_ARENA_INFIRME = "CAIN";
45
+const string LABEL_MONITOR_CAMERA_ARENA_CONFIRM = "CACO";
46
+const string LABEL_MONITOR_CAMERA_POSITION_COMPUTE= "CPCO";
47
+const string LABEL_MONITOR_CAMERA_POSITION_STOP= "CPST";
48
+const string LABEL_MONITOR_CAMERA_POSITION = "CPOS";
49
+const string LABEL_MONITOR_ROBOT_COM_OPEN = "ROPN";
50
+const string LABEL_MONITOR_ROBOT_COM_CLOSE = "RCLS";
51
+const string LABEL_MONITOR_ROBOT_PING = "RPIN";
52
+const string LABEL_MONITOR_ROBOT_RESET = "RRST";
53
+const string LABEL_MONITOR_ROBOT_START_WITHOUT_WD= "RSOW";
54
+const string LABEL_MONITOR_ROBOT_START_WITH_WD= "RSWW";
55
+const string LABEL_MONITOR_ROBOT_RELOAD_WD = "RLDW";
56
+const string LABEL_MONITOR_ROBOT_MOVE = "RMOV";
57
+const string LABEL_MONITOR_ROBOT_TURN = "RTRN";
58
+const string LABEL_MONITOR_ROBOT_GO_FORWARD = "RGFW";
59
+const string LABEL_MONITOR_ROBOT_GO_BACKWARD = "RGBW";
60
+const string LABEL_MONITOR_ROBOT_GO_LEFT = "RGLF";
61
+const string LABEL_MONITOR_ROBOT_GO_RIGHT = "RGRI";
62
+const string LABEL_MONITOR_ROBOT_STOP = "RSTP";
63
+const string LABEL_MONITOR_ROBOT_POWEROFF = "RPOF";
64
+const string LABEL_MONITOR_ROBOT_BATTERY_LEVEL = "RBLV";
65
+const string LABEL_MONITOR_ROBOT_GET_BATTERY = "RGBT";
66
+const string LABEL_MONITOR_ROBOT_GET_STATE = "RGST";
67
+const string LABEL_MONITOR_ROBOT_CURRENT_STATE = "RCST";
68
+
69
+const string LABEL_SEPARATOR_CHAR = ":";
70
+
71
+/**
72
+ * Create a server and open a socket over TCP
73
+ * 
74
+ * @param port Port used for communication
75
+ * @return Socket number
76
+ * @throw std::runtime_error if it fails
77
+ */
78
+int ComMonitor::Open(int port) {
79
+    struct sockaddr_in server;
80
+
81
+    socketFD = socket(AF_INET, SOCK_STREAM, 0);
82
+    if (socketFD < 0) {
83
+        throw std::runtime_error{"ComMonitor::Open : Can not create socket"};
84
+    }
85
+
86
+    server.sin_addr.s_addr = INADDR_ANY;
87
+    server.sin_family = AF_INET;
88
+    server.sin_port = htons(port);
89
+
90
+    if (bind(socketFD, (struct sockaddr *) &server, sizeof (server)) < 0) {
91
+        throw std::runtime_error{"ComMonitor::Open : Can not bind socket on port " + std::to_string(port)};
92
+    }
93
+
94
+    listen(socketFD, 1);
95
+
96
+    return socketFD;
97
+}
98
+
99
+/**
100
+ * Close socket and server
101
+ */
102
+void ComMonitor::Close() {
103
+    close(socketFD);
104
+
105
+    socketFD = -1;
106
+}
107
+
108
+/**
109
+ * Wait for a client to connect
110
+ * @return Client number 
111
+ * @throw std::runtime_error if it fails
112
+ */
113
+int ComMonitor::AcceptClient() {
114
+    struct sockaddr_in client;
115
+    int c = sizeof (struct sockaddr_in);
116
+
117
+    clientID = accept(socketFD, (struct sockaddr *) &client, (socklen_t*) & c);
118
+
119
+    if (clientID < 0)
120
+        throw std::runtime_error {
121
+        "ComMonitor::AcceptClient : Accept failed"
122
+    };
123
+
124
+    return clientID;
125
+}
126
+
127
+/**
128
+ * Send a message to monitor
129
+ * 
130
+ * @param msg Message to send to monitor
131
+ * @attention Message given in parameter will be destroyed (delete) after being sent. No need for user to delete message after that.
132
+ * @warning Write is not thread safe : check that multiple tasks can't access this method simultaneously  
133
+ */
134
+void ComMonitor::Write(Message &msg) {
135
+    string str;
136
+
137
+    // Call user method before Write
138
+    Write_Pre();
139
+
140
+    /* Convert message to string to send to monitor */
141
+    str = MessageToString(msg);
142
+
143
+    //cout << "Message sent to monitor: " << str->c_str() << endl;
144
+    write(clientID, str.c_str(), str.length());
145
+
146
+    delete(&msg);
147
+    
148
+    // Call user method after write
149
+    Write_Post();
150
+}
151
+
152
+/**
153
+ * Receive a message from monitor
154
+ * 
155
+ * @return Message received from monitor
156
+ * @attention Message provided is produced by the method. You must delete it when you are done using it
157
+ * @warning Read is not thread safe : check that multiple tasks can't access this method simultaneously  
158
+ */
159
+Message *ComMonitor::Read() {
160
+    char length = 0;
161
+    string s;
162
+    char data;
163
+    bool endReception=false;
164
+    Message *msg;
165
+    
166
+    // Call user method before read
167
+    Read_Pre();
168
+
169
+    if (clientID > 0) {
170
+        while (!endReception) {
171
+            if ((length = recv(clientID, (void*) &data, 1, MSG_WAITALL)) > 0) {
172
+                if (data != '\n') {
173
+                    s+=data;
174
+                } else endReception = true;
175
+            }
176
+        }
177
+
178
+        if (length<=0) msg = new Message(MESSAGE_MONITOR_LOST);
179
+        else {
180
+            msg=StringToMessage(s);
181
+        }
182
+    }
183
+
184
+    // Call user method after read
185
+    Read_Post();
186
+    
187
+    return msg;
188
+}
189
+
190
+/**
191
+ * Method used internally to convert a message content to a string that can be sent over TCP
192
+ * @param msg Message to be converted
193
+ * @return A string, image of the message
194
+ */
195
+string ComMonitor::MessageToString(Message &msg) {
196
+    int id;
197
+    string str;
198
+    Message *localMsg = &msg;
199
+    Position pos;
200
+    
201
+    id = msg.GetID();
202
+
203
+    switch (id) {
204
+        case MESSAGE_ANSWER:
205
+            switch (((MessageAnswer*)localMsg)->GetAnswer()) {
206
+                case ANSWER_ACK:
207
+                    str.append(LABEL_MONITOR_ANSWER_ACK);
208
+                    break;
209
+                case ANSWER_NACK:
210
+                    str.append(LABEL_MONITOR_ANSWER_NACK);
211
+                    break;
212
+                case ANSWER_LOST_ROBOT:
213
+                    str.append(LABEL_MONITOR_ANSWER_LOST_DMB);
214
+                    break;
215
+                case ANSWER_ROBOT_TIMEOUT:
216
+                    str.append(LABEL_MONITOR_ANSWER_TIMEOUT);
217
+                    break;
218
+                case ANSWER_ROBOT_UNKNOWN_COMMAND:
219
+                    str.append(LABEL_MONITOR_ANSWER_CMD_REJECTED);
220
+                    break;
221
+                case ANSWER_ROBOT_ERROR:
222
+                    str.append(LABEL_MONITOR_ANSWER_CMD_REJECTED);
223
+                    break;
224
+                default:
225
+                    str.append(LABEL_MONITOR_ANSWER_NACK);
226
+            };
227
+            
228
+            break;
229
+        case MESSAGE_POSITION:
230
+            pos = ((MessagePosition*)&msg)->GetPosition();
231
+            
232
+            str.append(LABEL_MONITOR_CAMERA_POSITION + LABEL_SEPARATOR_CHAR + to_string(pos.robotId) + ";" +
233
+                    to_string(pos.angle) + ";" + to_string(pos.center.x) + ";" + to_string(pos.center.y) + ";" +
234
+                    to_string(pos.direction.x) + ";" + to_string(pos.direction.y));
235
+            break;
236
+        case MESSAGE_IMAGE:
237
+            str.append(LABEL_MONITOR_CAMERA_IMAGE + LABEL_SEPARATOR_CHAR + ((MessageImg*) &msg)->GetImage()->ToBase64());
238
+            break;
239
+        case MESSAGE_ROBOT_BATTERY_LEVEL:
240
+            str.append(LABEL_MONITOR_ROBOT_BATTERY_LEVEL + LABEL_SEPARATOR_CHAR + to_string(((MessageBattery*) &msg)->GetLevel()));
241
+            break;
242
+        case MESSAGE_ROBOT_CURRENT_STATE:
243
+            str.append(LABEL_MONITOR_ROBOT_CURRENT_STATE + LABEL_SEPARATOR_CHAR + to_string(((MessageState*) &msg)->GetState()));
244
+            break;
245
+        case MESSAGE_LOG:
246
+            str.append(LABEL_MONITOR_MESSAGE + LABEL_SEPARATOR_CHAR + ((MessageString*) &msg)->GetString());
247
+            break;
248
+        case MESSAGE_EMPTY:
249
+            str.append(""); //empty string
250
+            break;
251
+        default:
252
+            throw std::runtime_error
253
+        {
254
+            "ComMonitor::MessageToString (from ComMonitor::Write): Invalid message to send (" + msg.ToString()
255
+        };
256
+    }
257
+
258
+    str.append("\n");
259
+
260
+    return str;
261
+}
262
+
263
+/**
264
+ * Method used internally to convert a string received over TCP to a message 
265
+ * @param s String containing message
266
+ * @return A message, image of the string
267
+ */
268
+Message *ComMonitor::StringToMessage(string &s) {
269
+    Message *msg;
270
+    size_t pos;
271
+    string org =s;
272
+    string tokenCmd;
273
+    string tokenData;
274
+    
275
+    /* Separate command from data if string contains a ':' */
276
+    if ((pos=org.find(LABEL_SEPARATOR_CHAR)) != string::npos) {
277
+        tokenCmd = org.substr(0,pos);
278
+        org.erase(0,pos+1);
279
+        tokenData=org;
280
+    } else tokenCmd=org;
281
+    
282
+    /* Convert command to message */
283
+    if (tokenCmd.find(LABEL_MONITOR_ROBOT_MOVE)!= string::npos) {
284
+        msg = new MessageInt(MESSAGE_ROBOT_MOVE,stoi(tokenData));
285
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_TURN)!= string::npos) {
286
+        msg = new MessageInt(MESSAGE_ROBOT_TURN,stoi(tokenData));
287
+    } else  if (tokenCmd.find(LABEL_MONITOR_ROBOT_START_WITHOUT_WD)!= string::npos) {
288
+        msg = new Message(MESSAGE_ROBOT_START_WITHOUT_WD);
289
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_START_WITH_WD)!= string::npos) {
290
+        msg = new Message(MESSAGE_ROBOT_START_WITH_WD);
291
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_RELOAD_WD)!= string::npos) {
292
+        msg = new Message(MESSAGE_ROBOT_RELOAD_WD);
293
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_PING)!= string::npos) {
294
+        msg = new Message(MESSAGE_ROBOT_PING);
295
+    } else  if (tokenCmd.find(LABEL_MONITOR_ROBOT_RESET)!= string::npos) {
296
+        msg = new Message(MESSAGE_ROBOT_RESET);
297
+    } else if (tokenCmd.find(LABEL_MONITOR_CAMERA_ARENA_ASK)!= string::npos) {
298
+        msg = new Message(MESSAGE_ASK_ARENA);
299
+    } else if (tokenCmd.find(LABEL_MONITOR_CAMERA_ARENA_CONFIRM)!= string::npos) {
300
+        msg = new Message(MESSAGE_ARENA_CONFIRM);
301
+    } else if (tokenCmd.find(LABEL_MONITOR_CAMERA_ARENA_INFIRME)!= string::npos) {
302
+        msg = new Message(MESSAGE_ARENA_INFIRM);
303
+    } else if (tokenCmd.find(LABEL_MONITOR_CAMERA_CLOSE)!= string::npos) {
304
+        msg = new Message(MESSAGE_CAM_CLOSE);
305
+    } else if (tokenCmd.find(LABEL_MONITOR_CAMERA_OPEN)!= string::npos) {
306
+        msg = new Message(MESSAGE_CAM_OPEN);
307
+    } else if (tokenCmd.find(LABEL_MONITOR_CAMERA_POSITION_COMPUTE)!= string::npos) {
308
+        msg = new Message(MESSAGE_COMPUTE_POSITION);
309
+    } else if (tokenCmd.find(LABEL_MONITOR_CAMERA_POSITION_STOP)!= string::npos) {
310
+        msg = new Message(MESSAGE_STOP_COMPUTE_POSITION);
311
+    } else if (tokenCmd.find(LABEL_MONITOR_MESSAGE)!= string::npos) {
312
+        msg = new MessageString(MESSAGE_LOG,tokenData);
313
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_COM_CLOSE)!= string::npos) {
314
+        msg = new Message(MESSAGE_CLOSE_COM);
315
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_COM_OPEN)!= string::npos) {
316
+        msg = new Message(MESSAGE_OPEN_COM);
317
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_GET_BATTERY)!= string::npos) {
318
+        msg = new Message(MESSAGE_ROBOT_GET_BATTERY);
319
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_GET_STATE)!= string::npos) {
320
+        msg = new Message(MESSAGE_ROBOT_GET_STATE);
321
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_GO_FORWARD)!= string::npos) {
322
+        msg = new Message(MESSAGE_ROBOT_GO_FORWARD);
323
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_GO_BACKWARD)!= string::npos) {
324
+        msg = new Message(MESSAGE_ROBOT_GO_BACK);
325
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_GO_LEFT)!= string::npos) {
326
+        msg = new Message(MESSAGE_ROBOT_GO_LEFT);
327
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_GO_RIGHT)!= string::npos) {
328
+        msg = new Message(MESSAGE_ROBOT_GO_RIGHT);
329
+    } else if (tokenCmd.find(LABEL_MONITOR_ROBOT_POWEROFF)!= string::npos) {
330
+        msg = new Message(MESSAGE_ROBOT_POWEROFF);
331
+    } else {
332
+        msg = new Message(MESSAGE_EMPTY);
333
+    }
334
+    
335
+    return msg;
336
+}

software/raspberry/superviseur-robot/lib/comgui.h → software/raspberry/superviseur-robot/lib/commonitor.h View File

@@ -15,8 +15,8 @@
15 15
  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
16 16
  */
17 17
 
18
-#ifndef __COMGUI_H__
19
-#define __COMGUI_H__
18
+#ifndef __COMMONITOR_H__
19
+#define __COMMONITOR_H__
20 20
 
21 21
 #include "messages.h"
22 22
 #include <string>
@@ -24,22 +24,22 @@
24 24
 using namespace std;
25 25
      
26 26
 /**
27
- * Class used for generating a server and communicating through it with GUI
27
+ * Class used for generating a server and communicating through it with monitor
28 28
  * 
29
- * @brief Communication class with GUI (server)
29
+ * @brief Communication class with monitor (server)
30 30
  * 
31 31
  */
32
-class ComGui {
32
+class ComMonitor {
33 33
 public:
34 34
     /**
35 35
      * Constructor
36 36
      */
37
-    ComGui() {}
37
+    ComMonitor() {}
38 38
     
39 39
     /**
40 40
      * Destructor
41 41
      */
42
-    virtual ~ComGui() {}
42
+    virtual ~ComMonitor() {}
43 43
     
44 44
     /**
45 45
      * Create a server and open a socket over TCP
@@ -63,13 +63,13 @@ public:
63 63
     int AcceptClient();
64 64
     
65 65
     /**
66
-     * Send a message to GUI
66
+     * Send a message to monitor
67 67
      * 
68
-     * @param msg Message to send to GUI
68
+     * @param msg Message to send to monitor
69 69
      * @attention Message given in parameter will be destroyed (delete) after being sent. No need for user to delete message after that.
70 70
      * @warning Write is not thread safe : check that multiple tasks can't access this method simultaneously  
71 71
      */
72
-    void Write(Message* msg);
72
+    void Write(Message &msg);
73 73
     
74 74
     /**
75 75
      * Function called at beginning of Write method
@@ -82,6 +82,27 @@ public:
82 82
      * Use it to do some synchronization (release of mutex, for example)
83 83
      */
84 84
     virtual void Write_Post() {}
85
+    
86
+    /**
87
+     * Receive a message from monitor
88
+     * 
89
+     * @return Message received from monitor
90
+     * @attention Message provided is produced by the method. You must delete it when you are done using it
91
+     * @warning Read is not thread safe : check that multiple tasks can't access this method simultaneously  
92
+     */
93
+    Message *Read();
94
+    
95
+    /**
96
+     * Function called at beginning of Read method
97
+     * Use it to do some synchronization (call of mutex, for example)
98
+     */
99
+    virtual void Read_Pre() {}
100
+    
101
+    /**
102
+     * Function called at end of Read method
103
+     * Use it to do some synchronization (release of mutex, for example)
104
+     */
105
+    virtual void Read_Post() {}
85 106
 protected:
86 107
     /**
87 108
      * Socket descriptor
@@ -98,7 +119,14 @@ protected:
98 119
      * @param msg Message to be converted
99 120
      * @return A string, image of the message
100 121
      */
101
-    string *MessageToString(Message *msg);
122
+    string MessageToString(Message &msg);
123
+    
124
+    /**
125
+     * Method used internally to convert a string received over TCP to a message 
126
+     * @param s String containing message
127
+     * @return A message, image of the string
128
+     */
129
+    Message *StringToMessage(string &s);
102 130
 };
103 131
 
104
-#endif /* __COMGUI_H__ */
132
+#endif /* __COMMONITOR_H__ */

+ 334
- 0
software/raspberry/superviseur-robot/lib/comrobot.cpp View File

@@ -0,0 +1,334 @@
1
+/*
2
+ * Copyright (C) 2018 dimercur
3
+ *
4
+ * This program is free software: you can redistribute it and/or modify
5
+ * it under the terms of the GNU General Public License as published by
6
+ * the Free Software Foundation, either version 3 of the License, or
7
+ * (at your option) any later version.
8
+ *
9
+ * This program is distributed in the hope that it will be useful,
10
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
11
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
12
+ * GNU General Public License for more details.
13
+ *
14
+ * You should have received a copy of the GNU General Public License
15
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
16
+ */
17
+
18
+#include "comrobot.h"
19
+
20
+#include <stdio.h>
21
+#include <stdlib.h> 
22
+#include <unistd.h>
23
+#include <fcntl.h>
24
+#include <termios.h>  
25
+
26
+#include <string>
27
+#include <stdexcept>
28
+
29
+#ifdef __FOR_PC__
30
+#define USART_FILENAME "/dev/ttyUSB0"
31
+#else
32
+#define USART_FILENAME "/dev/ttyS0"
33
+#endif /* __FOR_PC__ */
34
+
35
+/*
36
+ * Constants to be used for communicating with robot. Contains command tag
37
+ */
38
+typedef enum {
39
+    LABEL_ANGLE_POSITION = 'p',
40
+    LABEL_ANGULAR_SPEED = 's',
41
+    LABEL_BATTERY_LEVEL = 'b',
42
+    LABEL_BETA_ANGLE = 'v',
43
+    LABEL_USER_PRESENCE = 'u',
44
+
45
+    LABEL_TORQUE = 'c',
46
+    LABEL_EMERGENCY_STOP = 'a'
47
+} LabelRobot;
48
+
49
+/**
50
+ * Open serial link with robot
51
+ * @return File descriptor
52
+ * @throw std::runtime_error if it fails
53
+ */
54
+int ComRobot::Open() {
55
+    fd = open(USART_FILENAME, O_RDWR | O_NOCTTY /*| O_NDELAY*/); //Open in blocking read/write mode
56
+    if (fd == -1) {
57
+        //ERROR - CAN'T OPEN SERIAL PORT
58
+        throw std::runtime_error{"Error - Unable to open UART " + string(USART_FILENAME) + ".  Ensure it is not in use by another application"};
59
+        exit(EXIT_FAILURE);
60
+    }
61
+
62
+    //Configuration of the serial port 115 520 Bauds
63
+    struct termios options;
64
+    tcgetattr(fd, &options);
65
+    options.c_cflag = B115200 | CS8 | CLOCAL | CREAD; //<Set baud rate
66
+    options.c_iflag = IGNPAR; // ignores bytes with bad parity
67
+    options.c_oflag = 0;
68
+    options.c_lflag = 0;
69
+    tcflush(fd, TCIFLUSH);
70
+    tcsetattr(fd, TCSANOW, &options);
71
+
72
+    return fd;
73
+}
74
+
75
+/**
76
+ * Close serial link
77
+ * @return Success if above 0, failure if below 0
78
+ */
79
+int ComRobot::Close() {
80
+    return close(fd);
81
+}
82
+
83
+/**
84
+ * Get a message from robot
85
+ * @return Message currently received
86
+ * @attention A message object is created (new) when receiving data from robot. You MUST remember to destroy is (delete) after use
87
+ * @attention Read method is blocking until a message is received
88
+ * @warning Read is not thread safe : Do not call it in multiple tasks simultaneously
89
+ */
90
+Message* ComRobot::Read() {
91
+    int rxLength;
92
+    unsigned char rxBuffer[6];
93
+    unsigned char receivedChar;
94
+    bool messageComplete = false;
95
+    Message *msg;
96
+    unsigned int i;
97
+
98
+    /* Call pre method for read */
99
+    Read_Pre();
100
+
101
+    /* a message is composed of 7 bytes.
102
+                the byte 0 should always be '<'
103
+                the byte 1 should be an ascii char that is the label. It define what the data represent
104
+                the bytes 2 to 5 are the float value
105
+                the byte 6 should always be a '\n'
106
+     */
107
+    while (messageComplete == false) {
108
+        rxLength = read(this->fd, (void*) &receivedChar, 1); //Filestream, buffer to store in, number of bytes to read (max)
109
+        //printf ("W=%02X ", receivedChar);
110
+
111
+        if (rxLength <= -1) {
112
+            this->lostCom = true;
113
+            printf("Warning: communication lost in ComStm32::Read\n");
114
+            msg = new Message();
115
+
116
+            return msg;
117
+        } else if (rxLength == 0) {
118
+            // nothing to do
119
+        } else if (receivedChar == '<') { // start of frame received
120
+            i = 0;
121
+
122
+            do {
123
+                rxLength = read(this->fd, (void*) &rxBuffer[i], 6 - i); //Filestream, buffer to store in, number of bytes to read (max)
124
+
125
+                if (rxLength >= 0)
126
+                    i = i + rxLength;
127
+                else {
128
+                    printf("Error while reading (%i)", rxLength);
129
+
130
+                    return NULL;
131
+                }
132
+            } while (i < 6);
133
+
134
+            if (rxBuffer[5] == '\n') {
135
+                messageComplete = true;
136
+            }
137
+        }
138
+    }
139
+
140
+    /* Treatment of received message */
141
+    msg = CharToMessage(rxBuffer);
142
+
143
+    /* Call Post method for read */
144
+    Read_Post();
145
+
146
+    return msg;
147
+}
148
+
149
+/**
150
+ * Convert an array of char to its message representation (when receiving data from stm32)
151
+ * @param bytes Array of char
152
+ * @return Message corresponding to received array of char
153
+ */
154
+Message* ComRobot::CharToMessage(unsigned char *bytes) {
155
+    Message *msg = __null;
156
+    MessageFloat *msgf;
157
+    MessageBool *msgb;
158
+
159
+    switch (bytes[0]) {
160
+        case LABEL_ANGLE_POSITION:
161
+            msgf = new MessageFloat();
162
+            msgf->SetID(MESSAGE_ANGLE_POSITION);
163
+            msgf->SetValue(CharToFloat(&bytes[1]));
164
+            msg = (Message*) msgf;
165
+
166
+            break;
167
+        case LABEL_ANGULAR_SPEED:
168
+            msgf = new MessageFloat();
169
+            msgf->SetID(MESSAGE_ANGULAR_SPEED);
170
+            msgf->SetValue(CharToFloat(&bytes[1]));
171
+            msg = (Message*) msgf;
172
+
173
+            break;
174
+        case LABEL_BATTERY_LEVEL:
175
+            msgf = new MessageFloat();
176
+            msgf->SetID(MESSAGE_BATTERY);
177
+            msgf->SetValue(CharToFloat(&bytes[1]));
178
+            msg = (Message*) msgf;
179
+
180
+            break;
181
+        case LABEL_BETA_ANGLE:
182
+            msgf = new MessageFloat();
183
+            msgf->SetID(MESSAGE_BETA);
184
+            msgf->SetValue(CharToFloat(&bytes[1]));
185
+            msg = (Message*) msgf;
186
+
187
+            break;
188
+        case LABEL_USER_PRESENCE:
189
+            msgb = new MessageBool();
190
+            msgb->SetID(MESSAGE_USER_PRESENCE);
191
+            msgb->SetState(CharToBool(&bytes[1]));
192
+            msg = (Message*) msgb;
193
+
194
+            break;
195
+        default:
196
+            printf("Unknown message received from robot (%i)\n", bytes[0]);
197
+            fflush(stdout);
198
+            msg = new Message();
199
+    }
200
+
201
+    if (msg == NULL) {
202
+        printf("Message is null (%02X)\n", bytes[0]);
203
+        fflush(stdout);
204
+        msg = new Message();
205
+    }
206
+
207
+    return msg;
208
+}
209
+
210
+/**
211
+ * Convert an array of char to float
212
+ * @param bytes Array of char, containing a binary image of a float
213
+ * @return Float value
214
+ */
215
+float ComRobot::CharToFloat(unsigned char *bytes) {
216
+    unsigned long value;
217
+
218
+    union {
219
+        unsigned char buffer[4];
220
+        float f;
221
+    } convert;
222
+
223
+    convert.buffer[0] = bytes[0];
224
+    convert.buffer[1] = bytes[1];
225
+    convert.buffer[2] = bytes[2];
226
+    convert.buffer[3] = bytes[3];
227
+
228
+    //value = (bytes[3] << 24) | (bytes[2] << 16) | (bytes[1] << 8) | (bytes[0]);
229
+
230
+    return convert.f;
231
+}
232
+
233
+/**
234
+ * Convert an array of char to integer
235
+ * @param bytes Array of char, containing a binary image of an integer
236
+ * @return Integer value
237
+ */
238
+unsigned int ComRobot::CharToInt(unsigned char *bytes) {
239
+    unsigned long value;
240
+
241
+    value = (bytes[3] << 24) | (bytes[2] << 16) | (bytes[1] << 8) | (bytes[0]);
242
+
243
+    return (unsigned int) value;
244
+}
245
+
246
+/**
247
+ * Convert an array of char to boolean
248
+ * @param bytes Array of char, containing a binary image of a boolean
249
+ * @return Boolean value
250
+ */
251
+bool ComRobot::CharToBool(unsigned char *bytes) {
252
+    unsigned long value;
253
+
254
+    value = (bytes[3] << 24) | (bytes[2] << 16) | (bytes[1] << 8) | (bytes[0]);
255
+
256
+    if (value == 0) return false;
257
+
258
+    else return true;
259
+}
260
+
261
+/**
262
+ * Send a message to robot
263
+ * @param msg Message to send to robot
264
+ * @return 1 if success, 0 otherwise
265
+ * @attention Message is destroyed (delete) after being sent. You do not need to delete it yourself
266
+ * @attention Write is blocking until message is written into buffer (linux side)
267
+ * @warning Write is not thread save : check that multiple tasks can't access this method simultaneously  
268
+ */
269
+int ComRobot::Write(Message* msg) {
270
+    unsigned char buffer[7];
271
+    int ret_val = 0;
272
+
273
+    MessageToChar(msg, buffer);
274
+
275
+    Write_Pre();
276
+
277
+    if (this->fd != -1) {
278
+        int count = write(this->fd, &buffer[0], 7); //Filestream, bytes to write, number of bytes to write
279
+        if (count < 0) {
280
+            printf("Warning: UART TX error in ComStm32::Write\n");
281
+        } else {
282
+            ret_val = 1;
283
+        }
284
+    }
285
+
286
+    // deallocation of msg
287
+    delete(msg);
288
+
289
+    Write_Post();
290
+
291
+    return ret_val;
292
+}
293
+
294
+/**
295
+ * Convert a message to its array of char representation (for sending command to stm32)
296
+ * @param msg Message to be sent to robot
297
+ * @param buffer Array of char, image of message to send
298
+ */
299
+void ComRobot::MessageToChar(Message *msg, unsigned char *buffer) {
300
+    float val_f;
301
+    int val_i;
302
+    unsigned char *b;
303
+
304
+    buffer[0] = '<';
305
+    buffer[6] = '\n';
306
+
307
+    switch (msg->GetID()) {
308
+        case MESSAGE_TORQUE:
309
+            buffer[1] = LABEL_TORQUE;
310
+            val_f = ((MessageFloat*) msg)->GetValue();
311
+            b = (unsigned char *) &val_f;
312
+
313
+            break;
314
+        case MESSAGE_EMERGENCY_STOP:
315
+            buffer[1] = LABEL_EMERGENCY_STOP;
316
+            if (((MessageBool*) msg)->GetState())
317
+                val_i = 1;
318
+            else
319
+                val_i = 0;
320
+            b = (unsigned char *) &val_i;
321
+
322
+            break;
323
+        default:
324
+            printf("Invalid message to send");
325
+            val_i = 0;
326
+            b = (unsigned char *) &val_i;
327
+    }
328
+
329
+    buffer[2] = b[0];
330
+    buffer[3] = b[1];
331
+    buffer[4] = b[2];
332
+    buffer[5] = b[3];
333
+}
334
+

+ 143
- 0
software/raspberry/superviseur-robot/lib/comrobot.h View File

@@ -0,0 +1,143 @@
1
+/*
2
+ * Copyright (C) 2018 dimercur
3
+ *
4
+ * This program is free software: you can redistribute it and/or modify
5
+ * it under the terms of the GNU General Public License as published by
6
+ * the Free Software Foundation, either version 3 of the License, or
7
+ * (at your option) any later version.
8
+ *
9
+ * This program is distributed in the hope that it will be useful,
10
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
11
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
12
+ * GNU General Public License for more details.
13
+ *
14
+ * You should have received a copy of the GNU General Public License
15
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
16
+ */
17
+
18
+#ifndef __COMROBOT_H__
19
+#define __COMROBOT_H__
20
+
21
+#include "messages.h"
22
+
23
+using namespace std;
24
+
25
+/**
26
+ * Class used for communicating with robot over serial
27
+ * 
28
+ * @brief Communication class with robot
29
+ * 
30
+ */
31
+class ComRobot {
32
+public:
33
+    /**
34
+     * Constructor
35
+     */
36
+    ComRobot() {}
37
+    
38
+    /**
39
+     * Destructor
40
+     */
41
+    virtual ~ComRobot() {}
42
+    
43
+    /**
44
+     * Open serial link with robot
45
+     * @return File descriptor
46
+     * @throw std::runtime_error if it fails
47
+     */
48
+    int Open();
49
+    
50
+    /**
51
+     * Close serial link
52
+     * @return Success if above 0, failure if below 0
53
+     */
54
+    int Close();
55
+    
56
+    /**
57
+     * Get a message from robot
58
+     * @return Message currently received
59
+     * @attention A message object is created (new) when receiving data from robot. You MUST remember to destroy is (delete) after use
60
+     * @attention Read method is blocking until a message is received
61
+     * @warning Read is not thread safe : Do not call it in multiple tasks simultaneously
62
+     */
63
+    Message* Read();
64
+    
65
+    /**
66
+     * Send a message to robot
67
+     * @param msg Message to send to robot
68
+     * @return 1 if success, 0 otherwise
69
+     * @attention Message is destroyed (delete) after being sent. You do not need to delete it yourself
70
+     * @attention Write is blocking until message is written into buffer (linux side)
71
+     * @warning Write is not thread save : check that multiple tasks can't access this method simultaneously  
72
+     */
73
+    int Write(Message* msg);
74
+    
75
+    /**
76
+     * Function called at beginning of Read method
77
+     * Use it to do some synchronization (call of mutex, for example)
78
+     */
79
+    virtual void Read_Pre() {}
80
+    
81
+    /**
82
+     * Function called at end of Read method
83
+     * Use it to do some synchronization (call of mutex, for example)
84
+     */
85
+    virtual void Read_Post() {}
86
+    
87
+    /**
88
+     * Function called at beginning of Write method
89
+     * Use it to do some synchronization (call of mutex, for example)
90
+     */
91
+    virtual void Write_Pre() {}
92
+    
93
+    /**
94
+     * Function called at end of Write method
95
+     * Use it to do some synchronization (call of mutex, for example)
96
+     */
97
+    virtual void Write_Post() {}
98
+    
99
+    static Message *Ping();
100
+    
101
+protected:
102
+    /**
103
+     * Serial link file descriptor
104
+     */
105
+    int fd;
106
+    
107
+    /**
108
+     * Convert an array of char to float
109
+     * @param bytes Array of char, containing a binary image of a float
110
+     * @return Float value
111
+     */
112
+    float CharToFloat(unsigned char *bytes);
113
+    
114
+    /**
115
+     * Convert an array of char to boolean
116
+     * @param bytes Array of char, containing a binary image of a boolean
117
+     * @return Boolean value
118
+     */
119
+    bool CharToBool(unsigned char *bytes);
120
+    
121
+    /**
122
+     * Convert an array of char to integer
123
+     * @param bytes Array of char, containing a binary image of an integer
124
+     * @return Integer value
125
+     */
126
+    unsigned int CharToInt(unsigned char *bytes);
127
+    
128
+    /**
129
+     * Convert an array of char to its message representation (when receiving data from stm32)
130
+     * @param bytes Array of char
131
+     * @return Message corresponding to received array of char
132
+     */
133
+    Message* CharToMessage(unsigned char *bytes);
134
+    
135
+    /**
136
+     * Convert a message to its array of char representation (for sending command to stm32)
137
+     * @param msg Message to be sent to robot
138
+     * @param buffer Array of char, image of message to send
139
+     */
140
+    void MessageToChar(Message *msg, unsigned char *buffer);
141
+};
142
+
143
+#endif /* __COMROBOT_H__ */

+ 16
- 1
software/raspberry/superviseur-robot/lib/img.cpp View File

@@ -18,7 +18,6 @@
18 18
 #include "img.h"
19 19
 
20 20
 bool Arene::empty() {
21
-
22 21
     if ((this->arene.height==0) || (this->arene.width==0)) return true;
23 22
     else return false;
24 23
 }
@@ -27,6 +26,14 @@ Img::Img(ImageMat imgMatrice) {
27 26
     this->img = imgMatrice.clone();
28 27
 }
29 28
 
29
+string Img::ToString() {
30
+    return "Image size: "+this->img.cols+"x"this->img.rows+" (dim="+this->img.dims+")";
31
+}
32
+    
33
+Img* Img::Copy() {
34
+    return new Img(this->img);
35
+}
36
+    
30 37
 float Img::calculAngle(Position robot) {
31 38
     float a = robot.direction.x - robot.center.x;
32 39
     float b = robot.direction.y - robot.center.y ;
@@ -93,6 +100,14 @@ Jpg Img::toJpg() {
93 100
     return imgJpg;
94 101
 }
95 102
 
103
+string Img::ToBase64() {
104
+    string imgBase64;
105
+    Jpg imgJpg = toJpg();
106
+    
107
+    /* faire la convertion Jpg vers base 64 */
108
+    return imgBase64;
109
+}
110
+
96 111
 std::list<Position> Img::search_robot(Arene monArene) {
97 112
 
98 113
     std::list<Position> robotsFind;

+ 14
- 5
software/raspberry/superviseur-robot/lib/img.h View File

@@ -20,6 +20,7 @@
20 20
 
21 21
 #include <iostream>
22 22
 #include <list>
23
+#include <string>
23 24
 
24 25
 #include <opencv2/highgui/highgui.hpp>
25 26
 #include <opencv2/imgproc/imgproc.hpp>
@@ -33,16 +34,18 @@
33 34
 
34 35
 #define ARENA_NOT_DETECTED -1
35 36
 
37
+using namespace std;
38
+
36 39
 typedef cv::Mat ImageMat;
37 40
 
38
-typedef std::vector<unsigned char> Jpg;
41
+typedef vector<unsigned char> Jpg;
39 42
 
40
-struct Position {
43
+typedef struct {
41 44
     cv::Point2f center;
42 45
     cv::Point2f direction;
43 46
     float angle;
44 47
     int robotId;
45
-};
48
+} Position;
46 49
 
47 50
 class Arene {
48 51
 public:
@@ -55,7 +58,12 @@ public:
55 58
 class Img {
56 59
 public:
57 60
     Img(ImageMat imgMatrice);
61
+    
62
+    string ToString();
63
+    Img* Copy();
64
+    
58 65
     Jpg toJpg();
66
+    string ToBase64();
59 67
     Arene search_arena();
60 68
 
61 69
     int draw_robot(Position robot);
@@ -63,11 +71,12 @@ public:
63 71
     int draw_arena(Arene areneToDraw);
64 72
     std::list<Position> search_robot(Arene monArene);
65 73
     
74
+    
66 75
 #ifdef __WITH_ARUCO__    
67
-    std::list<Position> search_aruco(Arene monArene = NULL);
76
+    list<Position> search_aruco(Arene monArene = NULL);
68 77
 #endif // __WITH_ARUCO__
69 78
 private:
70
-    cv::Mat img;
79
+    ImageMat img;
71 80
     
72 81
 #ifdef __WITH_ARUCO__
73 82
     Ptr<std::Dictionary> dictionary;

+ 427
- 42
software/raspberry/superviseur-robot/lib/messages.cpp View File

@@ -21,13 +21,14 @@
21 21
 #include <string>
22 22
 
23 23
 /*
24
- * Constants used with ToString method, for printing message id
24
+ * @brief Constants used with ToString method, for printing message id
25 25
  */
26 26
 
27 27
 const string MESSAGE_ID_STRING[] = {
28 28
     "Empty",
29 29
     "Log",
30 30
     "Answer",
31
+    "Monitor connection lost",
31 32
     "Open serial com",
32 33
     "Close serial com",
33 34
     "Open camera",
@@ -37,7 +38,7 @@ const string MESSAGE_ID_STRING[] = {
37 38
     "Arena infirmed",
38 39
     "Compute position",
39 40
     "Stop compute position",
40
-    "Position,
41
+    "Position",
41 42
     "Image",
42 43
     "Robot ping",
43 44
     "Robot reset",
@@ -56,7 +57,19 @@ const string MESSAGE_ID_STRING[] = {
56 57
     "Robot battery level",
57 58
     "Robot get state",
58 59
     "Robot current state"
60
+};
59 61
 
62
+/*
63
+ * @brief Constants used with ToString method, for printing answer id
64
+ */
65
+const string ANSWER_ID_STRING[] = {
66
+    "Acknowledge",
67
+    "Not Acknowledge",
68
+    "Robot lost",
69
+    "Timeout error",
70
+    "Unknown command",
71
+    "Invalid or refused command",
72
+    "Checksum error"
60 73
 };
61 74
 
62 75
 /**
@@ -67,12 +80,29 @@ Message::Message() {
67 80
 }
68 81
 
69 82
 /**
83
+ * Create a new, empty message
84
+ */
85
+Message::Message(MessageID id) {
86
+    SetID(id);
87
+}
88
+
89
+/**
70 90
  * Destroy message
71 91
  */
72 92
 Message::~Message() {
73 93
 }
74 94
 
75 95
 /**
96
+ * Set message ID
97
+ * @param id Message ID
98
+ */
99
+void Message::SetID(MessageID id) {
100
+    if (CheckID(id)) {
101
+        this->messageID = id;
102
+    } else throw std::runtime_error {"Invalid message id for Message"};
103
+}
104
+
105
+/**
76 106
  * Translate content of message into a string that can be displayed
77 107
  * @return A string describing message contents
78 108
  */
@@ -99,6 +129,7 @@ Message* Message::Copy() {
99 129
  */
100 130
 bool Message::CheckID(MessageID id) {
101 131
     if ((id != MESSAGE_EMPTY) &&
132
+            (id != MESSAGE_MONITOR_LOST) &&
102 133
             (id != MESSAGE_ARENA_CONFIRM) &&
103 134
             (id != MESSAGE_ARENA_INFIRM) &&
104 135
             (id != MESSAGE_ASK_ARENA) &&
@@ -125,23 +156,23 @@ bool Message::CheckID(MessageID id) {
125 156
     } else return true;
126 157
 }
127 158
 
128
-/* MessageFloat */
159
+/* MessageInt */
129 160
 
130 161
 /**
131
- * Create a new, empty float message
162
+ * Create a new, empty int message
132 163
  */
133
-MessageFloat::MessageFloat() {
164
+MessageInt::MessageInt() {
134 165
     value = 0.0;
135 166
 }
136 167
 
137 168
 /**
138
- * Create a new float message, with given ID and value
169
+ * Create a new int message, with given ID and value
139 170
  * @param id Message ID
140 171
  * @param val Message value
141
- * @throw std::runtime_error if message ID is incompatible with float data
172
+ * @throw std::runtime_error if message ID is incompatible with int data
142 173
  */
143
-MessageFloat::MessageFloat(MessageID id, float val) {
144
-    MessageFloat::SetID(id);
174
+MessageInt::MessageInt(MessageID id, int val) {
175
+    MessageInt::SetID(id);
145 176
 
146 177
     value = val;
147 178
 }
@@ -151,12 +182,12 @@ MessageFloat::MessageFloat(MessageID id, float val) {
151 182
  * @param id Message ID
152 183
  * @throw std::runtime_error if message ID is incompatible with float data
153 184
  */
154
-void MessageFloat::SetID(MessageID id) {
185
+void MessageInt::SetID(MessageID id) {
155 186
     if (CheckID(id))
156 187
         messageID = id;
157 188
     else
158 189
         throw std::runtime_error {
159
-        "Invalid message id for MessageFloat"
190
+        "Invalid message id for MessageInt"
160 191
     };
161 192
 }
162 193
 
@@ -164,7 +195,7 @@ void MessageFloat::SetID(MessageID id) {
164 195
  * Translate content of message into a string that can be displayed
165 196
  * @return A string describing message contents
166 197
  */
167
-string MessageFloat::ToString() {
198
+string MessageInt::ToString() {
168 199
     if (CheckID(this->messageID))
169 200
         return "Id: \"" + MESSAGE_ID_STRING[this->messageID] + "\"\nValue: " + to_string(this->value);
170 201
     else
@@ -172,11 +203,11 @@ string MessageFloat::ToString() {
172 203
 }
173 204
 
174 205
 /**
175
- * Allocate a new mesage and copy contents of current message
206
+ * Allocate a new message and copy contents of current message
176 207
  * @return A message, copy of current
177 208
  */
178
-Message* MessageFloat::Copy() {
179
-    return new MessageFloat(this->messageID, this->value);
209
+Message* MessageInt::Copy() {
210
+    return new MessageInt(this->messageID, this->value);
180 211
 }
181 212
 
182 213
 /**
@@ -184,13 +215,9 @@ Message* MessageFloat::Copy() {
184 215
  * @param id Message ID
185 216
  * @return true, if message ID is acceptable, false otherwise
186 217
  */
187
-bool MessageFloat::CheckID(MessageID id) {
188
-    if ((id != MESSAGE_ANGLE_POSITION) &&
189
-            (id != MESSAGE_ANGULAR_SPEED) &&
190
-            (id != MESSAGE_BATTERY) &&
191
-            (id != MESSAGE_BETA) &&
192
-            (id != MESSAGE_LINEAR_SPEED) &&
193
-            (id != MESSAGE_TORQUE)) {
218
+bool MessageInt::CheckID(MessageID id) {
219
+    if ((id != MESSAGE_ROBOT_TURN) &&
220
+            (id != MESSAGE_ROBOT_MOVE)) {
194 221
         return false;
195 222
     } else return true;
196 223
 }
@@ -260,48 +287,147 @@ bool MessageString::CheckID(MessageID id) {
260 287
     } else return true;
261 288
 }
262 289
 
263
-/* class MessageBool */
290
+/* class MessageImg */
291
+
292
+/**
293
+ * Create a new, empty image message
294
+ */
295
+MessageImg::MessageImg() {
296
+    image = NULL;
297
+}
298
+
299
+/**
300
+ * Create a new image message, with given ID and image
301
+ * @param id Message ID
302
+ * @param image Image
303
+ * @throw std::runtime_error if message ID is incompatible with image
304
+ */
305
+MessageImg::MessageImg(MessageID id, Img* image) {
306
+    MessageImg::SetID(id);
307
+    MessageImg::SetImage(image);
308
+}
264 309
 
265 310
 /**
266
- * Create a new, empty boolean message
311
+ * Destroy Image message
267 312
  */
268
-MessageBool::MessageBool() {
269
-    state = false;
313
+MessageImg::~MessageImg() {
314
+    delete (this->image);
270 315
 }
271 316
 
272 317
 /**
273
- * Create a new boolean message, with given ID and boolean value
318
+ * Set message ID
319
+ * @param id Message ID
320
+ * @throw std::runtime_error if message ID is incompatible with image
321
+ */
322
+void MessageImg::SetID(MessageID id) {
323
+    if (CheckID(id))
324
+        messageID = id;
325
+    else
326
+        throw std::runtime_error {
327
+        "Invalid message id for MessageImg"
328
+    };
329
+}
330
+
331
+/**
332
+ * Set message image
333
+ * @param image Reference to image object
334
+ */
335
+void MessageImg::SetImage(Img* image) {
336
+    this->image = image->Copy();
337
+}
338
+
339
+/**
340
+ * Translate content of message into a string that can be displayed
341
+ * @return A string describing message contents
342
+ */
343
+string MessageImg::ToString() {
344
+    if (CheckID(this->messageID))
345
+        return "Id: \"" + MESSAGE_ID_STRING[this->messageID] + "\"\n" + this->image->ToString();
346
+    else
347
+        return "Invalid message";
348
+}
349
+
350
+/**
351
+ * Allocate a new message and copy contents of current message
352
+ * @return A message, copy of current
353
+ */
354
+Message* MessageImg::Copy() {
355
+    
356
+    return new MessageImg(this->messageID, this->image->Copy());
357
+}
358
+
359
+/**
360
+ * Verify if message ID is compatible with current message type
274 361
  * @param id Message ID
275
- * @param state Boolean value
276
- * @throw std::runtime_error if message ID is incompatible with boolean data
362
+ * @return true, if message ID is acceptable, false otherwise
277 363
  */
278
-MessageBool::MessageBool(MessageID id, bool state) {
279
-    MessageBool::SetID(id);
364
+bool MessageImg::CheckID(MessageID id) {
365
+    if (id != MESSAGE_IMAGE) {
366
+        return false;
367
+    } else return true;
368
+}
280 369
 
281
-    this->state = state;
370
+/* class MessageAnswer*/
371
+
372
+/**
373
+ * Create a new, empty answer message
374
+ */
375
+MessageAnswer::MessageAnswer() {
376
+    answer=ANSWER_ACK;
377
+}
378
+
379
+/**
380
+ * Create a new answer message, with given ID and answer
381
+ * @param id Message ID
382
+ * @param ans Answer ID
383
+ * @throw std::runtime_error if message ID is incompatible with string data
384
+ */
385
+MessageAnswer::MessageAnswer(MessageID id, AnswerID ans) {
386
+    MessageAnswer::SetID(id);
387
+    MessageAnswer::SetAnswer(ans);
282 388
 }
283 389
 
284 390
 /**
285 391
  * Set message ID
286 392
  * @param id Message ID
287
- * @throw std::runtime_error if message ID is incompatible with boolean data
393
+ * @throw std::runtime_error if message ID is incompatible with answer message
288 394
  */
289
-void MessageBool::SetID(MessageID id) {
395
+void MessageAnswer::SetID(MessageID id) {
290 396
     if (CheckID(id))
291 397
         messageID = id;
292 398
     else
293 399
         throw std::runtime_error {
294
-        "Invalid message id for MessageBool"
400
+        "Invalid message id for MessageAnswer"
295 401
     };
296 402
 }
297 403
 
298 404
 /**
405
+ * Set message answer
406
+ * @param ans Answer ID
407
+ * @throw std::runtime_error if answer ID is incompatible with answer data
408
+ */
409
+void MessageAnswer::SetAnswer(AnswerID ans) {
410
+    if ((ans != ANSWER_ACK) &&
411
+            (ans != ANSWER_NACK) &&
412
+            (ans != ANSWER_LOST_ROBOT) &&
413
+            (ans != ANSWER_ROBOT_CHECKSUM) &&
414
+            (ans != ANSWER_ROBOT_ERROR) &&
415
+            (ans != ANSWER_ROBOT_TIMEOUT) &&
416
+            (ans != ANSWER_ROBOT_UNKNOWN_COMMAND)) {
417
+        this->answer = answer;
418
+    } else {
419
+        throw std::runtime_error{
420
+            "Invalid answer for MessageAnswer"};
421
+    }
422
+}
423
+
424
+/**
299 425
  * Translate content of message into a string that can be displayed
300 426
  * @return A string describing message contents
301 427
  */
302
-string MessageBool::ToString() {
428
+string MessageAnswer::ToString() {
303 429
     if (CheckID(this->messageID))
304
-        return "Id: \"" + MESSAGE_ID_STRING[this->messageID] + "\"\nState: \"" + to_string(this->state) + "\"";
430
+        return "Id: \"" + MESSAGE_ID_STRING[this->messageID] + "\"\nAnswer: \"" + ANSWER_ID_STRING[this->answer] + "\"";
305 431
     else
306 432
         return "Invalid message";
307 433
 }
@@ -310,8 +436,8 @@ string MessageBool::ToString() {
310 436
  * Allocate a new message and copy contents of current message
311 437
  * @return A message, copy of current
312 438
  */
313
-Message* MessageBool::Copy() {
314
-    return new MessageBool(this->messageID, this->state);
439
+Message* MessageAnswer::Copy() {
440
+    return new MessageAnswer(this->messageID, this->answer);
315 441
 }
316 442
 
317 443
 /**
@@ -319,9 +445,268 @@ Message* MessageBool::Copy() {
319 445
  * @param id Message ID
320 446
  * @return true, if message ID is acceptable, false otherwise
321 447
  */
322
-bool MessageBool::CheckID(MessageID id) {
323
-    if ((id != MESSAGE_EMERGENCY_STOP) &&
324
-            (id != MESSAGE_USER_PRESENCE)) {
448
+bool MessageAnswer::CheckID(MessageID id) {
449
+    if ((id != MESSAGE_ANSWER)) {
325 450
         return false;
326 451
     } else return true;
327 452
 }
453
+
454
+/* class MessageBattery */
455
+
456
+/**
457
+ * Create a new, empty battery message
458
+ */
459
+MessageBattery::MessageBattery() {
460
+    this->level = BATTERY_UNKNOWN;
461
+}
462
+
463
+/**
464
+ * Create a new battery message, with given ID and battery level
465
+ * @param id Message ID
466
+ * @param level Battery level
467
+ * @throw std::runtime_error if message ID is incompatible with battery
468
+ */
469
+MessageBattery::MessageBattery(MessageID id, BatteryLevel level) {
470
+    MessageBattery::SetID(id);
471
+    MessageBattery::SetLevel(level);
472
+}
473
+
474
+/**
475
+ * Set message ID
476
+ * @param id Message ID
477
+ * @throw std::runtime_error if message ID is incompatible with battery
478
+ */
479
+void MessageBattery::SetID(MessageID id) {
480
+    if (CheckID(id))
481
+        messageID = id;
482
+    else
483
+        throw std::runtime_error {
484
+        "Invalid message id for MessageBattery"
485
+    };
486
+}
487
+
488
+/**
489
+ * Set battery level
490
+ * @param level Battery level
491
+ */
492
+void MessageBattery::SetLevel(BatteryLevel level) {
493
+    if ((level < BATTERY_UNKNOWN) || (level > BATTERY_FULL)) {
494
+        throw std::runtime_error{
495
+            "Invalid battery level for MessageBattery"};
496
+    } else {
497
+        this->level = level;
498
+    }
499
+}
500
+
501
+/**
502
+ * Translate content of message into a string that can be displayed
503
+ * @return A string describing message contents
504
+ */
505
+string MessageBattery::ToString() {
506
+    string levelString;
507
+    
508
+    switch (this->level) {
509
+        case BATTERY_UNKNOWN:
510
+            levelString="Unknown";
511
+            break;
512
+        case BATTERY_EMPTY:
513
+            levelString="Empty";
514
+            break;
515
+        case BATTERY_LOW:
516
+            levelString="Low";
517
+            break;
518
+        case BATTERY_FULL:
519
+            levelString="Full";
520
+            break;
521
+        default:
522
+            levelString="Invalid";
523
+    }
524
+    
525
+    if (CheckID(this->messageID))
526
+        return "Id: \"" + MESSAGE_ID_STRING[this->messageID] + "\"\nBattery level: \"" + levelString + "\"";
527
+    else
528
+        return "Invalid message";
529
+}
530
+
531
+/**
532
+ * Allocate a new message and copy contents of current message
533
+ * @return A message, copy of current
534
+ */
535
+Message* MessageBattery::Copy() {
536
+    return new MessageBattery(this->messageID, this->level);
537
+}
538
+
539
+/**
540
+ * Verify if message ID is compatible with current message type
541
+ * @param id Message ID
542
+ * @return true, if message ID is acceptable, false otherwise
543
+ */
544
+bool MessageBattery::CheckID(MessageID id) {
545
+    if ((id != MESSAGE_ROBOT_BATTERY_LEVEL)) {
546
+        return false;
547
+    } else return true;
548
+}
549
+
550
+/* class MessagePosition */
551
+
552
+/**
553
+ * Create a new, empty string message
554
+ */
555
+MessagePosition::MessagePosition() {
556
+    this->pos.angle = 0.0;
557
+    this->pos.robotId = 0;
558
+    this->pos.center.x=0.0;
559
+    this->pos.center.y=0.0;
560
+    this->pos.direction.x=0.0;
561
+    this->pos.direction.y=0.0;
562
+}
563
+
564
+/**
565
+ * Create a new string message, with given ID and string
566
+ * @param id Message ID
567
+ * @param s Message string
568
+ * @throw std::runtime_error if message ID is incompatible with string data
569
+ */
570
+MessagePosition::MessagePosition(MessageID id, Position& pos) {
571
+    MessagePosition::SetID(id);
572
+    MessagePosition::SetPosition(pos);
573
+}
574
+
575
+/**
576
+ * Set message ID
577
+ * @param id Message ID
578
+ * @throw std::runtime_error if message ID is incompatible with string data
579
+ */
580
+void MessagePosition::SetID(MessageID id) {
581
+    if (CheckID(id))
582
+        messageID = id;
583
+    else
584
+        throw std::runtime_error {
585
+        "Invalid message id for MessagePosition"
586
+    };
587
+}
588
+
589
+/**
590
+ * Set position
591
+ * @param pos Reference to position
592
+ */
593
+void MessagePosition::SetPosition(Position& pos) {
594
+    this->pos.angle = pos.angle;
595
+    this->pos.robotId = pos.robotId;
596
+    this->pos.center = pos.center;
597
+    this->pos.direction = pos.direction;
598
+}
599
+    
600
+/**
601
+ * Translate content of message into a string that can be displayed
602
+ * @return A string describing message contents
603
+ */
604
+string MessagePosition::ToString() {
605
+    if (CheckID(this->messageID))
606
+        return "Id: \"" + MESSAGE_ID_STRING[this->messageID] + "\"\nPosition: \"" + to_string(this->pos.center.x) + ";" + to_string(this->pos.center.y) + "\"";
607
+    else
608
+        return "Invalid message";
609
+}
610
+
611
+/**
612
+ * Allocate a new message and copy contents of current message
613
+ * @return A message, copy of current
614
+ */
615
+Message* MessagePosition::Copy() {
616
+    return new MessagePosition(this->messageID, this->pos);
617
+}
618
+
619
+/**
620
+ * Verify if message ID is compatible with current message type
621
+ * @param id Message ID
622
+ * @return true, if message ID is acceptable, false otherwise
623
+ */
624
+bool MessagePosition::CheckID(MessageID id) {
625
+    if ((id != MESSAGE_POSITION)) {
626
+        return false;
627
+    } else return true;
628
+}
629
+
630
+
631
+/* class MessageState */
632
+
633
+/**
634
+ * Create a new, empty state message
635
+ */
636
+MessageState::MessageState() {
637
+    state = ROBOT_NOT_BUSY;
638
+}
639
+
640
+/**
641
+ * Create a new string message, with given ID and string
642
+ * @param id Message ID
643
+ * @param s Message string
644
+ * @throw std::runtime_error if message ID is incompatible with string data
645
+ */
646
+MessageState::MessageState(MessageID id, RobotState state) {
647
+    MessageState::SetID(id);
648
+    MessageState::SetState(state);
649
+}
650
+
651
+/**
652
+ * Set message ID
653
+ * @param id Message ID
654
+ * @throw std::runtime_error if message ID is incompatible with robot state
655
+ */
656
+void MessageState::SetID(MessageID id) {
657
+    if (CheckID(id))
658
+        messageID = id;
659
+    else
660
+        throw std::runtime_error {
661
+        "Invalid message id for MessageState"
662
+    };
663
+}
664
+
665
+/**
666
+ * Set robot state
667
+ * @param state Robot state
668
+ */
669
+void MessageState::SetState(RobotState state) {
670
+    if ((state != ROBOT_NOT_BUSY) && (state != ROBOT_BUSY)) {
671
+        throw std::runtime_error{
672
+            "Invalid state for MessageState"};
673
+    } else {
674
+        this->state = state;
675
+    }
676
+}
677
+    
678
+/**
679
+ * Translate content of message into a string that can be displayed
680
+ * @return A string describing message contents
681
+ */
682
+string MessageState::ToString() {
683
+    string stateString;
684
+    
685
+    if (this->state == ROBOT_NOT_BUSY) stateString="Not busy";
686
+    else if (this->state == ROBOT_BUSY) stateString="Busy";
687
+    else stateString="Invalid state";
688
+    
689
+    if (CheckID(this->messageID))
690
+        return "Id: \"" + MESSAGE_ID_STRING[this->messageID] + "\"\nState: \"" + stateString + "\"";
691
+    else
692
+        return "Invalid message";
693
+}
694
+
695
+/**
696
+ * Allocate a new message and copy contents of current message
697
+ * @return A message, copy of current
698
+ */
699
+Message* MessageState::Copy() {
700
+    return new MessageState(this->messageID, this->state);
701
+}
702
+
703
+/**
704
+ * Verify if message ID is compatible with current message type
705
+ * @param id Message ID
706
+ * @return true, if message ID is acceptable, false otherwise
707
+ */
708
+bool MessageState::CheckID(MessageID id) {
709
+    if ((id != MESSAGE_ROBOT_CURRENT_STATE)) {
710
+        return false;
711
+    } else return true;
712
+}

+ 29
- 113
software/raspberry/superviseur-robot/lib/messages.h View File

@@ -38,7 +38,10 @@ typedef enum {
38 38
     // messages for serial communication with robot
39 39
     MESSAGE_OPEN_COM,
40 40
     MESSAGE_CLOSE_COM,
41
-            
41
+         
42
+    // Messages specific to server
43
+    MESSAGE_MONITOR_LOST,
44
+    
42 45
     // Messages for camera   
43 46
     MESSAGE_CAM_OPEN,
44 47
     MESSAGE_CAM_CLOSE,
@@ -75,12 +78,13 @@ typedef enum {
75 78
     ANSWER_NACK,
76 79
     ANSWER_LOST_ROBOT,
77 80
     ANSWER_ROBOT_TIMEOUT,
78
-    ANSWER_ROBOT_UNKNWON_COMMAND,
81
+    ANSWER_ROBOT_UNKNOWN_COMMAND,
79 82
     ANSWER_ROBOT_ERROR,
80 83
     ANSWER_ROBOT_CHECKSUM
81 84
 } AnswerID;
82 85
 
83 86
 typedef enum {
87
+    BATTERY_UNKNOWN=-1,
84 88
     BATTERY_EMPTY=0,
85 89
     BATTERY_LOW,
86 90
     BATTERY_FULL
@@ -107,6 +111,11 @@ public:
107 111
     Message();
108 112
 
109 113
     /**
114
+     * Create a new, empty message
115
+     */
116
+    Message(MessageID id);
117
+    
118
+    /**
110 119
      * Destroy message
111 120
      */
112 121
     virtual ~Message();
@@ -135,8 +144,7 @@ public:
135 144
      * Set message ID
136 145
      * @param id Message ID
137 146
      */
138
-    virtual void SetID(MessageID id) {
139
-    }
147
+    virtual void SetID(MessageID id);
140 148
 
141 149
     /**
142 150
      * Comparison operator
@@ -260,93 +268,6 @@ protected:
260 268
 };
261 269
 
262 270
 /**
263
- * Message class for holding float value, based on Message class
264
- * 
265
- * @brief Float message class
266
- * 
267
- */
268
-class MessageFloat : public Message {
269
-public:
270
-    /**
271
-     * Create a new, empty float message
272
-     */
273
-    MessageFloat();
274
-
275
-    /**
276
-     * Create a new float message, with given ID and value
277
-     * @param id Message ID
278
-     * @param val Message value
279
-     * @throw std::runtime_error if message ID is incompatible with float data
280
-     */
281
-    MessageFloat(MessageID id, float val);
282
-
283
-    /**
284
-     * Set message ID
285
-     * @param id Message ID
286
-     * @throw std::runtime_error if message ID is incompatible with float data
287
-     */
288
-    void SetID(MessageID id);
289
-
290
-    /**
291
-     * Get message value (float)
292
-     * @return Float value
293
-     */
294
-    float GetValue() {
295
-        return value;
296
-    }
297
-
298
-    /**
299
-     * Set message value (float)
300
-     * @param val Float value to store in message
301
-     */
302
-    void SetValue(float val) {
303
-        this->value = val;
304
-    }
305
-
306
-    /**
307
-     * Translate content of message into a string that can be displayed
308
-     * @return A string describing message contents
309
-     */
310
-    string ToString();
311
-
312
-    /**
313
-     * Allocate a new mesage and copy contents of current message
314
-     * @return A message, copy of current
315
-     */
316
-    Message* Copy();
317
-
318
-    /**
319
-     * Comparison operator
320
-     * @param msg Message to be compared
321
-     * @return true if message are equal, false otherwise
322
-     */
323
-    virtual bool operator==(const MessageFloat& msg) {
324
-        return ((messageID == msg.messageID) && (value == msg.value));
325
-    }
326
-
327
-    /**
328
-     * Difference operator
329
-     * @param msg Message to be compared
330
-     * @return true if message are different, false otherwise
331
-     */
332
-    virtual bool operator!=(const MessageFloat& msg) {
333
-        return !((messageID == msg.messageID) && (value == msg.value));
334
-    }
335
-protected:
336
-    /**
337
-     * Message float value
338
-     */
339
-    float value;
340
-
341
-    /**
342
-     * Verify if message ID is compatible with current message type
343
-     * @param id Message ID
344
-     * @return true, if message ID is acceptable, false otherwise
345
-     */
346
-    bool CheckID(MessageID id);
347
-};
348
-
349
-/**
350 271
  * Message class for holding string value, based on Message class
351 272
  * 
352 273
  * @brief String message class
@@ -455,6 +376,11 @@ public:
455 376
     MessageImg(MessageID id, Img* image);
456 377
 
457 378
     /**
379
+     * Destroy Image message
380
+     */
381
+    virtual ~MessageImg();
382
+    
383
+    /**
458 384
      * Set message ID
459 385
      * @param id Message ID
460 386
      * @throw std::runtime_error if message ID is incompatible withimage message
@@ -473,9 +399,7 @@ public:
473 399
      * Set message image
474 400
      * @param image Pointer to image object
475 401
      */
476
-    void SetImage(Img* image) {
477
-        this->image = image;
478
-    }
402
+    void SetImage(Img* image);
479 403
 
480 404
     /**
481 405
      * Translate content of message into a string that can be displayed
@@ -519,10 +443,10 @@ public:
519 443
     /**
520 444
      * Create a new image message, with given ID and boolean value
521 445
      * @param id Message ID
522
-     * @param image Pointer to image
446
+     * @param pos Position
523 447
      * @throw std::runtime_error if message ID is incompatible with image message
524 448
      */
525
-    MessagePosition(MessageID id, Position pos);
449
+    MessagePosition(MessageID id, Position& pos);
526 450
 
527 451
     /**
528 452
      * Set message ID
@@ -543,9 +467,7 @@ public:
543 467
      * Set message image
544 468
      * @param image Pointer to image object
545 469
      */
546
-    void SetPosition(Position pos) {
547
-        this->pos = pos;
548
-    }
470
+    void SetPosition(Position& pos);
549 471
 
550 472
     /**
551 473
      * Translate content of message into a string that can be displayed
@@ -613,9 +535,7 @@ public:
613 535
      * Set message image
614 536
      * @param image Pointer to image object
615 537
      */
616
-    void SetLevel(BatteryLevel level) {
617
-        this->level = level;
618
-    }
538
+    void SetLevel(BatteryLevel level);
619 539
 
620 540
     /**
621 541
      * Translate content of message into a string that can be displayed
@@ -659,10 +579,10 @@ public:
659 579
     /**
660 580
      * Create a new image message, with given ID and boolean value
661 581
      * @param id Message ID
662
-     * @param image Pointer to image
582
+     * @param ans Answer ID
663 583
      * @throw std::runtime_error if message ID is incompatible with image message
664 584
      */
665
-    MessageAnswer(MessageID id, AnswerID answer);
585
+    MessageAnswer(MessageID id, AnswerID ans);
666 586
 
667 587
     /**
668 588
      * Set message ID
@@ -680,12 +600,10 @@ public:
680 600
     }
681 601
 
682 602
     /**
683
-     * Set message image
684
-     * @param image Pointer to image object
603
+     * Set message answer
604
+     * @param ans Answer ID
685 605
      */
686
-    void SetAnswer(AnswerID answer) {
687
-        this->answer = answer;
688
-    }
606
+    void SetAnswer(AnswerID ans);
689 607
 
690 608
     /**
691 609
      * Translate content of message into a string that can be displayed
@@ -753,9 +671,7 @@ public:
753 671
      * Set message image
754 672
      * @param image Pointer to image object
755 673
      */
756
-    void SetState(RobotState state) {
757
-        this->state = state;
758
-    }
674
+    void SetState(RobotState state);
759 675
 
760 676
     /**
761 677
      * Translate content of message into a string that can be displayed
@@ -771,7 +687,7 @@ public:
771 687
 
772 688
 protected:
773 689
     /**
774
-     * Message answer
690
+     * Robot state
775 691
      */
776 692
    RobotState state;
777 693
 

+ 19
- 1
software/raspberry/superviseur-robot/nbproject/Makefile-Debug.mk View File

@@ -41,7 +41,10 @@ OBJECTFILES= \
41 41
 	${OBJECTDIR}/lib/robot.o \
42 42
 	${OBJECTDIR}/lib/server.o \
43 43
 	${OBJECTDIR}/main.o \
44
-	${OBJECTDIR}/tasks.o
44
+	${OBJECTDIR}/tasks.o \
45
+	${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o \
46
+	${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o \
47
+	${OBJECTDIR}/tasks_pthread.o
45 48
 
46 49
 
47 50
 # C Compiler Flags
@@ -103,6 +106,21 @@ ${OBJECTDIR}/tasks.o: tasks.cpp
103 106
 	${RM} "$@.d"
104 107
 	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -I./ -I./lib -I/usr/xenomai/include -I/usr/xenomai/include/mercury `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/tasks.o tasks.cpp
105 108
 
109
+${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o: /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp
110
+	${MKDIR} -p ${OBJECTDIR}/_ext/6cc0dc4a
111
+	${RM} "$@.d"
112
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -I./ -I./lib -I/usr/xenomai/include -I/usr/xenomai/include/mercury `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp
113
+
114
+${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o: /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp
115
+	${MKDIR} -p ${OBJECTDIR}/_ext/6cc0dc4a
116
+	${RM} "$@.d"
117
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -I./ -I./lib -I/usr/xenomai/include -I/usr/xenomai/include/mercury `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp
118
+
119
+${OBJECTDIR}/tasks_pthread.o: tasks_pthread.cpp
120
+	${MKDIR} -p ${OBJECTDIR}
121
+	${RM} "$@.d"
122
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -I./ -I./lib -I/usr/xenomai/include -I/usr/xenomai/include/mercury `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/tasks_pthread.o tasks_pthread.cpp
123
+
106 124
 # Subprojects
107 125
 .build-subprojects:
108 126
 

+ 131
- 0
software/raspberry/superviseur-robot/nbproject/Makefile-Debug__Pthread_.mk View File

@@ -0,0 +1,131 @@
1
+#
2
+# Generated Makefile - do not edit!
3
+#
4
+# Edit the Makefile in the project folder instead (../Makefile). Each target
5
+# has a -pre and a -post target defined where you can add customized code.
6
+#
7
+# This makefile implements configuration specific macros and targets.
8
+
9
+
10
+# Environment
11
+MKDIR=mkdir
12
+CP=cp
13
+GREP=grep
14
+NM=nm
15
+CCADMIN=CCadmin
16
+RANLIB=ranlib
17
+CC=gcc
18
+CCC=g++
19
+CXX=g++
20
+FC=gfortran
21
+AS=as
22
+
23
+# Macros
24
+CND_PLATFORM=GNU-Linux
25
+CND_DLIB_EXT=so
26
+CND_CONF=Debug__Pthread_
27
+CND_DISTDIR=dist
28
+CND_BUILDDIR=build
29
+
30
+# Include project Makefile
31
+include ./Makefile
32
+
33
+# Object Directory
34
+OBJECTDIR=${CND_BUILDDIR}/${CND_CONF}/${CND_PLATFORM}
35
+
36
+# Object Files
37
+OBJECTFILES= \
38
+	${OBJECTDIR}/lib/message.o \
39
+	${OBJECTDIR}/lib/messages.o \
40
+	${OBJECTDIR}/lib/monitor.o \
41
+	${OBJECTDIR}/lib/robot.o \
42
+	${OBJECTDIR}/lib/server.o \
43
+	${OBJECTDIR}/main.o \
44
+	${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o \
45
+	${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o \
46
+	${OBJECTDIR}/tasks_pthread.o
47
+
48
+
49
+# C Compiler Flags
50
+CFLAGS=-I/usr/xenomai/include/mercury -I/usr/xenomai/include -D_GNU_SOURCE -D_REENTRANT -fasynchronous-unwind-tables -D__MERCURY__ -I/usr/xenomai/include/alchemy
51
+
52
+# CC Compiler Flags
53
+CCFLAGS=-D_GNU_SOURCE -D_REENTRANT -fasynchronous-unwind-tables
54
+CXXFLAGS=-D_GNU_SOURCE -D_REENTRANT -fasynchronous-unwind-tables
55
+
56
+# Fortran Compiler Flags
57
+FFLAGS=
58
+
59
+# Assembler Flags
60
+ASFLAGS=
61
+
62
+# Link Libraries and Options
63
+LDLIBSOPTIONS=`pkg-config --libs opencv`  
64
+
65
+# Build Targets
66
+.build-conf: ${BUILD_SUBPROJECTS}
67
+	"${MAKE}"  -f nbproject/Makefile-${CND_CONF}.mk ${CND_DISTDIR}/${CND_CONF}/${CND_PLATFORM}/superviseur-robot
68
+
69
+${CND_DISTDIR}/${CND_CONF}/${CND_PLATFORM}/superviseur-robot: ${OBJECTFILES}
70
+	${MKDIR} -p ${CND_DISTDIR}/${CND_CONF}/${CND_PLATFORM}
71
+	${LINK.cc} -o ${CND_DISTDIR}/${CND_CONF}/${CND_PLATFORM}/superviseur-robot ${OBJECTFILES} ${LDLIBSOPTIONS} -lpthread -lrt
72
+
73
+${OBJECTDIR}/lib/message.o: lib/message.cpp
74
+	${MKDIR} -p ${OBJECTDIR}/lib
75
+	${RM} "$@.d"
76
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -D__WITH_PTHREAD__ -I./ -I./lib `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/lib/message.o lib/message.cpp
77
+
78
+${OBJECTDIR}/lib/messages.o: lib/messages.cpp
79
+	${MKDIR} -p ${OBJECTDIR}/lib
80
+	${RM} "$@.d"
81
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -D__WITH_PTHREAD__ -I./ -I./lib `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/lib/messages.o lib/messages.cpp
82
+
83
+${OBJECTDIR}/lib/monitor.o: lib/monitor.cpp
84
+	${MKDIR} -p ${OBJECTDIR}/lib
85
+	${RM} "$@.d"
86
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -D__WITH_PTHREAD__ -I./ -I./lib `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/lib/monitor.o lib/monitor.cpp
87
+
88
+${OBJECTDIR}/lib/robot.o: lib/robot.cpp
89
+	${MKDIR} -p ${OBJECTDIR}/lib
90
+	${RM} "$@.d"
91
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -D__WITH_PTHREAD__ -I./ -I./lib `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/lib/robot.o lib/robot.cpp
92
+
93
+${OBJECTDIR}/lib/server.o: lib/server.cpp
94
+	${MKDIR} -p ${OBJECTDIR}/lib
95
+	${RM} "$@.d"
96
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -D__WITH_PTHREAD__ -I./ -I./lib `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/lib/server.o lib/server.cpp
97
+
98
+${OBJECTDIR}/main.o: main.cpp
99
+	${MKDIR} -p ${OBJECTDIR}
100
+	${RM} "$@.d"
101
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -D__WITH_PTHREAD__ -I./ -I./lib `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/main.o main.cpp
102
+
103
+${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o: /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp
104
+	${MKDIR} -p ${OBJECTDIR}/_ext/6cc0dc4a
105
+	${RM} "$@.d"
106
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -D__WITH_PTHREAD__ -I./ -I./lib `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp
107
+
108
+${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o: /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp
109
+	${MKDIR} -p ${OBJECTDIR}/_ext/6cc0dc4a
110
+	${RM} "$@.d"
111
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -D__WITH_PTHREAD__ -I./ -I./lib `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp
112
+
113
+${OBJECTDIR}/tasks_pthread.o: tasks_pthread.cpp
114
+	${MKDIR} -p ${OBJECTDIR}
115
+	${RM} "$@.d"
116
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -D__FOR_PC__ -D__WITH_PTHREAD__ -I./ -I./lib `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/tasks_pthread.o tasks_pthread.cpp
117
+
118
+# Subprojects
119
+.build-subprojects:
120
+
121
+# Clean Targets
122
+.clean-conf: ${CLEAN_SUBPROJECTS}
123
+	${RM} -r ${CND_BUILDDIR}/${CND_CONF}
124
+
125
+# Subprojects
126
+.clean-subprojects:
127
+
128
+# Enable dependency checking
129
+.dep.inc: .depcheck-impl
130
+
131
+include .dep.inc

+ 19
- 1
software/raspberry/superviseur-robot/nbproject/Makefile-Debug__RPI_.mk View File

@@ -42,7 +42,10 @@ OBJECTFILES= \
42 42
 	${OBJECTDIR}/lib/robot.o \
43 43
 	${OBJECTDIR}/lib/server.o \
44 44
 	${OBJECTDIR}/main.o \
45
-	${OBJECTDIR}/tasks.o
45
+	${OBJECTDIR}/tasks.o \
46
+	${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o \
47
+	${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o \
48
+	${OBJECTDIR}/tasks_pthread.o
46 49
 
47 50
 
48 51
 # C Compiler Flags
@@ -109,6 +112,21 @@ ${OBJECTDIR}/tasks.o: tasks.cpp
109 112
 	${RM} "$@.d"
110 113
 	$(COMPILE.cc) -g -D_WITH_TRACE_ -I./ -I./lib -I/usr/xenomai/include -I/usr/xenomai/include/mercury `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/tasks.o tasks.cpp
111 114
 
115
+${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o: /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp
116
+	${MKDIR} -p ${OBJECTDIR}/_ext/6cc0dc4a
117
+	${RM} "$@.d"
118
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -I./ -I./lib -I/usr/xenomai/include -I/usr/xenomai/include/mercury `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp
119
+
120
+${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o: /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp
121
+	${MKDIR} -p ${OBJECTDIR}/_ext/6cc0dc4a
122
+	${RM} "$@.d"
123
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -I./ -I./lib -I/usr/xenomai/include -I/usr/xenomai/include/mercury `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp
124
+
125
+${OBJECTDIR}/tasks_pthread.o: tasks_pthread.cpp
126
+	${MKDIR} -p ${OBJECTDIR}
127
+	${RM} "$@.d"
128
+	$(COMPILE.cc) -g -D_WITH_TRACE_ -I./ -I./lib -I/usr/xenomai/include -I/usr/xenomai/include/mercury `pkg-config --cflags opencv`   -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/tasks_pthread.o tasks_pthread.cpp
129
+
112 130
 # Subprojects
113 131
 .build-subprojects:
114 132
 

+ 19
- 1
software/raspberry/superviseur-robot/nbproject/Makefile-Release.mk View File

@@ -42,7 +42,10 @@ OBJECTFILES= \
42 42
 	${OBJECTDIR}/lib/robot.o \
43 43
 	${OBJECTDIR}/lib/server.o \
44 44
 	${OBJECTDIR}/main.o \
45
-	${OBJECTDIR}/tasks.o
45
+	${OBJECTDIR}/tasks.o \
46
+	${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o \
47
+	${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o \
48
+	${OBJECTDIR}/tasks_pthread.o
46 49
 
47 50
 
48 51
 # C Compiler Flags
@@ -109,6 +112,21 @@ ${OBJECTDIR}/tasks.o: tasks.cpp
109 112
 	${RM} "$@.d"
110 113
 	$(COMPILE.cc) -O2 -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/tasks.o tasks.cpp
111 114
 
115
+${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o: /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp
116
+	${MKDIR} -p ${OBJECTDIR}/_ext/6cc0dc4a
117
+	${RM} "$@.d"
118
+	$(COMPILE.cc) -O2 -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/_ext/6cc0dc4a/commonitor.o /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp
119
+
120
+${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o: /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp
121
+	${MKDIR} -p ${OBJECTDIR}/_ext/6cc0dc4a
122
+	${RM} "$@.d"
123
+	$(COMPILE.cc) -O2 -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/_ext/6cc0dc4a/comrobot.o /home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp
124
+
125
+${OBJECTDIR}/tasks_pthread.o: tasks_pthread.cpp
126
+	${MKDIR} -p ${OBJECTDIR}
127
+	${RM} "$@.d"
128
+	$(COMPILE.cc) -O2 -MMD -MP -MF "$@.d" -o ${OBJECTDIR}/tasks_pthread.o tasks_pthread.cpp
129
+
112 130
 # Subprojects
113 131
 .build-subprojects:
114 132
 

+ 1
- 1
software/raspberry/superviseur-robot/nbproject/Makefile-impl.mk View File

@@ -31,7 +31,7 @@ DEFAULTCONF=Debug
31 31
 CONF=${DEFAULTCONF}
32 32
 
33 33
 # All Configurations
34
-ALLCONFS=Debug Release Debug__RPI_ 
34
+ALLCONFS=Debug Release Debug__RPI_ Debug__Pthread_ 
35 35
 
36 36
 
37 37
 # build

+ 8
- 0
software/raspberry/superviseur-robot/nbproject/Makefile-variables.mk View File

@@ -30,6 +30,14 @@ CND_ARTIFACT_PATH_Debug__RPI_=dist/Debug__RPI_/GNU-Linux/superviseur-robot
30 30
 CND_PACKAGE_DIR_Debug__RPI_=dist/Debug__RPI_/GNU-Linux/package
31 31
 CND_PACKAGE_NAME_Debug__RPI_=superviseur-robot.tar
32 32
 CND_PACKAGE_PATH_Debug__RPI_=dist/Debug__RPI_/GNU-Linux/package/superviseur-robot.tar
33
+# Debug__Pthread_ configuration
34
+CND_PLATFORM_Debug__Pthread_=GNU-Linux
35
+CND_ARTIFACT_DIR_Debug__Pthread_=dist/Debug__Pthread_/GNU-Linux
36
+CND_ARTIFACT_NAME_Debug__Pthread_=superviseur-robot
37
+CND_ARTIFACT_PATH_Debug__Pthread_=dist/Debug__Pthread_/GNU-Linux/superviseur-robot
38
+CND_PACKAGE_DIR_Debug__Pthread_=dist/Debug__Pthread_/GNU-Linux/package
39
+CND_PACKAGE_NAME_Debug__Pthread_=superviseur-robot.tar
40
+CND_PACKAGE_PATH_Debug__Pthread_=dist/Debug__Pthread_/GNU-Linux/package/superviseur-robot.tar
33 41
 #
34 42
 # include compiler specific variables
35 43
 #

+ 76
- 0
software/raspberry/superviseur-robot/nbproject/Package-Debug__Pthread_.bash View File

@@ -0,0 +1,76 @@
1
+#!/bin/bash -x
2
+
3
+#
4
+# Generated - do not edit!
5
+#
6
+
7
+# Macros
8
+TOP=`pwd`
9
+CND_PLATFORM=GNU-Linux
10
+CND_CONF=Debug__Pthread_
11
+CND_DISTDIR=dist
12
+CND_BUILDDIR=build
13
+CND_DLIB_EXT=so
14
+NBTMPDIR=${CND_BUILDDIR}/${CND_CONF}/${CND_PLATFORM}/tmp-packaging
15
+TMPDIRNAME=tmp-packaging
16
+OUTPUT_PATH=${CND_DISTDIR}/${CND_CONF}/${CND_PLATFORM}/superviseur-robot
17
+OUTPUT_BASENAME=superviseur-robot
18
+PACKAGE_TOP_DIR=superviseur-robot/
19
+
20
+# Functions
21
+function checkReturnCode
22
+{
23
+    rc=$?
24
+    if [ $rc != 0 ]
25
+    then
26
+        exit $rc
27
+    fi
28
+}
29
+function makeDirectory
30
+# $1 directory path
31
+# $2 permission (optional)
32
+{
33
+    mkdir -p "$1"
34
+    checkReturnCode
35
+    if [ "$2" != "" ]
36
+    then
37
+      chmod $2 "$1"
38
+      checkReturnCode
39
+    fi
40
+}
41
+function copyFileToTmpDir
42
+# $1 from-file path
43
+# $2 to-file path
44
+# $3 permission
45
+{
46
+    cp "$1" "$2"
47
+    checkReturnCode
48
+    if [ "$3" != "" ]
49
+    then
50
+        chmod $3 "$2"
51
+        checkReturnCode
52
+    fi
53
+}
54
+
55
+# Setup
56
+cd "${TOP}"
57
+mkdir -p ${CND_DISTDIR}/${CND_CONF}/${CND_PLATFORM}/package
58
+rm -rf ${NBTMPDIR}
59
+mkdir -p ${NBTMPDIR}
60
+
61
+# Copy files and create directories and links
62
+cd "${TOP}"
63
+makeDirectory "${NBTMPDIR}/superviseur-robot/bin"
64
+copyFileToTmpDir "${OUTPUT_PATH}" "${NBTMPDIR}/${PACKAGE_TOP_DIR}bin/${OUTPUT_BASENAME}" 0755
65
+
66
+
67
+# Generate tar file
68
+cd "${TOP}"
69
+rm -f ${CND_DISTDIR}/${CND_CONF}/${CND_PLATFORM}/package/superviseur-robot.tar
70
+cd ${NBTMPDIR}
71
+tar -vcf ../../../../${CND_DISTDIR}/${CND_CONF}/${CND_PLATFORM}/package/superviseur-robot.tar *
72
+checkReturnCode
73
+
74
+# Cleanup
75
+cd "${TOP}"
76
+rm -rf ${NBTMPDIR}

+ 179
- 0
software/raspberry/superviseur-robot/nbproject/configurations.xml View File

@@ -5,6 +5,8 @@
5 5
                    displayName="Header Files"
6 6
                    projectFiles="true">
7 7
       <itemPath>./lib/camera.h</itemPath>
8
+      <itemPath>/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.h</itemPath>
9
+      <itemPath>/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.h</itemPath>
8 10
       <itemPath>./lib/definitions.h</itemPath>
9 11
       <itemPath>./lib/image.h</itemPath>
10 12
       <itemPath>./lib/img.h</itemPath>
@@ -14,6 +16,7 @@
14 16
       <itemPath>./lib/robot.h</itemPath>
15 17
       <itemPath>./lib/server.h</itemPath>
16 18
       <itemPath>./tasks.h</itemPath>
19
+      <itemPath>tasks_pthread.h</itemPath>
17 20
     </logicalFolder>
18 21
     <logicalFolder name="ResourceFiles"
19 22
                    displayName="Resource Files"
@@ -24,6 +27,8 @@
24 27
                    displayName="Source Files"
25 28
                    projectFiles="true">
26 29
       <itemPath>./lib/camera.cpp</itemPath>
30
+      <itemPath>/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp</itemPath>
31
+      <itemPath>/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp</itemPath>
27 32
       <itemPath>./lib/image.cpp</itemPath>
28 33
       <itemPath>./lib/img.cpp</itemPath>
29 34
       <itemPath>./main.cpp</itemPath>
@@ -33,6 +38,7 @@
33 38
       <itemPath>./lib/robot.cpp</itemPath>
34 39
       <itemPath>./lib/server.cpp</itemPath>
35 40
       <itemPath>./tasks.cpp</itemPath>
41
+      <itemPath>tasks_pthread.cpp</itemPath>
36 42
     </logicalFolder>
37 43
     <logicalFolder name="TestFiles"
38 44
                    displayName="Test Files"
@@ -46,6 +52,9 @@
46 52
       <itemPath>./Makefile</itemPath>
47 53
     </logicalFolder>
48 54
   </logicalFolder>
55
+  <sourceRootList>
56
+    <Elem>/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib</Elem>
57
+  </sourceRootList>
49 58
   <projectmakefile>./Makefile</projectmakefile>
50 59
   <confs>
51 60
     <conf name="Debug" type="1">
@@ -122,6 +131,30 @@
122 131
       </item>
123 132
       <item path="./tasks.h" ex="false" tool="3" flavor2="0">
124 133
       </item>
134
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp"
135
+            ex="false"
136
+            tool="1"
137
+            flavor2="0">
138
+      </item>
139
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.h"
140
+            ex="false"
141
+            tool="3"
142
+            flavor2="0">
143
+      </item>
144
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp"
145
+            ex="false"
146
+            tool="1"
147
+            flavor2="0">
148
+      </item>
149
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.h"
150
+            ex="false"
151
+            tool="3"
152
+            flavor2="0">
153
+      </item>
154
+      <item path="tasks_pthread.cpp" ex="false" tool="1" flavor2="0">
155
+      </item>
156
+      <item path="tasks_pthread.h" ex="false" tool="3" flavor2="0">
157
+      </item>
125 158
     </conf>
126 159
     <conf name="Release" type="1">
127 160
       <toolsSet>
@@ -185,6 +218,30 @@
185 218
       </item>
186 219
       <item path="./tasks.h" ex="false" tool="3" flavor2="0">
187 220
       </item>
221
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp"
222
+            ex="false"
223
+            tool="1"
224
+            flavor2="0">
225
+      </item>
226
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.h"
227
+            ex="false"
228
+            tool="3"
229
+            flavor2="0">
230
+      </item>
231
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp"
232
+            ex="false"
233
+            tool="1"
234
+            flavor2="0">
235
+      </item>
236
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.h"
237
+            ex="false"
238
+            tool="3"
239
+            flavor2="0">
240
+      </item>
241
+      <item path="tasks_pthread.cpp" ex="false" tool="1" flavor2="0">
242
+      </item>
243
+      <item path="tasks_pthread.h" ex="false" tool="3" flavor2="0">
244
+      </item>
188 245
     </conf>
189 246
     <conf name="Debug__RPI_" type="1">
190 247
       <toolsSet>
@@ -265,6 +322,128 @@
265 322
       </item>
266 323
       <item path="./tasks.h" ex="false" tool="3" flavor2="0">
267 324
       </item>
325
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp"
326
+            ex="false"
327
+            tool="1"
328
+            flavor2="0">
329
+      </item>
330
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.h"
331
+            ex="false"
332
+            tool="3"
333
+            flavor2="0">
334
+      </item>
335
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp"
336
+            ex="false"
337
+            tool="1"
338
+            flavor2="0">
339
+      </item>
340
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.h"
341
+            ex="false"
342
+            tool="3"
343
+            flavor2="0">
344
+      </item>
345
+      <item path="tasks_pthread.cpp" ex="false" tool="1" flavor2="0">
346
+      </item>
347
+      <item path="tasks_pthread.h" ex="false" tool="3" flavor2="0">
348
+      </item>
349
+    </conf>
350
+    <conf name="Debug__Pthread_" type="1">
351
+      <toolsSet>
352
+        <compilerSet>default</compilerSet>
353
+        <dependencyChecking>true</dependencyChecking>
354
+        <rebuildPropChanged>false</rebuildPropChanged>
355
+      </toolsSet>
356
+      <compileType>
357
+        <cTool>
358
+          <incDir>
359
+            <pElem>./</pElem>
360
+            <pElem>./lib</pElem>
361
+          </incDir>
362
+          <commandLine>-I/usr/xenomai/include/mercury -I/usr/xenomai/include -D_GNU_SOURCE -D_REENTRANT -fasynchronous-unwind-tables -D__MERCURY__ -I/usr/xenomai/include/alchemy</commandLine>
363
+        </cTool>
364
+        <ccTool>
365
+          <incDir>
366
+            <pElem>./</pElem>
367
+            <pElem>./lib</pElem>
368
+          </incDir>
369
+          <commandLine>-D_GNU_SOURCE -D_REENTRANT -fasynchronous-unwind-tables</commandLine>
370
+          <preprocessorList>
371
+            <Elem>_WITH_TRACE_</Elem>
372
+            <Elem>__FOR_PC__</Elem>
373
+            <Elem>__WITH_PTHREAD__</Elem>
374
+          </preprocessorList>
375
+        </ccTool>
376
+        <linkerTool>
377
+          <linkerLibItems>
378
+            <linkerOptionItem>`pkg-config --libs opencv`</linkerOptionItem>
379
+          </linkerLibItems>
380
+          <commandLine>-lpthread -lrt</commandLine>
381
+        </linkerTool>
382
+      </compileType>
383
+      <item path="./gdbsudo.sh" ex="false" tool="3" flavor2="0">
384
+      </item>
385
+      <item path="./lib/camera.cpp" ex="false" tool="3" flavor2="0">
386
+      </item>
387
+      <item path="./lib/camera.h" ex="false" tool="3" flavor2="0">
388
+      </item>
389
+      <item path="./lib/definitions.h" ex="false" tool="3" flavor2="0">
390
+      </item>
391
+      <item path="./lib/image.cpp" ex="true" tool="1" flavor2="9">
392
+      </item>
393
+      <item path="./lib/image.h" ex="false" tool="3" flavor2="0">
394
+      </item>
395
+      <item path="./lib/img.cpp" ex="false" tool="3" flavor2="0">
396
+      </item>
397
+      <item path="./lib/img.h" ex="false" tool="3" flavor2="0">
398
+      </item>
399
+      <item path="./lib/message.cpp" ex="false" tool="1" flavor2="9">
400
+      </item>
401
+      <item path="./lib/message.h" ex="false" tool="3" flavor2="0">
402
+      </item>
403
+      <item path="./lib/messages.cpp" ex="false" tool="1" flavor2="9">
404
+      </item>
405
+      <item path="./lib/messages.h" ex="false" tool="3" flavor2="0">
406
+      </item>
407
+      <item path="./lib/monitor.cpp" ex="false" tool="1" flavor2="9">
408
+      </item>
409
+      <item path="./lib/monitor.h" ex="false" tool="3" flavor2="0">
410
+      </item>
411
+      <item path="./lib/robot.cpp" ex="false" tool="1" flavor2="9">
412
+      </item>
413
+      <item path="./lib/robot.h" ex="false" tool="3" flavor2="0">
414
+      </item>
415
+      <item path="./lib/server.cpp" ex="false" tool="1" flavor2="9">
416
+      </item>
417
+      <item path="./lib/server.h" ex="false" tool="3" flavor2="0">
418
+      </item>
419
+      <item path="./main.cpp" ex="false" tool="1" flavor2="9">
420
+      </item>
421
+      <item path="./tasks.cpp" ex="true" tool="1" flavor2="9">
422
+      </item>
423
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp"
424
+            ex="false"
425
+            tool="1"
426
+            flavor2="0">
427
+      </item>
428
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.h"
429
+            ex="false"
430
+            tool="3"
431
+            flavor2="0">
432
+      </item>
433
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp"
434
+            ex="false"
435
+            tool="1"
436
+            flavor2="0">
437
+      </item>
438
+      <item path="/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.h"
439
+            ex="false"
440
+            tool="3"
441
+            flavor2="0">
442
+      </item>
443
+      <item path="tasks_pthread.cpp" ex="false" tool="1" flavor2="9">
444
+      </item>
445
+      <item path="tasks_pthread.h" ex="false" tool="3" flavor2="0">
446
+      </item>
268 447
     </conf>
269 448
   </confs>
270 449
 </configurationDescriptor>

+ 1
- 0
software/raspberry/superviseur-robot/nbproject/private/Makefile-variables.mk View File

@@ -6,3 +6,4 @@
6 6
 # Debug configuration
7 7
 # Release configuration
8 8
 # Debug__RPI_ configuration
9
+# Debug__Pthread_ configuration

+ 37
- 0
software/raspberry/superviseur-robot/nbproject/private/configurations.xml View File

@@ -105,5 +105,42 @@
105 105
         </environment>
106 106
       </runprofile>
107 107
     </conf>
108
+    <conf name="Debug__Pthread_" type="1">
109
+      <toolsSet>
110
+        <developmentServer>localhost</developmentServer>
111
+        <platform>2</platform>
112
+      </toolsSet>
113
+      <dbx_gdbdebugger version="1">
114
+        <gdb_pathmaps>
115
+        </gdb_pathmaps>
116
+        <gdb_interceptlist>
117
+          <gdbinterceptoptions gdb_all="false" gdb_unhandled="true" gdb_unexpected="true"/>
118
+        </gdb_interceptlist>
119
+        <gdb_options>
120
+          <DebugOptions>
121
+          </DebugOptions>
122
+        </gdb_options>
123
+        <gdb_buildfirst gdb_buildfirst_overriden="false" gdb_buildfirst_old="false"/>
124
+      </dbx_gdbdebugger>
125
+      <nativedebugger version="1">
126
+        <engine>gdb</engine>
127
+      </nativedebugger>
128
+      <runprofile version="9">
129
+        <runcommandpicklist>
130
+          <runcommandpicklistitem>sudo "${OUTPUT_PATH}"</runcommandpicklistitem>
131
+          <runcommandpicklistitem>sudo -E "${OUTPUT_PATH}"</runcommandpicklistitem>
132
+          <runcommandpicklistitem>pkexec "${OUTPUT_PATH}"</runcommandpicklistitem>
133
+          <runcommandpicklistitem>"${OUTPUT_PATH}"</runcommandpicklistitem>
134
+        </runcommandpicklist>
135
+        <runcommand>"${OUTPUT_PATH}"</runcommand>
136
+        <rundir></rundir>
137
+        <buildfirst>true</buildfirst>
138
+        <console-type>1</console-type>
139
+        <terminal-type>0</terminal-type>
140
+        <remove-instrumentation>0</remove-instrumentation>
141
+        <environment>
142
+        </environment>
143
+      </runprofile>
144
+    </conf>
108 145
   </confs>
109 146
 </configurationDescriptor>

+ 7
- 1
software/raspberry/superviseur-robot/nbproject/private/private.xml View File

@@ -2,21 +2,27 @@
2 2
 <project-private xmlns="http://www.netbeans.org/ns/project-private/1">
3 3
     <data xmlns="http://www.netbeans.org/ns/make-project-private/1">
4 4
         <activeConfTypeElem>1</activeConfTypeElem>
5
-        <activeConfIndexElem>0</activeConfIndexElem>
5
+        <activeConfIndexElem>3</activeConfIndexElem>
6 6
     </data>
7 7
     <editor-bookmarks xmlns="http://www.netbeans.org/ns/editor-bookmarks/2" lastBookmarkId="0"/>
8 8
     <open-files xmlns="http://www.netbeans.org/ns/projectui-open-files/2">
9 9
         <group>
10 10
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/monitor.h</file>
11
+            <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.cpp</file>
12
+            <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/comrobot.h</file>
13
+            <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.h</file>
11 14
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/img.h</file>
12 15
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/img.cpp</file>
13 16
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/messages.h</file>
14 17
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/robot.h</file>
18
+            <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/commonitor.cpp</file>
15 19
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/camera.cpp</file>
20
+            <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/tasks_pthread.cpp</file>
16 21
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/image.h</file>
17 22
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/server.h</file>
18 23
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/camera.h</file>
19 24
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/tasks.cpp</file>
25
+            <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/tasks_pthread.h</file>
20 26
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/message.h</file>
21 27
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/main.cpp</file>
22 28
             <file>file:/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib/messages.cpp</file>

+ 7
- 1
software/raspberry/superviseur-robot/nbproject/project.xml View File

@@ -9,7 +9,9 @@
9 9
             <header-extensions>h</header-extensions>
10 10
             <sourceEncoding>UTF-8</sourceEncoding>
11 11
             <make-dep-projects/>
12
-            <sourceRootList/>
12
+            <sourceRootList>
13
+                <sourceRootElem>/home/dimercur/Documents/Travail/git/dumber/software/raspberry/superviseur-robot/lib</sourceRootElem>
14
+            </sourceRootList>
13 15
             <confList>
14 16
                 <confElem>
15 17
                     <name>Debug</name>
@@ -23,6 +25,10 @@
23 25
                     <name>Debug__RPI_</name>
24 26
                     <type>1</type>
25 27
                 </confElem>
28
+                <confElem>
29
+                    <name>Debug__Pthread_</name>
30
+                    <type>1</type>
31
+                </confElem>
26 32
             </confList>
27 33
             <formatting>
28 34
                 <project-formatting-style>false</project-formatting-style>

+ 2
- 2
software/raspberry/superviseur-robot/tasks.h View File

@@ -23,8 +23,8 @@
23 23
  * \brief     Miscellaneous functions used for destijl project.
24 24
  */
25 25
 
26
-#ifndef FUNCTIONS_H
27
-#define FUNCTIONS_H
26
+#ifndef __TASKS_H__
27
+#define __TASKS_H__
28 28
 
29 29
 #include <stdio.h>
30 30
 #include <stdlib.h>

+ 263
- 0
software/raspberry/superviseur-robot/tasks_pthread.cpp View File

@@ -0,0 +1,263 @@
1
+/*
2
+ * Copyright (C) 2018 dimercur
3
+ *
4
+ * This program is free software: you can redistribute it and/or modify
5
+ * it under the terms of the GNU General Public License as published by
6
+ * the Free Software Foundation, either version 3 of the License, or
7
+ * (at your option) any later version.
8
+ *
9
+ * This program is distributed in the hope that it will be useful,
10
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
11
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
12
+ * GNU General Public License for more details.
13
+ *
14
+ * You should have received a copy of the GNU General Public License
15
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
16
+ */
17
+
18
+/**
19
+ * \file      functions.h
20
+ * \author    PE.Hladik
21
+ * \version   1.0
22
+ * \date      06/06/2017
23
+ * \brief     Miscellaneous functions used for destijl project.
24
+ */
25
+
26
+#include "tasks_pthread.h"
27
+
28
+#ifdef __WITH_PTHREAD__
29
+char mode_start;
30
+
31
+void write_in_queue(RT_QUEUE *, MessageToMon);
32
+
33
+void f_server(void *arg) {
34
+    int err;
35
+    /* INIT */
36
+    RT_TASK_INFO info;
37
+    rt_task_inquire(NULL, &info);
38
+    printf("Init %s\n", info.name);
39
+    rt_sem_p(&sem_barrier, TM_INFINITE);
40
+
41
+    err=openServer(DEFAULT_SERVER_PORT);
42
+
43
+    if (err < 0) {
44
+        printf("Failed to start server: %s\n", strerror(-err));
45
+        exit(EXIT_FAILURE);
46
+    } else {
47
+#ifdef _WITH_TRACE_
48
+        printf("%s: server started\n", info.name);
49
+#endif
50
+        //Waiting for a client to connect
51
+        err=acceptClient();
52
+        
53
+        if (err<0) {
54
+            printf("Client accept failed: %s\n", strerror(-err));
55
+            exit(EXIT_FAILURE);
56
+        }
57
+
58
+#ifdef _WITH_TRACE_
59
+        printf ("client connected: %d\n", err);
60
+        printf ("Rock'n'roll baby !\n");
61
+#endif        
62
+        rt_sem_broadcast(&sem_serverOk);
63
+    }
64
+}
65
+
66
+void f_sendToMon(void * arg) {
67
+    int err;
68
+    MessageToMon msg;
69
+
70
+    /* INIT */
71
+    RT_TASK_INFO info;
72
+    rt_task_inquire(NULL, &info);
73
+    printf("Init %s\n", info.name);
74
+    rt_sem_p(&sem_barrier, TM_INFINITE);
75
+
76
+#ifdef _WITH_TRACE_
77
+    printf("%s : waiting for sem_serverOk\n", info.name);
78
+#endif
79
+    rt_sem_p(&sem_serverOk, TM_INFINITE);
80
+    while (1) {
81
+
82
+#ifdef _WITH_TRACE_
83
+        printf("%s : waiting for a message in queue\n", info.name);
84
+#endif
85
+        if (rt_queue_read(&q_messageToMon, &msg, sizeof (MessageToRobot), TM_INFINITE) >= 0) {
86
+#ifdef _WITH_TRACE_
87
+            printf("%s : message {%s,%s} in queue\n", info.name, msg.header, (char*)msg.data);
88
+#endif
89
+
90
+            send_message_to_monitor(msg.header, msg.data);
91
+            free_msgToMon_data(&msg);
92
+            rt_queue_free(&q_messageToMon, &msg);
93
+        } else {
94
+            printf("Error msg queue write: %s\n", strerror(-err));
95
+        }
96
+    }
97
+}
98
+
99
+void f_receiveFromMon(void *arg) {
100
+    MessageFromMon msg;
101
+    int err;
102
+
103
+    /* INIT */
104
+    RT_TASK_INFO info;
105
+    rt_task_inquire(NULL, &info);
106
+    printf("Init %s\n", info.name);
107
+    rt_sem_p(&sem_barrier, TM_INFINITE);
108
+
109
+#ifdef _WITH_TRACE_
110
+    printf("%s : waiting for sem_serverOk\n", info.name);
111
+#endif
112
+    rt_sem_p(&sem_serverOk, TM_INFINITE);
113
+    do {
114
+#ifdef _WITH_TRACE_
115
+        printf("%s : waiting for a message from monitor\n", info.name);
116
+#endif
117
+        err = receive_message_from_monitor(msg.header, msg.data);
118
+#ifdef _WITH_TRACE_
119
+        printf("%s: msg {header:%s,data=%s} received from UI\n", info.name, msg.header, msg.data);
120
+#endif
121
+        if (strcmp(msg.header, HEADER_MTS_COM_DMB) == 0) {
122
+            if (msg.data[0] == OPEN_COM_DMB) { // Open communication supervisor-robot
123
+#ifdef _WITH_TRACE_
124
+                printf("%s: message open Xbee communication\n", info.name);
125
+#endif
126
+                rt_sem_v(&sem_openComRobot);
127
+            }
128
+        } else if (strcmp(msg.header, HEADER_MTS_DMB_ORDER) == 0) {
129
+            if (msg.data[0] == DMB_START_WITHOUT_WD) { // Start robot
130
+#ifdef _WITH_TRACE_
131
+                printf("%s: message start robot\n", info.name);
132
+#endif 
133
+                rt_sem_v(&sem_startRobot);
134
+
135
+            } else if ((msg.data[0] == DMB_GO_BACK)
136
+                    || (msg.data[0] == DMB_GO_FORWARD)
137
+                    || (msg.data[0] == DMB_GO_LEFT)
138
+                    || (msg.data[0] == DMB_GO_RIGHT)
139
+                    || (msg.data[0] == DMB_STOP_MOVE)) {
140
+
141
+                rt_mutex_acquire(&mutex_move, TM_INFINITE);
142
+                robotMove = msg.data[0];
143
+                rt_mutex_release(&mutex_move);
144
+#ifdef _WITH_TRACE_
145
+                printf("%s: message update movement with %c\n", info.name, robotMove);
146
+#endif
147
+
148
+            }
149
+        }
150
+    } while (err > 0);
151
+
152
+}
153
+
154
+void f_openComRobot(void * arg) {
155
+    int err;
156
+
157
+    /* INIT */
158
+    RT_TASK_INFO info;
159
+    rt_task_inquire(NULL, &info);
160
+    printf("Init %s\n", info.name);
161
+    rt_sem_p(&sem_barrier, TM_INFINITE);
162
+
163
+    while (1) {
164
+#ifdef _WITH_TRACE_
165
+        printf("%s : Wait sem_openComRobot\n", info.name);
166
+#endif
167
+        rt_sem_p(&sem_openComRobot, TM_INFINITE);
168
+#ifdef _WITH_TRACE_
169
+        printf("%s : sem_openComRobot arrived => open communication robot\n", info.name);
170
+#endif
171
+        err = open_communication_robot();
172
+        if (err == 0) {
173
+#ifdef _WITH_TRACE_
174
+            printf("%s : the communication is opened\n", info.name);
175
+#endif
176
+            MessageToMon msg;
177
+            set_msgToMon_header(&msg, (char*)HEADER_STM_ACK);
178
+            write_in_queue(&q_messageToMon, msg);
179
+        } else {
180
+            MessageToMon msg;
181
+            set_msgToMon_header(&msg, (char*)HEADER_STM_NO_ACK);
182
+            write_in_queue(&q_messageToMon, msg);
183
+        }
184
+    }
185
+}
186
+
187
+void f_startRobot(void * arg) {
188
+    int err;
189
+
190
+    /* INIT */
191
+    RT_TASK_INFO info;
192
+    rt_task_inquire(NULL, &info);
193
+    printf("Init %s\n", info.name);
194
+    rt_sem_p(&sem_barrier, TM_INFINITE);
195
+
196
+    while (1) {
197
+#ifdef _WITH_TRACE_
198
+        printf("%s : Wait sem_startRobot\n", info.name);
199
+#endif
200
+        rt_sem_p(&sem_startRobot, TM_INFINITE);
201
+#ifdef _WITH_TRACE_
202
+        printf("%s : sem_startRobot arrived => Start robot\n", info.name);
203
+#endif
204
+        err = send_command_to_robot(DMB_START_WITHOUT_WD);
205
+        if (err == 0) {
206
+#ifdef _WITH_TRACE_
207
+            printf("%s : the robot is started\n", info.name);
208
+#endif
209
+            rt_mutex_acquire(&mutex_robotStarted, TM_INFINITE);
210
+            robotStarted = 1;
211
+            rt_mutex_release(&mutex_robotStarted);
212
+            MessageToMon msg;
213
+            set_msgToMon_header(&msg, (char*)HEADER_STM_ACK);
214
+            write_in_queue(&q_messageToMon, msg);
215
+        } else {
216
+            MessageToMon msg;
217
+            set_msgToMon_header(&msg, (char*)HEADER_STM_NO_ACK);
218
+            write_in_queue(&q_messageToMon, msg);
219
+        }
220
+    }
221
+}
222
+
223
+void f_move(void *arg) {
224
+    /* INIT */
225
+    RT_TASK_INFO info;
226
+    rt_task_inquire(NULL, &info);
227
+    printf("Init %s\n", info.name);
228
+    rt_sem_p(&sem_barrier, TM_INFINITE);
229
+
230
+    /* PERIODIC START */
231
+#ifdef _WITH_PERIODIC_TRACE_
232
+    printf("%s: start period\n", info.name);
233
+#endif
234
+    rt_task_set_periodic(NULL, TM_NOW, 100000000);
235
+    while (1) {
236
+#ifdef _WITH_PERIODIC_TRACE_
237
+        printf("%s: Wait period \n", info.name);
238
+#endif
239
+        rt_task_wait_period(NULL);
240
+#ifdef _WITH_PERIODIC_TRACE_
241
+        printf("%s: Periodic activation\n", info.name);
242
+        printf("%s: move equals %c\n", info.name, robotMove);
243
+#endif
244
+        rt_mutex_acquire(&mutex_robotStarted, TM_INFINITE);
245
+        if (robotStarted) {
246
+            rt_mutex_acquire(&mutex_move, TM_INFINITE);
247
+            send_command_to_robot(robotMove);
248
+            rt_mutex_release(&mutex_move);
249
+#ifdef _WITH_TRACE_
250
+            printf("%s: the movement %c was sent\n", info.name, robotMove);
251
+#endif            
252
+        }
253
+        rt_mutex_release(&mutex_robotStarted);
254
+    }
255
+}
256
+
257
+void write_in_queue(RT_QUEUE *queue, MessageToMon msg) {
258
+    void *buff;
259
+    buff = rt_queue_alloc(&q_messageToMon, sizeof (MessageToMon));
260
+    memcpy(buff, &msg, sizeof (MessageToMon));
261
+    rt_queue_send(&q_messageToMon, buff, sizeof (MessageToMon), Q_NORMAL);
262
+}
263
+#endif //__WITH_PTHREAD__

+ 104
- 0
software/raspberry/superviseur-robot/tasks_pthread.h View File

@@ -0,0 +1,104 @@
1
+/*
2
+ * Copyright (C) 2018 dimercur
3
+ *
4
+ * This program is free software: you can redistribute it and/or modify
5
+ * it under the terms of the GNU General Public License as published by
6
+ * the Free Software Foundation, either version 3 of the License, or
7
+ * (at your option) any later version.
8
+ *
9
+ * This program is distributed in the hope that it will be useful,
10
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
11
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
12
+ * GNU General Public License for more details.
13
+ *
14
+ * You should have received a copy of the GNU General Public License
15
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
16
+ */
17
+
18
+/**
19
+ * \file      functions.h
20
+ * \author    PE.Hladik
21
+ * \version   1.0
22
+ * \date      06/06/2017
23
+ * \brief     Miscellaneous functions used for destijl project.
24
+ */
25
+
26
+#ifndef __TASKS_H__
27
+#define __TASKS_H__
28
+
29
+#ifdef __WITH_PTHREAD__
30
+#include <stdio.h>
31
+#include <stdlib.h>
32
+#include <unistd.h>
33
+
34
+#include <sys/mman.h>
35
+
36
+#include "monitor.h"
37
+#include "robot.h"
38
+#include "image.h"
39
+#include "message.h"
40
+#include "server.h"
41
+
42
+extern RT_TASK th_server;
43
+extern RT_TASK th_sendToMon;
44
+extern RT_TASK th_receiveFromMon;
45
+extern RT_TASK th_openComRobot;
46
+extern RT_TASK th_startRobot;
47
+extern RT_TASK th_move;
48
+
49
+extern RT_MUTEX mutex_robotStarted;
50
+extern RT_MUTEX mutex_move;
51
+
52
+extern RT_SEM sem_barrier;
53
+extern RT_SEM sem_openComRobot;
54
+extern RT_SEM sem_serverOk;
55
+extern RT_SEM sem_startRobot;
56
+
57
+extern RT_QUEUE q_messageToMon;
58
+
59
+extern int etatCommMoniteur;
60
+extern int robotStarted;
61
+extern char robotMove;
62
+
63
+extern int MSG_QUEUE_SIZE;
64
+
65
+extern int PRIORITY_TSERVER;
66
+extern int PRIORITY_TOPENCOMROBOT;
67
+extern int PRIORITY_TMOVE;
68
+extern int PRIORITY_TSENDTOMON;
69
+extern int PRIORITY_TRECEIVEFROMMON;
70
+extern int PRIORITY_TSTARTROBOT;
71
+
72
+/**
73
+ * \brief       Thread handling server communication.
74
+ */ 
75
+void f_server(void *arg);
76
+
77
+/**
78
+ * \brief       Thread handling communication to monitor.
79
+ */ 
80
+void f_sendToMon(void *arg);
81
+
82
+/**
83
+ * \brief       Thread handling communication from monitor.
84
+ */ 
85
+void f_receiveFromMon(void *arg);
86
+
87
+/**
88
+ * \brief       Thread handling opening of robot communication.
89
+ */ 
90
+void f_openComRobot(void * arg);
91
+
92
+/**
93
+ * \brief       Thread handling robot mouvements.
94
+ */ 
95
+void f_move(void *arg);
96
+
97
+/**
98
+ * \brief       Thread handling robot activation.
99
+ */ 
100
+void f_startRobot(void *arg);
101
+
102
+#endif // __WITH_PTHREAD__
103
+#endif /* __TASKS_H__ */
104
+

Loading…
Cancel
Save