Apollo 10.0
自动驾驶开放平台
radar_config_200.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2018 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 racobit_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());
51 set_ctrl_relay_valid_p(data, radar_conf_.ctrl_relay_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_ctrl_relay_p(data, static_cast<uint8_t>(radar_conf_.ctrl_relay()));
59 set_send_ext_info_p(data, radar_conf_.send_ext_info());
60 set_send_quality_p(data, radar_conf_.send_quality());
61 set_sort_index_p(data, static_cast<uint8_t>(radar_conf_.sort_index()));
62 set_store_in_nvm_p(data, static_cast<uint8_t>(radar_conf_.store_in_nvm()));
63 set_rcs_threshold_p(data, radar_conf_.rcs_threshold());
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(true);
78 radar_conf_.set_ctrl_relay_valid(false);
79 radar_conf_.set_rcs_threshold_valid(true);
80
81 radar_conf_.set_max_distance(125);
82 radar_conf_.set_sensor_id(0);
83 radar_conf_.set_output_type(RacobitRadarState_201::OUTPUT_TYPE_NONE);
84 radar_conf_.set_radar_power(0);
85 radar_conf_.set_ctrl_relay(0);
86 radar_conf_.set_send_ext_info(1);
87 radar_conf_.set_send_quality(1);
88 radar_conf_.set_sort_index(0);
89 radar_conf_.set_store_in_nvm(1);
90 radar_conf_.set_rcs_threshold(RacobitRadarState_201::RCS_THRESHOLD_STANDARD);
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_ctrl_relay_valid(valid);
142 return this;
143}
144
146 radar_conf_.set_rcs_threshold_valid(valid);
147 return this;
148}
149
151 radar_conf_.set_max_distance(data);
152 return this;
153}
154
156 radar_conf_.set_sensor_id(data);
157 return this;
158}
159
162 radar_conf_.set_output_type(type);
163 return this;
164}
165
167 radar_conf_.set_radar_power(data);
168 return this;
169}
170
172 radar_conf_.set_ctrl_relay(data);
173 return this;
174}
175
177 radar_conf_.set_send_ext_info(data);
178 return this;
179}
180
182 radar_conf_.set_send_quality(data);
183 return this;
184}
185
187 radar_conf_.set_sort_index(data);
188 return this;
189}
190
192 radar_conf_.set_store_in_nvm(data);
193 return this;
194}
195
198 radar_conf_.set_rcs_threshold(rcs_theshold);
199 return this;
200}
201
202void RadarConfig200::set_max_distance_valid_p(uint8_t* data, bool valid) {
203 Byte frame(data);
204 if (valid) {
205 frame.set_bit_1(0);
206 } else {
207 frame.set_bit_0(0);
208 }
209}
210
211void RadarConfig200::set_sensor_id_valid_p(uint8_t* data, bool valid) {
212 Byte frame(data);
213 if (valid) {
214 frame.set_bit_1(1);
215 } else {
216 frame.set_bit_0(1);
217 }
218}
219
220void RadarConfig200::set_radar_power_valid_p(uint8_t* data, bool valid) {
221 Byte frame(data);
222 if (valid) {
223 frame.set_value(1, 2, 1);
224 } else {
225 frame.set_value(0, 2, 1);
226 }
227}
228
229void RadarConfig200::set_output_type_valid_p(uint8_t* data, bool valid) {
230 Byte frame(data);
231 if (valid) {
232 frame.set_value(1, 3, 1);
233 } else {
234 frame.set_value(0, 3, 1);
235 }
236}
237
238void RadarConfig200::set_send_quality_valid_p(uint8_t* data, bool valid) {
239 Byte frame(data);
240 if (valid) {
241 frame.set_value(1, 4, 1);
242 } else {
243 frame.set_value(0, 4, 1);
244 }
245}
246
247void RadarConfig200::set_send_ext_info_valid_p(uint8_t* data, bool valid) {
248 Byte frame(data);
249 if (valid) {
250 frame.set_value(1, 5, 1);
251 } else {
252 frame.set_value(0, 5, 1);
253 }
254}
255
256void RadarConfig200::set_sort_index_valid_p(uint8_t* data, bool valid) {
257 Byte frame(data);
258 if (valid) {
259 frame.set_value(1, 6, 1);
260 } else {
261 frame.set_value(0, 6, 1);
262 }
263}
264
265void RadarConfig200::set_store_in_nvm_valid_p(uint8_t* data, bool valid) {
266 Byte frame(data);
267 if (valid) {
268 frame.set_value(1, 7, 1);
269 } else {
270 frame.set_value(0, 7, 1);
271 }
272}
273
274void RadarConfig200::set_ctrl_relay_valid_p(uint8_t* data, bool valid) {
275 Byte frame(data + 5);
276 if (valid) {
277 frame.set_bit_1(0);
278 } else {
279 frame.set_bit_0(0);
280 }
281}
282
283void RadarConfig200::set_rcs_threshold_valid_p(uint8_t* data, bool valid) {
284 Byte frame(data + 6);
285 if (valid) {
286 frame.set_bit_1(0);
287 } else {
288 frame.set_bit_0(0);
289 }
290}
291
292void RadarConfig200::set_max_distance_p(uint8_t* data, uint16_t value) {
293 value /= 2;
294 uint8_t low = static_cast<uint8_t>(value >> 2);
295 Byte frame_low(data + 1);
296 frame_low.set_value(low, 0, 8);
297
298 uint8_t high = static_cast<uint8_t>(value << 6);
299 high &= 0xc0;
300 Byte frame_high(data + 2);
301 frame_high.set_value(high, 0, 8);
302}
303
304void RadarConfig200::set_sensor_id_p(uint8_t* data, uint8_t value) {
305 Byte frame(data + 4);
306 frame.set_value(value, 0, 3);
307}
308
310 uint8_t* data, RacobitRadarState_201::OutputType type) {
311 Byte frame(data + 4);
312 uint8_t value = static_cast<uint8_t>(type);
313 frame.set_value(value, 3, 2);
314}
315
316void RadarConfig200::set_radar_power_p(uint8_t* data, uint8_t value) {
317 Byte frame(data + 4);
318 frame.set_value(value, 5, 3);
319}
320
321void RadarConfig200::set_ctrl_relay_p(uint8_t* data, uint8_t value) {
322 Byte frame(data + 5);
323 frame.set_value(value, 1, 1);
324}
325
326void RadarConfig200::set_send_ext_info_p(uint8_t* data, uint8_t value) {
327 Byte frame(data + 5);
328 frame.set_value(value, 3, 1);
329}
330
331void RadarConfig200::set_send_quality_p(uint8_t* data, uint8_t value) {
332 Byte frame(data + 5);
333 frame.set_value(value, 2, 1);
334}
335
336void RadarConfig200::set_sort_index_p(uint8_t* data, uint8_t value) {
337 Byte frame(data + 5);
338 frame.set_value(value, 4, 3);
339}
340
341void RadarConfig200::set_store_in_nvm_p(uint8_t* data, uint8_t value) {
342 Byte frame(data + 5);
343 frame.set_value(value, 7, 1);
344}
345
347 uint8_t* data, RacobitRadarState_201::RcsThreshold rcs_threshold) {
348 Byte frame(data + 6);
349 uint8_t value = static_cast<uint8_t>(rcs_threshold);
350 frame.set_value(value, 1, 3);
351}
352
353} // namespace racobit_radar
354} // namespace drivers
355} // 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_max_distance(uint16_t data)
void set_max_distance_valid_p(uint8_t *data, bool valid)
RadarConfig200 * set_store_in_nvm(uint8_t data)
void set_sensor_id_p(uint8_t *data, uint8_t value)
void set_sort_index_p(uint8_t *data, uint8_t value)
void set_send_quality_p(uint8_t *data, uint8_t value)
void set_send_quality_valid_p(uint8_t *data, bool valid)
RadarConfig200 * set_max_distance_valid(bool valid)
void set_send_ext_info_valid_p(uint8_t *data, bool valid)
uint32_t GetPeriod() const override
get the data period
void set_store_in_nvm_valid_p(uint8_t *data, bool valid)
RadarConfig200 * set_send_quality_valid(bool valid)
void Reset() override
reset the private variables
void set_sensor_id_valid_p(uint8_t *data, bool valid)
void set_sort_index_valid_p(uint8_t *data, bool valid)
void UpdateData(uint8_t *data) override
update the data
RadarConfig200 * set_rcs_threshold_valid(bool valid)
void set_store_in_nvm_p(uint8_t *data, uint8_t value)
RadarConfig200 * set_rcs_threshold(RacobitRadarState_201::RcsThreshold rcs_theshold)
void set_radar_power_valid_p(uint8_t *data, bool valid)
void set_radar_power_p(uint8_t *data, uint8_t value)
RadarConfig200 * set_store_in_nvm_valid(bool valid)
RadarConfig200 * set_radar_conf(RadarConf radar_conf)
void set_ctrl_relay_valid_p(uint8_t *data, bool valid)
RadarConfig200 * set_send_ext_info(uint8_t data)
void set_ctrl_relay_p(uint8_t *data, uint8_t value)
void set_max_distance_p(uint8_t *data, uint16_t value)
void set_send_ext_info_p(uint8_t *data, uint8_t value)
RadarConfig200 * set_send_quality(uint8_t data)
RadarConfig200 * set_send_ext_info_valid(bool valid)
void set_output_type_valid_p(uint8_t *data, bool valid)
void set_rcs_threshold_valid_p(uint8_t *data, bool valid)
RadarConfig200 * set_output_type(RacobitRadarState_201::OutputType type)
void set_output_type_p(uint8_t *data, RacobitRadarState_201::OutputType type)
void set_rcs_threshold_p(uint8_t *data, RacobitRadarState_201::RcsThreshold rcs_theshold)
class register implement
Definition arena_queue.h:37
optional RacobitRadarState_201::RcsThreshold rcs_threshold
optional RacobitRadarState_201::OutputType output_type