unittest_scanner.cpp
Go to the documentation of this file.
1 // Copyright (c) 2019-2020 Pilz GmbH & Co. KG
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU Lesser General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU Lesser General Public License for more details.
12 //
13 // You should have received a copy of the GNU Lesser General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 
16 #include <ros/ros.h>
17 #include <gtest/gtest.h>
18 
20 #include "psen_scan/scanner.h"
21 #include "psen_scan/laserscan.h"
22 #include "psen_scan/scanner_data.h"
28 
29 using namespace psen_scan;
30 using ::testing::_;
31 using ::testing::Assign;
32 using ::testing::AtLeast;
33 using ::testing::AtMost;
34 using ::testing::DoAll;
35 using ::testing::Return;
36 using ::testing::SetArgPointee;
37 using ::testing::SetArgReferee;
38 using ::testing::Throw;
39 
40 #define READ_FRAME(x) WillOnce(DoAll(fillArg0(expected_monitoring_frames_.at(x)), Return(sizeof(MonitoringFrame))))
41 #define RETURN_IP(ip_str) Return(udp::endpoint(boost::asio::ip::address_v4::from_string(ip_str), 2000))
42 
43 namespace psen_scan_test
44 {
45 class ScannerTest : public ::testing::Test
46 {
47 protected:
48  void SetUp() override
49  {
50  udp_interface_ptr = std::unique_ptr<MockPSENscanUDPInterface>(new MockPSENscanUDPInterface());
51 
52  MonitoringFrame expected_monitoring_frame = {};
53 
54  // Frame 0
55  expected_monitoring_frame.opcode_ = MONITORING_FRAME_OPCODE;
56  expected_monitoring_frame.scanner_id_ = (uint8_t)0;
57  expected_monitoring_frame.resolution_ = (uint8_t)1;
58  expected_monitoring_frame.scan_counter_ = (uint32_t)4294967295U;
59  expected_monitoring_frame.number_of_samples_ = (uint16_t)500;
60  expected_monitoring_frame.from_theta_ = (uint16_t)0;
61  expected_monitoring_frames_.push_back(expected_monitoring_frame);
62 
63  // Frame 1
64  expected_monitoring_frame.from_theta_ = 500;
65  expected_monitoring_frames_.push_back(expected_monitoring_frame);
66 
67  // Frame 2
68  expected_monitoring_frame.from_theta_ = 1000;
69  expected_monitoring_frames_.push_back(expected_monitoring_frame);
70 
71  // Frame 3
72  expected_monitoring_frame.from_theta_ = 1500;
73  expected_monitoring_frames_.push_back(expected_monitoring_frame);
74 
75  // Frame 4
76  expected_monitoring_frame.from_theta_ = 2000;
77  expected_monitoring_frames_.push_back(expected_monitoring_frame);
78 
79  // Frame 5
80  expected_monitoring_frame.from_theta_ = 2500;
81  expected_monitoring_frame.number_of_samples_ = 250;
82  expected_monitoring_frame.scan_counter_ = 0U;
83  expected_monitoring_frames_.push_back(expected_monitoring_frame);
84 
85  // ---------------------------------------------------- //
86  // From this point only frames with errors are declared //
87  // ---------------------------------------------------- //
88 
89  // Frame 6
90  expected_monitoring_frame.opcode_ = 0U; // this is the bug it is != MONITORING_FRAME_OPCODE
91  expected_monitoring_frame.from_theta_ = 0;
92  expected_monitoring_frame.number_of_samples_ = 500;
93  expected_monitoring_frame.scan_counter_ = 0;
94  expected_monitoring_frames_.push_back(expected_monitoring_frame);
95 
96  // Frame 7
97  expected_monitoring_frame.opcode_ = 123U; // this is the bug it is != MONITORING_FRAME_OPCODE
98  expected_monitoring_frames_.push_back(expected_monitoring_frame);
99 
100  // Frame 8
101  expected_monitoring_frame.opcode_ = MONITORING_FRAME_OPCODE;
102  expected_monitoring_frame.scanner_id_ = 0;
103  expected_monitoring_frame.number_of_samples_ = 550; // No bug but its a limit / border
104  expected_monitoring_frames_.push_back(expected_monitoring_frame);
105 
106  // Frame 9
107  expected_monitoring_frame.number_of_samples_ = 551; // Above the limit by one
108  expected_monitoring_frames_.push_back(expected_monitoring_frame);
109 
110  // Frame 10
111  expected_monitoring_frame.number_of_samples_ = 500;
112  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.ossd1_short_circuit_ = 1;
113  expected_monitoring_frames_.push_back(expected_monitoring_frame);
114 
115  // Frame 11
116  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.ossd1_short_circuit_ = 0;
117  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.short_circuit_at_least_two_ossd_ = 1;
118  expected_monitoring_frames_.push_back(expected_monitoring_frame);
119 
120  // Frame 12
121  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.short_circuit_at_least_two_ossd_ = 0;
122  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.integrity_check_problem_on_any_ossd_ = 1;
123  expected_monitoring_frames_.push_back(expected_monitoring_frame);
124 
125  // Frame 13
126  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.integrity_check_problem_on_any_ossd_ = 0;
127  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.internal_error_1_ = 1;
128  expected_monitoring_frames_.push_back(expected_monitoring_frame);
129 
130  // Frame 14
131  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.internal_error_1_ = 0;
132  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.window_cleaning_alarm_ = 1;
133  expected_monitoring_frames_.push_back(expected_monitoring_frame);
134 
135  // Frame 15
136  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.window_cleaning_alarm_ = 0;
137  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.power_supply_problem_ = 1;
138  expected_monitoring_frames_.push_back(expected_monitoring_frame);
139 
140  // Frame 16
141  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.power_supply_problem_ = 0;
142  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.network_problem_ = 1;
143  expected_monitoring_frames_.push_back(expected_monitoring_frame);
144 
145  // Frame 17
146  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.network_problem_ = 0;
147  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.dust_circuit_failure_ = 1;
148  expected_monitoring_frames_.push_back(expected_monitoring_frame);
149 
150  // Frame 18
151  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.dust_circuit_failure_ = 0;
152  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.measure_problem_ = 1;
153  expected_monitoring_frames_.push_back(expected_monitoring_frame);
154 
155  // Frame 19
156  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.measure_problem_ = 0;
157  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.incoherence_data_ = 1;
158  expected_monitoring_frames_.push_back(expected_monitoring_frame);
159 
160  // Frame 20
161  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.incoherence_data_ = 0;
162  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.zone_invalid_input_transition_or_integrity_ = 1;
163  expected_monitoring_frames_.push_back(expected_monitoring_frame);
164 
165  // Frame 21
166  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.zone_invalid_input_transition_or_integrity_ = 0;
167  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.zone_invalid_input_configuration_connection_ = 1;
168  expected_monitoring_frames_.push_back(expected_monitoring_frame);
169 
170  // Frame 22
171  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.zone_invalid_input_configuration_connection_ = 0;
172  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.window_cleaning_warning_ = 1;
173  expected_monitoring_frames_.push_back(expected_monitoring_frame);
174 
175  // Frame 23
176  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.window_cleaning_warning_ = 0;
177  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.internal_communication_problem_ = 1;
178  expected_monitoring_frames_.push_back(expected_monitoring_frame);
179 
180  // Frame 24
181  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.internal_communication_problem_ = 0;
182  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.generic_error_ = 1;
183  expected_monitoring_frames_.push_back(expected_monitoring_frame);
184 
185  // Frame 25
186  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.generic_error_ = 0;
187  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.display_communication_problem_ = 1;
188  expected_monitoring_frames_.push_back(expected_monitoring_frame);
189 
190  // Frame 26
191  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.display_communication_problem_ = 0;
192  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.temperature_measurement_problem_ = 1;
193  expected_monitoring_frames_.push_back(expected_monitoring_frame);
194 
195  // Frame 27
196  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.temperature_measurement_problem_ = 0;
197  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.configuration_error_ = 1;
198  expected_monitoring_frames_.push_back(expected_monitoring_frame);
199 
200  // Frame 28
201  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.configuration_error_ = 0;
202  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.out_of_range_error_ = 1;
203  expected_monitoring_frames_.push_back(expected_monitoring_frame);
204 
205  // Frame 29
206  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.out_of_range_error_ = 0;
207  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.temperature_range_error_ = 1;
208  expected_monitoring_frames_.push_back(expected_monitoring_frame);
209 
210  // Frame 30
211  expected_monitoring_frame.diagnostic_area_.diagnostic_information_.temperature_range_error_ = 0;
212  expected_monitoring_frames_.push_back(expected_monitoring_frame);
213 
214  // Frame 31
215  expected_monitoring_frame.from_theta_ = 500;
216  expected_monitoring_frame.resolution_ = 2; // resolution changed
217  expected_monitoring_frames_.push_back(expected_monitoring_frame);
218 
219  // Frame 32
220  expected_monitoring_frame.from_theta_ = 0;
221  expected_monitoring_frame.resolution_ = 1;
222  expected_monitoring_frame.scanner_id_ = 1; // scanner_id not equal 0
223  expected_monitoring_frames_.push_back(expected_monitoring_frame);
224 
225  // Frame 33
226  expected_monitoring_frame.scan_counter_ = 0;
227  expected_monitoring_frame.scanner_id_ = 0;
228  expected_monitoring_frames_.push_back(expected_monitoring_frame);
229 
230  // Frame 34
231  expected_monitoring_frame.from_theta_ = 500;
232  expected_monitoring_frame.scan_counter_ = 1; // scan counter changed
233  expected_monitoring_frames_.push_back(expected_monitoring_frame);
234  }
235 
236  std::unique_ptr<MockPSENscanUDPInterface> udp_interface_ptr;
237  std::vector<MonitoringFrame> expected_monitoring_frames_;
238 };
239 
240 ACTION_P(fillArg0, monitoring_frame)
241 {
242  ::testing::StaticAssertTypeEq<MonitoringFrame, monitoring_frame_type>();
243  boost::asio::buffer_copy(arg0, boost::asio::buffer(&monitoring_frame, sizeof(MonitoringFrame)));
244 }
245 
246 TEST_F(ScannerTest, getCompleteScan_ideal)
247 {
248  EXPECT_CALL(*udp_interface_ptr, read(_, _))
249  .Times(AtMost(6))
250  .READ_FRAME(0)
251  .READ_FRAME(1)
252  .READ_FRAME(2)
253  .READ_FRAME(3)
254  .READ_FRAME(4)
255  .READ_FRAME(5);
256 
257  Scanner scanner("1.2.3.4",
258  0x01020305,
259  1234,
260  "p4sswort",
262  PSENscanInternalAngle(2750),
263  std::move(udp_interface_ptr));
264 
265  LaserScan scan = scanner.getCompleteScan();
266 
267  EXPECT_EQ(scan.min_scan_angle_, PSENscanInternalAngle(0));
268  EXPECT_EQ(scan.max_scan_angle_, PSENscanInternalAngle(2750));
269  EXPECT_EQ(scan.resolution_, PSENscanInternalAngle(1));
270  std::vector<uint16_t> expected_measures(2750, 0);
271  EXPECT_EQ(scan.measures_, expected_measures);
272 }
273 
274 TEST_F(ScannerTest, getCompleteScan_missing_frame_middle)
275 {
276  EXPECT_CALL(*udp_interface_ptr, read(_, _)).Times(AtMost(2)).READ_FRAME(0).READ_FRAME(2);
277 
278  Scanner scanner("1.2.3.4",
279  0x01020305,
280  1234,
281  "p4sswort",
283  PSENscanInternalAngle(2750),
284  std::move(udp_interface_ptr));
285 
286  ASSERT_THROW(scanner.getCompleteScan(), CoherentMonitoringFramesException);
287 }
288 
289 TEST_F(ScannerTest, getCompleteScan_missing_frame_first)
290 {
291  EXPECT_CALL(*udp_interface_ptr, read(_, _)).Times(AtMost(1)).READ_FRAME(1);
292 
293  Scanner scanner("1.2.3.4",
294  0x01020305,
295  1234,
296  "p4sswort",
298  PSENscanInternalAngle(2750),
299  std::move(udp_interface_ptr));
300 
301  ASSERT_THROW(scanner.getCompleteScan(), CoherentMonitoringFramesException);
302 }
303 
304 TEST_F(ScannerTest, getCompleteScan_missing_frame_last)
305 {
306  EXPECT_CALL(*udp_interface_ptr, read(_, _))
307  .Times(AtMost(6))
308  .READ_FRAME(0)
309  .READ_FRAME(1)
310  .READ_FRAME(2)
311  .READ_FRAME(3)
312  .READ_FRAME(4)
313  .READ_FRAME(0);
314 
315  Scanner scanner("1.2.3.4",
316  0x01020305,
317  1234,
318  "p4sswort",
320  PSENscanInternalAngle(2750),
321  std::move(udp_interface_ptr));
322 
323  ASSERT_THROW(scanner.getCompleteScan(), CoherentMonitoringFramesException);
324 }
325 
326 TEST_F(ScannerTest, getCompleteScan_correct_return_value)
327 {
328  EXPECT_CALL(*udp_interface_ptr, read(_, _))
329  .Times(AtMost(6))
330  .READ_FRAME(0)
331  .READ_FRAME(1)
332  .READ_FRAME(2)
333  .READ_FRAME(3)
334  .READ_FRAME(4)
335  .READ_FRAME(5);
336 
337  Scanner scanner("1.2.3.4",
338  0x01020305,
339  1234,
340  "p4sswort",
343  std::move(udp_interface_ptr));
344 
345  LaserScan scan = scanner.getCompleteScan();
346 
347  EXPECT_EQ(scan.min_scan_angle_, PSENscanInternalAngle(90));
348  EXPECT_EQ(scan.max_scan_angle_, PSENscanInternalAngle(300));
349  EXPECT_EQ(scan.resolution_, PSENscanInternalAngle(1));
350  std::vector<uint16_t> expected_measures(210, 0);
351  EXPECT_EQ(scan.measures_, expected_measures);
352 }
353 
354 TEST_F(ScannerTest, ConstructorWrongArguments)
355 {
356  EXPECT_THROW(Scanner scanner("1.2.3.450", // This throws exception
357  0x01020305,
358  1234,
359  "p4sswort",
361  PSENscanInternalAngle(2750),
362  std::move(udp_interface_ptr)),
364  EXPECT_THROW(Scanner scanner("1.2.3.4",
365  0x01020305,
366  65536, // This throws exception
367  "p4sswort",
369  PSENscanInternalAngle(2750),
370  std::move(udp_interface_ptr)),
372  EXPECT_THROW(Scanner scanner("1.2.3.4",
373  0x01020305,
374  1023, // Print Warning
375  "p4sswort",
377  PSENscanInternalAngle(2750),
378  nullptr // This throws exception
379  ),
381  EXPECT_THROW(Scanner scanner("1.2.3.4",
382  0x01020305,
383  1023, // Print Warning
384  "p4sswort",
386  PSENscanInternalAngle(1), // This throws exception
387  std::move(udp_interface_ptr)),
389  EXPECT_THROW(Scanner scanner("1.2.3.4",
390  0x01020305,
391  1023, // Print Warning
392  "p4sswort",
394  MAX_SCAN_ANGLE + PSENscanInternalAngle(1), // This throws exception
395  std::move(udp_interface_ptr)),
397 }
398 
399 TEST_F(ScannerTest, StartStop)
400 {
401  EXPECT_CALL(*udp_interface_ptr, write(_)).Times(2);
402 
403  Scanner scanner("1.2.3.4",
404  0x01020305,
405  1234,
406  "p4sswort",
408  PSENscanInternalAngle(2750),
409  std::move(udp_interface_ptr));
410 
411  scanner.start();
412  scanner.stop();
413 }
414 
415 TEST_F(ScannerTest, testParseMonitoringFrameException)
416 {
417  EXPECT_CALL(*udp_interface_ptr, read(_, _))
418  .Times(5)
419  .READ_FRAME(6)
420  .READ_FRAME(7)
421  .READ_FRAME(32)
422  .READ_FRAME(8)
423  .READ_FRAME(9);
424 
425  Scanner scanner("1.2.3.4",
426  0x01020305,
427  1234,
428  "p4sswort",
430  PSENscanInternalAngle(2750),
431  std::move(udp_interface_ptr));
432 
433  EXPECT_THROW(scanner.getCompleteScan(), ParseMonitoringFrameException);
434  EXPECT_THROW(scanner.getCompleteScan(), ParseMonitoringFrameException);
435  EXPECT_THROW(scanner.getCompleteScan(), ParseMonitoringFrameException);
436  EXPECT_THROW(scanner.getCompleteScan(), ParseMonitoringFrameException);
437 }
438 
439 TEST_F(ScannerTest, testDiagnosticInformationException)
440 {
441  EXPECT_CALL(*udp_interface_ptr, read(_, _))
442  .Times(20)
443  .READ_FRAME(10)
444  .READ_FRAME(11)
445  .READ_FRAME(12)
446  .READ_FRAME(13)
447  .READ_FRAME(14)
448  .READ_FRAME(15)
449  .READ_FRAME(16)
450  .READ_FRAME(17)
451  .READ_FRAME(18)
452  .READ_FRAME(19)
453  .READ_FRAME(20)
454  .READ_FRAME(21)
455  .READ_FRAME(22)
456  .READ_FRAME(23)
457  .READ_FRAME(24)
458  .READ_FRAME(25)
459  .READ_FRAME(26)
460  .READ_FRAME(27)
461  .READ_FRAME(28)
462  .READ_FRAME(29);
463 
464  Scanner scanner("1.2.3.4",
465  0x01020305,
466  1234,
467  "p4sswort",
469  PSENscanInternalAngle(2750),
470  std::move(udp_interface_ptr));
471 
472  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
473  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
474  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
475  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
476  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
477  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
478  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
479  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
480  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
481  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
482  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
483  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
484  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
485  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
486  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
487  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
488  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
489  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
490  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
491  EXPECT_THROW(scanner.getCompleteScan(), DiagnosticInformationException);
492 }
493 
494 TEST_F(ScannerTest, testCoherentMonitoringFramesException)
495 {
496  EXPECT_CALL(*udp_interface_ptr, read(_, _))
497  .Times(5)
498  .READ_FRAME(30)
499  .READ_FRAME(31)
500  .READ_FRAME(32)
501  .READ_FRAME(33)
502  .READ_FRAME(34);
503 
504  Scanner scanner("1.2.3.4",
505  0x01020305,
506  1234,
507  "p4sswort",
509  PSENscanInternalAngle(2750),
510  std::move(udp_interface_ptr));
511 
512  EXPECT_THROW(scanner.getCompleteScan(), CoherentMonitoringFramesException);
513  EXPECT_THROW(scanner.getCompleteScan(), ParseMonitoringFrameException);
514  EXPECT_THROW(scanner.getCompleteScan(), CoherentMonitoringFramesException);
515 }
516 
517 TEST_F(ScannerTest, testFetchMonitoringFrameException)
518 {
519  EXPECT_CALL(*udp_interface_ptr, write(_)).Times(2);
520 
521  EXPECT_CALL(*udp_interface_ptr, read(_, _))
522  .Times(4)
523  .READ_FRAME(0)
524  .WillOnce(DoAll(fillArg0(expected_monitoring_frames_.at(1)), Return(sizeof(MonitoringFrame) - 1)))
525  .WillOnce(Throw(ScannerReadTimeout("")))
526  .READ_FRAME(2);
527 
528  Scanner scanner("1.2.3.4",
529  0x01020305,
530  1234,
531  "p4sswort",
533  PSENscanInternalAngle(2750),
534  std::move(udp_interface_ptr));
535 
536  EXPECT_THROW(scanner.getCompleteScan(), CoherentMonitoringFramesException);
537 }
538 
539 TEST_F(ScannerTest, new_scanner)
540 {
541  std::unique_ptr<Scanner> scanner = std::unique_ptr<Scanner>(new Scanner("1.2.3.4",
542  0x01020305,
543  1234,
544  "p4sswort",
546  PSENscanInternalAngle(2750),
547  std::move(udp_interface_ptr)));
548 }
549 } // namespace psen_scan_test
MonitoringFrame as coming from Laserscanner.
std::vector< MonitoringFrame > expected_monitoring_frames_
LaserScan getCompleteScan()
Reads from UDP Interface until complete laserscan object can be formed.
Definition: scanner.cpp:306
void start()
Send start signal to Laserscanner.
Definition: scanner.cpp:106
PSENscanInternalAngle const MAX_SCAN_ANGLE(2750)
Class to hold the data for one laserscan without depencies to ROS.
Definition: laserscan.h:29
uint32_t const MONITORING_FRAME_OPCODE
Definition: scanner_data.h:50
std::vector< uint16_t > measures_
Definition: laserscan.h:36
ACTION_P(fillArg0, monitoring_frame)
PSENscanInternalAngle const min_scan_angle_
Definition: laserscan.h:38
Class for Modeling a PSENscan safety laser scanner.
Definition: scanner.h:42
PSENscanInternalAngle const max_scan_angle_
Definition: laserscan.h:39
PSENscanInternalAngle resolution_
Definition: laserscan.h:37
TEST_F(ScannerTest, new_scanner)
Class to model angles in PSENscan internal format (tenth of degrees)
std::unique_ptr< MockPSENscanUDPInterface > udp_interface_ptr
void stop()
Send stop signal to Laserscanner.
Definition: scanner.cpp:115


psen_scan
Author(s):
autogenerated on Mon Feb 28 2022 23:16:20