Apollo 10.0
自动驾驶开放平台
radar_config_200.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2021 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
18
20
21namespace apollo {
22namespace drivers {
23namespace nano_radar {
24
27
28const uint32_t RadarConfig200::ID = 0x200;
29
32
33uint32_t RadarConfig200::GetPeriod() const {
34 static const uint32_t PERIOD = 20 * 1000;
35 return PERIOD;
36}
37
42void RadarConfig200::UpdateData(uint8_t* data) {
44 set_sensor_id_valid_p(data, radar_conf_.sensor_id_valid());
45 set_radar_power_valid_p(data, radar_conf_.radar_power_valid());
46 set_output_type_valid_p(data, radar_conf_.output_type_valid());
49 set_sort_index_valid_p(data, radar_conf_.sort_index_valid());
52 set_baudrate_valid_p(data, radar_conf_.baudrate_valid());
53
54 set_max_distance_p(data, static_cast<uint16_t>(radar_conf_.max_distance()));
55 set_sensor_id_p(data, static_cast<uint8_t>(radar_conf_.sensor_id()));
56 set_output_type_p(data, radar_conf_.output_type());
57 set_radar_power_p(data, static_cast<uint8_t>(radar_conf_.radar_power()));
58 set_send_ext_info_p(data, radar_conf_.send_ext_info());
59 set_send_quality_p(data, radar_conf_.send_quality());
60 set_sort_index_p(data, static_cast<uint8_t>(radar_conf_.sort_index()));
61 set_store_in_nvm_p(data, static_cast<uint8_t>(radar_conf_.store_in_nvm()));
62 set_rcs_threshold_p(data, radar_conf_.rcs_threshold());
63 set_baudrate_p(data, radar_conf_.baudrate());
64}
65
70 radar_conf_.set_max_distance_valid(false);
71 radar_conf_.set_sensor_id_valid(false);
72 radar_conf_.set_radar_power_valid(false);
73 radar_conf_.set_output_type_valid(true);
74 radar_conf_.set_send_quality_valid(true);
75 radar_conf_.set_send_ext_info_valid(true);
76 radar_conf_.set_sort_index_valid(false);
77 radar_conf_.set_store_in_nvm_valid(false);
78 radar_conf_.set_rcs_threshold_valid(true);
79 radar_conf_.set_baudrate_valid(true);
80
81 radar_conf_.set_max_distance(125);
82 radar_conf_.set_sensor_id(0);
83 radar_conf_.set_output_type(NanoRadarState_201::OUTPUT_TYPE_NONE);
84 radar_conf_.set_radar_power(0);
85 radar_conf_.set_send_ext_info(1);
86 radar_conf_.set_send_quality(1);
87 radar_conf_.set_sort_index(0);
88 radar_conf_.set_store_in_nvm(0);
89 radar_conf_.set_rcs_threshold(NanoRadarState_201::RCS_THRESHOLD_STANDARD);
90 radar_conf_.set_baudrate(0);
91}
92
93RadarConf RadarConfig200::radar_conf() { return radar_conf_; }
94
96 radar_conf_.CopyFrom(radar_conf);
97 return this;
98}
99
101 radar_conf_.set_max_distance_valid(valid);
102 return this;
103}
104
106 radar_conf_.set_sensor_id_valid(valid);
107 return this;
108}
109
111 radar_conf_.set_radar_power_valid(valid);
112 return this;
113}
114
116 radar_conf_.set_output_type_valid(valid);
117 return this;
118}
119
121 radar_conf_.set_send_quality_valid(valid);
122 return this;
123}
124
126 radar_conf_.set_send_ext_info_valid(valid);
127 return this;
128}
129
131 radar_conf_.set_sort_index_valid(valid);
132 return this;
133}
134
136 radar_conf_.set_store_in_nvm_valid(valid);
137 return this;
138}
139
141 radar_conf_.set_rcs_threshold_valid(valid);
142 return this;
143}
144
146 radar_conf_.set_max_distance(data);
147 return this;
148}
149
151 radar_conf_.set_sensor_id(data);
152 return this;
153}
154
157 radar_conf_.set_output_type(type);
158 return this;
159}
160
162 radar_conf_.set_radar_power(data);
163 return this;
164}
165
167 radar_conf_.set_send_ext_info(data);
168 return this;
169}
170
172 radar_conf_.set_send_quality(data);
173 return this;
174}
175
177 radar_conf_.set_sort_index(data);
178 return this;
179}
180
182 radar_conf_.set_store_in_nvm(data);
183 return this;
184}
185
188 radar_conf_.set_rcs_threshold(rcs_theshold);
189 return this;
190}
191
192void RadarConfig200::set_max_distance_valid_p(uint8_t* data, bool valid) {
193 Byte frame(data);
194 if (valid) {
195 frame.set_bit_1(0);
196 } else {
197 frame.set_bit_0(0);
198 }
199}
200
201void RadarConfig200::set_sensor_id_valid_p(uint8_t* data, bool valid) {
202 Byte frame(data);
203 if (valid) {
204 frame.set_bit_1(1);
205 } else {
206 frame.set_bit_0(1);
207 }
208}
209
210void RadarConfig200::set_radar_power_valid_p(uint8_t* data, bool valid) {
211 Byte frame(data);
212 if (valid) {
213 frame.set_value(1, 2, 1);
214 } else {
215 frame.set_value(0, 2, 1);
216 }
217}
218
219void RadarConfig200::set_output_type_valid_p(uint8_t* data, bool valid) {
220 Byte frame(data);
221 if (valid) {
222 frame.set_value(1, 3, 1);
223 } else {
224 frame.set_value(0, 3, 1);
225 }
226}
227
228void RadarConfig200::set_send_quality_valid_p(uint8_t* data, bool valid) {
229 Byte frame(data);
230 if (valid) {
231 frame.set_value(1, 4, 1);
232 } else {
233 frame.set_value(0, 4, 1);
234 }
235}
236
237void RadarConfig200::set_send_ext_info_valid_p(uint8_t* data, bool valid) {
238 Byte frame(data);
239 if (valid) {
240 frame.set_value(1, 5, 1);
241 } else {
242 frame.set_value(0, 5, 1);
243 }
244}
245
246void RadarConfig200::set_sort_index_valid_p(uint8_t* data, bool valid) {
247 Byte frame(data);
248 if (valid) {
249 frame.set_value(1, 6, 1);
250 } else {
251 frame.set_value(0, 6, 1);
252 }
253}
254
255void RadarConfig200::set_store_in_nvm_valid_p(uint8_t* data, bool valid) {
256 Byte frame(data);
257 if (valid) {
258 frame.set_value(1, 7, 1);
259 } else {
260 frame.set_value(0, 7, 1);
261 }
262}
263
264void RadarConfig200::set_rcs_threshold_valid_p(uint8_t* data, bool valid) {
265 Byte frame(data + 6);
266 if (valid) {
267 frame.set_bit_1(0);
268 } else {
269 frame.set_bit_0(0);
270 }
271}
272
273// void RadarConfig200::set_max_distance_p(uint8_t* data, uint16_t value) {
274// value /= 2;
275// uint8_t low = static_cast<uint8_t>(value >> 2);
276// Byte frame_low(data + 1);
277// frame_low.set_value(low, 0, 8);
278
279// uint8_t high = static_cast<uint8_t>(value << 6);
280// high &= 0xc0;
281// Byte frame_high(data + 2);
282// frame_high.set_value(high, 0, 8);
283// }
284
285void RadarConfig200::set_max_distance_p(uint8_t* data, uint16_t value) {
286 uint16_t x = value / 2;
287 uint8_t t = 0;
288
289 t = x & 0x3;
290 Byte to_set0(data + 2);
291 to_set0.set_value(t, 6, 2);
292 x >>= 2;
293
294 t = x & 0xFF;
295 Byte to_set1(data + 1);
296 to_set1.set_value(t, 0, 8);
297}
298
299void RadarConfig200::set_sensor_id_p(uint8_t* data, uint8_t value) {
300 Byte frame(data + 4);
301 frame.set_value(value, 0, 3);
302}
303
306 Byte frame(data + 4);
307 uint8_t value = static_cast<uint8_t>(type);
308 frame.set_value(value, 3, 2);
309}
310
311void RadarConfig200::set_radar_power_p(uint8_t* data, uint8_t value) {
312 Byte frame(data + 4);
313 frame.set_value(value, 5, 3);
314}
315
316void RadarConfig200::set_send_ext_info_p(uint8_t* data, uint8_t value) {
317 Byte frame(data + 5);
318 frame.set_value(value, 3, 1);
319}
320
321void RadarConfig200::set_send_quality_p(uint8_t* data, uint8_t value) {
322 Byte frame(data + 5);
323 frame.set_value(value, 2, 1);
324}
325
326void RadarConfig200::set_sort_index_p(uint8_t* data, uint8_t value) {
327 Byte frame(data + 5);
328 frame.set_value(value, 4, 3);
329}
330
331void RadarConfig200::set_store_in_nvm_p(uint8_t* data, uint8_t value) {
332 Byte frame(data + 5);
333 frame.set_value(value, 7, 1);
334}
335
337 uint8_t* data, NanoRadarState_201::RcsThreshold rcs_threshold) {
338 Byte frame(data + 6);
339 uint8_t value = static_cast<uint8_t>(rcs_threshold);
340 frame.set_value(value, 1, 3);
341}
342
344 radar_conf_.set_baudrate_valid(valid);
345 return this;
346}
347
348void RadarConfig200::set_baudrate_valid_p(uint8_t* data, bool valid) {
349 Byte frame(data + 7);
350 if (valid) {
351 frame.set_value(1, 4, 1);
352 } else {
353 frame.set_value(0, 4, 1);
354 }
355}
356
358 radar_conf_.set_baudrate(data);
359 return this;
360}
361
362void RadarConfig200::set_baudrate_p(uint8_t* data, uint8_t value) {
363 Byte frame(data + 7);
364 frame.set_value(value, 5, 3);
365}
366
367} // namespace nano_radar
368} // namespace drivers
369} // namespace apollo
Defines the Byte class.
The class of one byte, which is 8 bits.
Definition byte.h:39
void set_bit_1(const int32_t pos)
Set the bit on a specified position to one.
Definition byte.cc:70
void set_bit_0(const int32_t pos)
Set the bit on a specified position to zero.
Definition byte.cc:78
void set_value(const uint8_t value)
Reset this Byte by a specified one-byte unsigned integer.
Definition byte.cc:90
RadarConfig200 * set_output_type_valid(bool valid)
RadarConfig200 * set_baudrate(uint8_t data)
RadarConfig200 * set_radar_conf(RadarConf radar_conf)
RadarConfig200 * set_max_distance(uint16_t data)
void set_max_distance_valid_p(uint8_t *data, bool valid)
RadarConfig200 * set_output_type(NanoRadarState_201::OutputType type)
void set_send_quality_p(uint8_t *data, uint8_t value)
void set_max_distance_p(uint8_t *data, uint16_t value)
RadarConfig200 * set_store_in_nvm_valid(bool valid)
RadarConfig200 * set_sensor_id_valid(bool valid)
RadarConfig200 * set_sort_index_valid(bool valid)
void set_sort_index_valid_p(uint8_t *data, bool valid)
void set_store_in_nvm_valid_p(uint8_t *data, bool valid)
RadarConfig200 * set_rcs_threshold_valid(bool valid)
void set_baudrate_valid_p(uint8_t *data, bool valid)
void set_output_type_valid_p(uint8_t *data, bool valid)
RadarConfig200 * set_store_in_nvm(uint8_t data)
RadarConfig200 * set_send_quality_valid(bool valid)
RadarConfig200 * set_radar_power(uint8_t data)
void set_sort_index_p(uint8_t *data, uint8_t value)
RadarConfig200 * set_rcs_threshold(NanoRadarState_201::RcsThreshold rcs_theshold)
void set_send_ext_info_p(uint8_t *data, uint8_t value)
void set_rcs_threshold_valid_p(uint8_t *data, bool valid)
uint32_t GetPeriod() const override
get the data period
RadarConfig200 * set_sort_index(uint8_t data)
RadarConfig200 * set_sensor_id(uint8_t data)
void set_send_quality_valid_p(uint8_t *data, bool valid)
void set_sensor_id_valid_p(uint8_t *data, bool valid)
RadarConfig200 * set_send_quality(uint8_t data)
void set_rcs_threshold_p(uint8_t *data, NanoRadarState_201::RcsThreshold rcs_theshold)
void set_output_type_p(uint8_t *data, NanoRadarState_201::OutputType type)
RadarConfig200 * set_send_ext_info_valid(bool valid)
void set_sensor_id_p(uint8_t *data, uint8_t value)
RadarConfig200 * set_max_distance_valid(bool valid)
void UpdateData(uint8_t *data) override
update the data
RadarConfig200 * set_radar_power_valid(bool valid)
RadarConfig200 * set_baudrate_valid(bool valid)
void set_baudrate_p(uint8_t *data, uint8_t value)
void set_send_ext_info_valid_p(uint8_t *data, bool valid)
RadarConfig200 * set_send_ext_info(uint8_t data)
void set_store_in_nvm_p(uint8_t *data, uint8_t value)
void set_radar_power_p(uint8_t *data, uint8_t value)
void set_radar_power_valid_p(uint8_t *data, bool valid)
void Reset() override
reset the private variables
class register implement
Definition arena_queue.h:37
optional NanoRadarState_201::OutputType output_type
optional NanoRadarState_201::RcsThreshold rcs_threshold