range_and_reflectance_measurement_test.cpp
Go to the documentation of this file.
1 
27 #include <gtest/gtest.h>
28 #include <boost/asio.hpp>
29 
34 
35 using namespace boost::asio;
36 using namespace omron_os32c_driver;
37 using namespace eip;
38 using namespace eip::serialization;
39 using namespace boost::asio;
40 
41 class RangeAndReflectanceMeasurementTest : public ::testing ::Test
42 {
43 };
44 
46 {
47  EIP_BYTE d[56 + 4000];
48 
49  // use a measurement report header to serialize the header data
51  mrh.scan_count = 0xDEADBEEF;
52  mrh.scan_rate = 40000;
53  mrh.scan_timestamp = 0x55AA55AA;
54  mrh.scan_beam_period = 43333;
55  mrh.machine_state = 3;
56  mrh.machine_stop_reasons = 7;
57  mrh.active_zone_set = 0x45;
58  mrh.zone_inputs = 0xAA;
59  mrh.detection_zone_status = 0x0F;
60  mrh.output_status = 7;
61  mrh.input_status = 3;
62  mrh.display_status = 0x0402;
63  mrh.non_safety_config_checksum = 0x55AA;
64  mrh.safety_config_checksum = 0x5AA5;
65  mrh.range_report_format = 1;
67  mrh.num_beams = 1000;
68 
69  BufferWriter writer(buffer(d));
70  mrh.serialize(writer);
71 
72  for (EIP_UINT i = 10000; i < 10000 + 1000; ++i)
73  {
74  writer.write(i);
75  }
76 
77  for (EIP_UINT i = 20000; i < 20000 + 1000; ++i)
78  {
79  writer.write(i);
80  }
81 
82  ASSERT_EQ(sizeof(d), writer.getByteCount());
83 
84  BufferReader reader(buffer(d));
86  mr.deserialize(reader);
87  EXPECT_EQ(sizeof(d), reader.getByteCount());
88 
89  EXPECT_EQ(0xDEADBEEF, mr.header.scan_count);
90  EXPECT_EQ(40000, mr.header.scan_rate);
91  EXPECT_EQ(0x55AA55AA, mr.header.scan_timestamp);
92  EXPECT_EQ(43333, mr.header.scan_beam_period);
93  EXPECT_EQ(3, mr.header.machine_state);
94  EXPECT_EQ(7, mr.header.machine_stop_reasons);
95  EXPECT_EQ(0x45, mr.header.active_zone_set);
96  EXPECT_EQ(0xAA, mr.header.zone_inputs);
97  EXPECT_EQ(0x0F, mr.header.detection_zone_status);
98  EXPECT_EQ(7, mr.header.output_status);
99  EXPECT_EQ(3, mr.header.input_status);
100  EXPECT_EQ(0x0402, mr.header.display_status);
101  EXPECT_EQ(0x55AA, mr.header.non_safety_config_checksum);
102  EXPECT_EQ(0x5AA5, mr.header.safety_config_checksum);
103  EXPECT_EQ(1, mr.header.range_report_format);
104  EXPECT_EQ(1, mr.header.refletivity_report_format);
105  EXPECT_EQ(1000, mr.header.num_beams);
106 
107  EXPECT_EQ(1000, mr.range_data.size());
108  for (int i = 0; i < mr.range_data.size(); ++i)
109  {
110  EXPECT_EQ(i + 10000, mr.range_data[i]);
111  }
112 
113  EXPECT_EQ(1000, mr.reflectance_data.size());
114  for (int i = 0; i < mr.reflectance_data.size(); ++i)
115  {
116  EXPECT_EQ(i + 20000, mr.reflectance_data[i]);
117  }
118 }
119 
121 {
123  mr.header.scan_count = 0xDEADBEEF;
124  mr.header.scan_rate = 40000;
125  mr.header.scan_timestamp = 0x55AA55AA;
126  mr.header.scan_beam_period = 43333;
127  mr.header.machine_state = 3;
129  mr.header.active_zone_set = 0x45;
130  mr.header.zone_inputs = 0xAA;
131  mr.header.detection_zone_status = 0x0F;
132  mr.header.output_status = 7;
133  mr.header.input_status = 3;
134  mr.header.display_status = 0x0402;
136  mr.header.safety_config_checksum = 0x5AA5;
139  mr.header.num_beams = 1000;
140 
141  mr.range_data.resize(1000);
142  for (int i = 0; i < 1000; ++i)
143  {
144  mr.range_data[i] = i + 30000;
145  }
146 
147  mr.reflectance_data.resize(1000);
148  for (int i = 0; i < 1000; ++i)
149  {
150  mr.reflectance_data[i] = i + 40000;
151  }
152 
153  EIP_BYTE d[56 + 4000];
154  EXPECT_EQ(sizeof(d), mr.getLength());
155  BufferWriter writer(buffer(d));
156  mr.serialize(writer);
157  EXPECT_EQ(sizeof(d), writer.getByteCount());
158 
159  EXPECT_EQ(d[0], 0xEF);
160  EXPECT_EQ(d[1], 0xBE);
161  EXPECT_EQ(d[2], 0xAD);
162  EXPECT_EQ(d[3], 0xDE);
163  EXPECT_EQ(d[4], 0x40);
164  EXPECT_EQ(d[5], 0x9C);
165  EXPECT_EQ(d[6], 0);
166  EXPECT_EQ(d[7], 0);
167  EXPECT_EQ(d[8], 0xAA);
168  EXPECT_EQ(d[9], 0x55);
169  EXPECT_EQ(d[10], 0xAA);
170  EXPECT_EQ(d[11], 0x55);
171  EXPECT_EQ(d[12], 0x45);
172  EXPECT_EQ(d[13], 0xA9);
173  EXPECT_EQ(d[14], 0);
174  EXPECT_EQ(d[15], 0);
175  EXPECT_EQ(d[16], 3);
176  EXPECT_EQ(d[17], 0);
177  EXPECT_EQ(d[18], 7);
178  EXPECT_EQ(d[19], 0);
179  EXPECT_EQ(d[20], 0x45);
180  EXPECT_EQ(d[21], 0);
181  EXPECT_EQ(d[22], 0xAA);
182  EXPECT_EQ(d[23], 0);
183  EXPECT_EQ(d[24], 0x0F);
184  EXPECT_EQ(d[25], 0);
185  EXPECT_EQ(d[26], 0x07);
186  EXPECT_EQ(d[27], 0);
187  EXPECT_EQ(d[28], 0x03);
188  EXPECT_EQ(d[29], 0);
189  EXPECT_EQ(d[30], 0x02);
190  EXPECT_EQ(d[31], 0x04);
191  EXPECT_EQ(d[32], 0xAA);
192  EXPECT_EQ(d[33], 0x55);
193  EXPECT_EQ(d[34], 0xA5);
194  EXPECT_EQ(d[35], 0x5A);
195  EXPECT_EQ(d[36], 0);
196  EXPECT_EQ(d[37], 0);
197  EXPECT_EQ(d[38], 0);
198  EXPECT_EQ(d[39], 0);
199  EXPECT_EQ(d[40], 0);
200  EXPECT_EQ(d[41], 0);
201  EXPECT_EQ(d[42], 0);
202  EXPECT_EQ(d[43], 0);
203  EXPECT_EQ(d[44], 0);
204  EXPECT_EQ(d[45], 0);
205  EXPECT_EQ(d[46], 0);
206  EXPECT_EQ(d[47], 0);
207  EXPECT_EQ(d[48], 1);
208  EXPECT_EQ(d[49], 0);
209  EXPECT_EQ(d[50], 1);
210  EXPECT_EQ(d[51], 0);
211  EXPECT_EQ(d[52], 0);
212  EXPECT_EQ(d[53], 0);
213  EXPECT_EQ(d[54], 0xE8);
214  EXPECT_EQ(d[55], 0x03);
215 
216  for (int i = 0; i < 1000; ++i)
217  {
218  EIP_UINT exp_value = i + 30000;
219  EXPECT_EQ((exp_value)&0x00FF, d[56 + i * 2]);
220  EXPECT_EQ((exp_value >> 8) & 0x00FF, d[56 + i * 2 + 1]);
221  }
222 
223  for (int i = 0; i < 1000; ++i)
224  {
225  EIP_UINT exp_value = i + 40000;
226  EXPECT_EQ((exp_value)&0x00FF, d[56 + 2000 + i * 2]);
227  EXPECT_EQ((exp_value >> 8) & 0x00FF, d[56 + 2000 + i * 2 + 1]);
228  }
229 }
omron_os32c_driver::RangeAndReflectanceMeasurement
Definition: range_and_reflectance_measurement.h:50
omron_os32c_driver::MeasurementReportHeader::scan_count
EIP_UDINT scan_count
Definition: measurement_report_header.h:50
omron_os32c_driver::MeasurementReportHeader::active_zone_set
EIP_UINT active_zone_set
Definition: measurement_report_header.h:56
omron_os32c_driver::MeasurementReportHeader::num_beams
EIP_UINT num_beams
Definition: measurement_report_header.h:66
omron_os32c_driver::MeasurementReportHeader::machine_state
EIP_UINT machine_state
Definition: measurement_report_header.h:54
eip
EIP_BYTE
uint8_t EIP_BYTE
eip::serialization::BufferWriter
omron_os32c_driver::RangeAndReflectanceMeasurement::deserialize
virtual Reader & deserialize(Reader &reader, size_t length)
Definition: range_and_reflectance_measurement.h:82
omron_os32c_driver::MeasurementReportHeader::scan_rate
EIP_UDINT scan_rate
Definition: measurement_report_header.h:51
omron_os32c_driver::MeasurementReportHeader::output_status
EIP_WORD output_status
Definition: measurement_report_header.h:59
eip::serialization::Writer::write
void write(const T &v)
EIP_UINT
uint16_t EIP_UINT
buffer_writer.h
eip::serialization
omron_os32c_driver::MeasurementReportHeader::scan_beam_period
EIP_UDINT scan_beam_period
Definition: measurement_report_header.h:53
omron_os32c_driver::MeasurementReportHeader::machine_stop_reasons
EIP_UINT machine_stop_reasons
Definition: measurement_report_header.h:55
omron_os32c_driver::MeasurementReportHeader::zone_inputs
EIP_WORD zone_inputs
Definition: measurement_report_header.h:57
omron_os32c_driver::RangeAndReflectanceMeasurement::serialize
virtual Writer & serialize(Writer &writer) const
Definition: range_and_reflectance_measurement.h:71
omron_os32c_driver::RangeAndReflectanceMeasurement::reflectance_data
vector< EIP_UINT > reflectance_data
Definition: range_and_reflectance_measurement.h:55
omron_os32c_driver::MeasurementReportHeader::non_safety_config_checksum
EIP_UINT non_safety_config_checksum
Definition: measurement_report_header.h:62
omron_os32c_driver
Definition: measurement_report.h:43
omron_os32c_driver::RangeAndReflectanceMeasurement::getLength
virtual size_t getLength() const
Definition: range_and_reflectance_measurement.h:60
omron_os32c_driver::MeasurementReportHeader::safety_config_checksum
EIP_UINT safety_config_checksum
Definition: measurement_report_header.h:63
omron_os32c_driver::MeasurementReportHeader::range_report_format
EIP_UINT range_report_format
Definition: measurement_report_header.h:64
d
d
omron_os32c_driver::MeasurementReportHeader
Definition: measurement_report_header.h:47
omron_os32c_driver::RangeAndReflectanceMeasurement::range_data
vector< EIP_UINT > range_data
Definition: range_and_reflectance_measurement.h:54
eip::serialization::BufferReader::getByteCount
virtual size_t getByteCount()
buffer_reader.h
TEST_F
TEST_F(RangeAndReflectanceMeasurementTest, test_deserialize)
Definition: range_and_reflectance_measurement_test.cpp:45
omron_os32c_driver::MeasurementReportHeader::refletivity_report_format
EIP_UINT refletivity_report_format
Definition: measurement_report_header.h:65
eip::serialization::BufferWriter::getByteCount
size_t getByteCount()
omron_os32c_driver::MeasurementReportHeader::serialize
virtual Writer & serialize(Writer &writer) const
Definition: measurement_report_header.h:82
eip::serialization::BufferReader
serializable_buffer.h
range_and_reflectance_measurement.h
RangeAndReflectanceMeasurementTest
Definition: range_and_reflectance_measurement_test.cpp:41
omron_os32c_driver::RangeAndReflectanceMeasurement::header
MeasurementReportHeader header
Definition: range_and_reflectance_measurement.h:53
omron_os32c_driver::MeasurementReportHeader::detection_zone_status
EIP_WORD detection_zone_status
Definition: measurement_report_header.h:58
omron_os32c_driver::MeasurementReportHeader::display_status
EIP_UINT display_status
Definition: measurement_report_header.h:61
omron_os32c_driver::MeasurementReportHeader::scan_timestamp
EIP_UDINT scan_timestamp
Definition: measurement_report_header.h:52
omron_os32c_driver::MeasurementReportHeader::input_status
EIP_WORD input_status
Definition: measurement_report_header.h:60


omron_os32c_driver
Author(s): Kareem Shehata
autogenerated on Wed Mar 2 2022 00:39:14