amiro-os / components / Lidar.cpp @ 6acaea07
History | View | Annotate | Download (9.723 KB)
1 |
#include <amiro/Lidar.h> |
---|---|
2 |
|
3 |
#include <global.hpp> |
4 |
|
5 |
using namespace chibios_rt; |
6 |
using namespace amiro; |
7 |
|
8 |
extern Global global;
|
9 |
|
10 |
uint8_t Lidar::scannedData[NUMBER_OF_CHARACTERS + 1] = {};
|
11 |
|
12 |
Lidar::Lidar(const uint8_t boardId, Lidar::SETUP setup)
|
13 |
: BaseStaticThread<256>(),
|
14 |
boardId(boardId), |
15 |
setup(setup) { |
16 |
|
17 |
} |
18 |
|
19 |
Lidar:: |
20 |
~Lidar() { |
21 |
|
22 |
// Power down the LIDAR
|
23 |
// TODO Is it correct anyway
|
24 |
switch (boardId) {
|
25 |
case(CAN::LIGHT_RING_ID):
|
26 |
palWritePad(GPIOB, GPIOB_LASER_EN, PAL_LOW); |
27 |
break;
|
28 |
default:
|
29 |
break;
|
30 |
} |
31 |
this->isReady = false; |
32 |
}; |
33 |
|
34 |
void Lidar::flushSD2InputQueue() {
|
35 |
chSysLock(); |
36 |
chIQResetI(&SD2.iqueue); |
37 |
chSysUnlock(); |
38 |
} |
39 |
|
40 |
msg_t Lidar::main(void) {
|
41 |
|
42 |
|
43 |
switch (this->boardId) { |
44 |
case(CAN::LIGHT_RING_ID): {
|
45 |
|
46 |
// Power up the LIDAR
|
47 |
palWritePad(GPIOB, GPIOB_LASER_EN, PAL_HIGH); |
48 |
BaseThread::sleep(MS2ST(5000));
|
49 |
|
50 |
// Setup the driver and lidar, if we want to communicate with it
|
51 |
if (setup != SETUP::POWER_ONLY) {
|
52 |
// Flush the queue because there is a "0" in it
|
53 |
flushSD2InputQueue(); |
54 |
|
55 |
// Configure LIDAR serial interface speed
|
56 |
// chprintf((BaseSequentialStream*) &global.sercanmux1, "Speed switch to " STR(SD_SPEED) "\n");
|
57 |
chprintf((BaseSequentialStream*) &SD2, "SS" STR(SD_SPEED_PREFIX) STR(SD_SPEED) LF);
|
58 |
|
59 |
// Check if the switch went well, otherwise terminate the thread
|
60 |
if (checkDataString("SS" STR(SD_SPEED_PREFIX) STR(SD_SPEED) "\n00P\n\n")) { |
61 |
chprintf((BaseSequentialStream*) &global.sercanmux1, "Lidar speed switch OK\n");
|
62 |
// Configure serial interface of STM32
|
63 |
sdStop(&SD2); |
64 |
SerialConfig sdLidarconf = { SD_SPEED, 0, 0, 0 }; |
65 |
sdStart(&SD2, &sdLidarconf); |
66 |
} else {
|
67 |
chprintf((BaseSequentialStream*) &global.sercanmux1, "Lidar speed switch NOT OK: Terminating Lidar \n");
|
68 |
palWritePad(GPIOB, GPIOB_LASER_EN, PAL_LOW); |
69 |
return -1; |
70 |
} |
71 |
} |
72 |
break;
|
73 |
} |
74 |
default:
|
75 |
break;
|
76 |
} |
77 |
|
78 |
evtInit(&this->evtimer, UPDATE_LIDAR_PERIOD_MSEC);
|
79 |
|
80 |
EvtSource *eventTimerEvtSource = reinterpret_cast<EvtSource *>(&this->evtimer.et_es); |
81 |
|
82 |
EvtListener eventTimerEvtListener; |
83 |
|
84 |
// TODO Does PERIODIC_TIMER_ID has something to do with ControllerAreNetwork.h ?
|
85 |
eventTimerEvtSource->registerOne(&eventTimerEvtListener, CAN::PERIODIC_TIMER_ID); |
86 |
|
87 |
evtStart(&this->evtimer);
|
88 |
|
89 |
this->setName("Lidar"); |
90 |
|
91 |
while (!this->shouldTerminate()) { |
92 |
|
93 |
eventmask_t eventMask = this->waitOneEvent(ALL_EVENTS);
|
94 |
switch (eventMask) {
|
95 |
case EVENT_MASK(CAN::PERIODIC_TIMER_ID):
|
96 |
// printDetails();
|
97 |
if (setup != SETUP::POWER_ONLY) {
|
98 |
updateSensorVal(); |
99 |
} |
100 |
break;
|
101 |
} |
102 |
} |
103 |
|
104 |
evtStop(&this->evtimer);
|
105 |
eventTimerEvtSource->unregister(&eventTimerEvtListener); |
106 |
|
107 |
return RDY_OK;
|
108 |
} |
109 |
|
110 |
bool_t Lidar::getScan(uint16_t (&scannedData)[NUMBER_OF_STEPS]) { |
111 |
if (this->isReady && !this->isFail) { |
112 |
chSysLock(); |
113 |
memcpy(&scannedData, &(Lidar::scannedData[0]), NUMBER_OF_CHARACTERS);
|
114 |
this->isReady = false; |
115 |
chSysUnlock(); |
116 |
return true; |
117 |
} else {
|
118 |
return false; |
119 |
} |
120 |
} |
121 |
|
122 |
uint16_t Lidar::getNumberOfValues() { |
123 |
return NUMBER_OF_STEPS;
|
124 |
} |
125 |
|
126 |
uint16_t Lidar::twoCharacterEncoding(uint8_t &char1, uint8_t &char2) { |
127 |
return uint16_t((((char1 - 0x30) & 0b00111111) << 6) | ((char2 - 0x30) & 0b00111111)); |
128 |
} |
129 |
|
130 |
bool_t Lidar::getData(uint8_t &data, uint32_t timeoutMs) { |
131 |
|
132 |
// data = sdGet(&SD2);
|
133 |
msg_t dataTmp = chIQGetTimeout(&SD2.iqueue, MS2ST(timeoutMs)); |
134 |
if (dataTmp == Q_TIMEOUT || dataTmp == Q_RESET) {
|
135 |
return false; |
136 |
} else {
|
137 |
data = uint8_t(dataTmp); |
138 |
++this->dataCounter;
|
139 |
return true; |
140 |
} |
141 |
} |
142 |
|
143 |
msg_t Lidar::updateSensorVal() { |
144 |
|
145 |
chSysLock(); |
146 |
// Set this flag so that the everyone knows, that scannedData will be filed right now
|
147 |
this->isReady = false; |
148 |
// Reset the FAIL flag
|
149 |
this->isFail = false; |
150 |
chSysUnlock(); |
151 |
|
152 |
while (!this->isReady) { |
153 |
switch(step) {
|
154 |
case SEND_SCAN_CMD:
|
155 |
flushSD2InputQueue(); |
156 |
// Read (725-(44-1))=682 values with two-character encoding what makes 1364 datapoints
|
157 |
// 1456 in total:
|
158 |
// 16 (Cmd-Echo) + ? (Remaining Scans) + 1 (LF) + ? (String Characters) + 1 (LF) + 2 (Status) + 1 (Sum) + 1 (LF) + ? (Timestamp) + 1 (LF) + 1364 (Data for a certain setup) + 1 (Sum) + 1 (LF) + 1 (LF)
|
159 |
chprintf((BaseSequentialStream*) &SD2,DATA_ACQ_CODE STR(STARTING_STEP_PREFIX) STR(STARTING_STEP) STR(END_STEP_PREFIX) STR(END_STEP) STR(CLUSTER_COUNT) STR(SCAN_INTERVALL) STR(NUMBER_OF_INTERVALL) LF); |
160 |
step = DATA_VALID_CHECK; |
161 |
this->dataCounter = 0; |
162 |
break;
|
163 |
case DATA_VALID_CHECK:
|
164 |
if(getData(this->newInput, 200)) { |
165 |
// TODO check for last data, if scan has a few errors
|
166 |
// HACK The timeout fix this issue at least, because after a while there
|
167 |
// wont be any transmitts
|
168 |
if (this->newInput == validScanTag[this->checkStatusIdx]) { |
169 |
if (++this->checkStatusIdx == 5) { |
170 |
// scan_data is without error: Found the sting "\n99b\n"
|
171 |
step = DATA_START_CHECK; |
172 |
this->checkStatusIdx = 0; |
173 |
} |
174 |
} else {
|
175 |
this->checkStatusIdx = 0; |
176 |
} |
177 |
} else {
|
178 |
step = FAIL; |
179 |
} |
180 |
break;
|
181 |
case DATA_START_CHECK:
|
182 |
// Check for the next linefeed to start the record
|
183 |
if(getData(this->newInput, 200)) { |
184 |
if (this->newInput == 10) { |
185 |
step = DATA_RECORD; |
186 |
this->dataIdx = 0; |
187 |
} |
188 |
} else {
|
189 |
step = FAIL; |
190 |
} |
191 |
break;
|
192 |
case DATA_RECORD:
|
193 |
if(getData(this->newInput, 200)) { |
194 |
if (this->lastInput == 10 && this->newInput == 10) { |
195 |
// end of data
|
196 |
this->lastInput = 0x0; // Just to delete this->lastInput value |
197 |
step = DATA_DECODE; |
198 |
} else if (this->newInput != 10) { |
199 |
Lidar::scannedData[this->dataIdx++] = this->newInput; |
200 |
this->lastInput = this->newInput; |
201 |
} else { // this->lastInput != 10 && this->newInput == 10 |
202 |
// This is the case, where we know that the last character was the checksum.
|
203 |
// Therefore, we need to decrement the counter
|
204 |
--this->dataIdx;
|
205 |
this->lastInput = this->newInput; |
206 |
} |
207 |
//chprintf((BaseSequentialStream*) &global.sercanmux1, "%d ", this->newInput);
|
208 |
} else {
|
209 |
step = FAIL; |
210 |
} |
211 |
break;
|
212 |
case DATA_DECODE:
|
213 |
// Decode the recorded data
|
214 |
for (uint16_t idx=0; idx < NUMBER_OF_CHARACTERS; idx += 2) { |
215 |
//TODO Check if +1 is right
|
216 |
*((uint16_t*) &(Lidar::scannedData[idx])) = twoCharacterEncoding(Lidar::scannedData[idx],Lidar::scannedData[idx+1]);
|
217 |
} |
218 |
// To print out the data in this thread, choose "step = DATA_SHOW"
|
219 |
step = FINISH; |
220 |
break;
|
221 |
case DATA_SHOW:
|
222 |
// Show the decoded data
|
223 |
chprintf((BaseSequentialStream*) &global.sercanmux1, "\n%d", this->dataCounter); |
224 |
for (uint32_t idx=0; idx < this->dataIdx; idx+=2) { |
225 |
chprintf((BaseSequentialStream*) &global.sercanmux1, "\n%d", *((uint16_t*) &(Lidar::scannedData[idx])));
|
226 |
} |
227 |
step = FINISH; |
228 |
break;
|
229 |
case FAIL:
|
230 |
// Set the FAIL flag
|
231 |
chSysLock(); |
232 |
// Set this flag so that the everyone knows, that scannedData holds wrong information
|
233 |
this->isFail = true; |
234 |
chSysUnlock(); |
235 |
break;
|
236 |
case FINISH:
|
237 |
// Clean up
|
238 |
this->step = SEND_SCAN_CMD;
|
239 |
chSysLock(); |
240 |
// Set this flag so that the everyone knows, that scannedData holds the actual data
|
241 |
this->isReady = true; |
242 |
chSysUnlock(); |
243 |
break;
|
244 |
default:
|
245 |
break;
|
246 |
} |
247 |
} |
248 |
|
249 |
return RDY_OK;
|
250 |
} |
251 |
|
252 |
void Lidar::printData() {
|
253 |
uint8_t lastInput = 0xFF, newInput = 0xFF; |
254 |
while (true) { |
255 |
if(getData(newInput, 200)) { |
256 |
if (lastInput == 10 && newInput == 10) { |
257 |
return;
|
258 |
} else {
|
259 |
chprintf((BaseSequentialStream*) &global.sercanmux1, "%c", newInput);
|
260 |
} |
261 |
lastInput = newInput; |
262 |
} else {
|
263 |
chprintf((BaseSequentialStream*) &global.sercanmux1, "TIMEOUT\n", newInput);
|
264 |
return;
|
265 |
} |
266 |
} |
267 |
} |
268 |
|
269 |
bool_t Lidar::checkDataString(const char compareString[]) { |
270 |
uint8_t lastInput = 0xFF, newInput = 0xFF, recIdx = 0; |
271 |
bool_t dataOk = true, processFlag = true; |
272 |
while (processFlag) {
|
273 |
if (getData(newInput, 200)) { |
274 |
// End of data received, quit processing
|
275 |
if (lastInput == 10 && newInput == 10) { |
276 |
processFlag = false;
|
277 |
} |
278 |
// Compare data if the characters before have been ok
|
279 |
// Otherwise do not compare anymore, because of possible
|
280 |
// segmentation fault
|
281 |
if (dataOk) {
|
282 |
if (newInput != compareString[recIdx++]) {
|
283 |
dataOk = false;
|
284 |
} |
285 |
} |
286 |
// Save the received character
|
287 |
lastInput = newInput; |
288 |
} else {
|
289 |
processFlag = false;
|
290 |
dataOk = false;
|
291 |
} |
292 |
} |
293 |
return dataOk;
|
294 |
} |
295 |
|
296 |
void Lidar::printDetails() {
|
297 |
|
298 |
chprintf((BaseSequentialStream*) &global.sercanmux1, "Print sensor details:\n");
|
299 |
|
300 |
// Tell the sensor to transmit its details
|
301 |
chprintf((BaseSequentialStream*) &SD2, "VV\n");
|
302 |
|
303 |
// Print the transmitted data
|
304 |
printData(); |
305 |
} |
306 |
|
307 |
void Lidar::printSpecification() {
|
308 |
|
309 |
chprintf((BaseSequentialStream*) &global.sercanmux1, "Print sensor specification:\n");
|
310 |
|
311 |
// Tell the sensor to transmit its specifications
|
312 |
chprintf((BaseSequentialStream*) &SD2, "PP\n");
|
313 |
|
314 |
// Print the transmitted data
|
315 |
printData(); |
316 |
} |
317 |
|
318 |
void Lidar::printInformation() {
|
319 |
chprintf((BaseSequentialStream*) &global.sercanmux1, "Print sensor information:\n");
|
320 |
|
321 |
// Tell the sensor to transmit its information
|
322 |
chprintf((BaseSequentialStream*) &SD2, "II\n");
|
323 |
|
324 |
// Print the transmitted data
|
325 |
printData(); |
326 |
} |
327 |
|
328 |
bool_t Lidar::getIsReady() { |
329 |
return this->isReady; |
330 |
} |