APM:Libraries
AP_RangeFinder_VL53L0X.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  driver for ST VL53L0X lidar
17 
18  Many thanks to Pololu, https://github.com/pololu/vl53l0x-arduino and
19  the ST example code
20  */
21 #include "AP_RangeFinder_VL53L0X.h"
22 
23 #include <utility>
24 
25 #include <AP_HAL/AP_HAL.h>
27 #include <stdio.h>
28 
29 extern const AP_HAL::HAL& hal;
30 
31 enum regAddr
32 {
34 
37 
41 
43 
45 
47 
50 
56 
58 
60 
62 
67 
72 
75 
79 
83 
88 
90 
94 
96 
104 
109 
111 
114 };
115 
116 // tuning register settings
118 {
119  { 0xFF, 0x01 },
120  { 0x00, 0x00 },
121 
122  { 0xFF, 0x00 },
123  { 0x09, 0x00 },
124  { 0x10, 0x00 },
125  { 0x11, 0x00 },
126 
127  { 0x24, 0x01 },
128  { 0x25, 0xFF },
129  { 0x75, 0x00 },
130 
131  { 0xFF, 0x01 },
132  { 0x4E, 0x2C },
133  { 0x48, 0x00 },
134  { 0x30, 0x20 },
135 
136  { 0xFF, 0x00 },
137  { 0x30, 0x09 },
138  { 0x54, 0x00 },
139  { 0x31, 0x04 },
140  { 0x32, 0x03 },
141  { 0x40, 0x83 },
142  { 0x46, 0x25 },
143  { 0x60, 0x00 },
144  { 0x27, 0x00 },
145  { 0x50, 0x06 },
146  { 0x51, 0x00 },
147  { 0x52, 0x96 },
148  { 0x56, 0x08 },
149  { 0x57, 0x30 },
150  { 0x61, 0x00 },
151  { 0x62, 0x00 },
152  { 0x64, 0x00 },
153  { 0x65, 0x00 },
154  { 0x66, 0xA0 },
155 
156  { 0xFF, 0x01 },
157  { 0x22, 0x32 },
158  { 0x47, 0x14 },
159  { 0x49, 0xFF },
160  { 0x4A, 0x00 },
161 
162  { 0xFF, 0x00 },
163  { 0x7A, 0x0A },
164  { 0x7B, 0x00 },
165  { 0x78, 0x21 },
166 
167  { 0xFF, 0x01 },
168  { 0x23, 0x34 },
169  { 0x42, 0x00 },
170  { 0x44, 0xFF },
171  { 0x45, 0x26 },
172  { 0x46, 0x05 },
173  { 0x40, 0x40 },
174  { 0x0E, 0x06 },
175  { 0x20, 0x1A },
176  { 0x43, 0x40 },
177 
178  { 0xFF, 0x00 },
179  { 0x34, 0x03 },
180  { 0x35, 0x44 },
181 
182  { 0xFF, 0x01 },
183  { 0x31, 0x04 },
184  { 0x4B, 0x09 },
185  { 0x4C, 0x05 },
186  { 0x4D, 0x04 },
187 
188  { 0xFF, 0x00 },
189  { 0x44, 0x00 },
190  { 0x45, 0x20 },
191  { 0x47, 0x08 },
192  { 0x48, 0x28 },
193  { 0x67, 0x00 },
194  { 0x70, 0x04 },
195  { 0x71, 0x01 },
196  { 0x72, 0xFE },
197  { 0x76, 0x00 },
198  { 0x77, 0x00 },
199 
200  { 0xFF, 0x01 },
201  { 0x0D, 0x01 },
202 
203  { 0xFF, 0x00 },
204  { 0x80, 0x01 },
205  { 0x01, 0xF8 },
206 
207  { 0xFF, 0x01 },
208  { 0x8E, 0x01 },
209  { 0x00, 0x01 },
210  { 0xFF, 0x00 },
211  { 0x80, 0x00 },
212 };
213 
214 /*
215  The constructor also initializes the rangefinder. Note that this
216  constructor is not called until detect() returns true, so we
217  already know that we should setup the rangefinder
218 */
220  : AP_RangeFinder_Backend(_state)
221  , dev(std::move(_dev)) {}
222 
223 
224 /*
225  detect if a VL53L0X rangefinder is connected. We'll detect by
226  trying to take a reading on I2C. If we get a result the sensor is
227  there.
228 */
230 {
231  if(!dev){
232  return nullptr;
233  }
234  AP_RangeFinder_VL53L0X *sensor
235  = new AP_RangeFinder_VL53L0X(_state, std::move(dev));
236 
237  if (!sensor) {
238  delete sensor;
239  return nullptr;
240  }
241 
242  if (sensor->dev->get_semaphore()->take(0)) {
243  if (!sensor->check_id()) {
244  sensor->dev->get_semaphore()->give();
245  delete sensor;
246  return nullptr;
247  }
248  sensor->dev->get_semaphore()->give();
249  }
250 
251  sensor->init();
252 
253  return sensor;
254 }
255 
256 // check sensor ID registers
258 {
259  uint8_t v1, v2;
260  if (!dev->read_registers(0xC0, &v1, 1) ||
261  !dev->read_registers(0xC1, &v2, 1) ||
262  v1 != 0xEE ||
263  v2 != 0xAA) {
264  return false;
265  }
266  printf("Detected VL53L0X on bus 0x%x\n", dev->get_bus_id());
267  return true;
268 }
269 
270 // Get reference SPAD (single photon avalanche diode) count and type
271 // based on VL53L0X_get_info_from_device(),
272 // but only gets reference SPAD count and type
273 bool AP_RangeFinder_VL53L0X::get_SPAD_info(uint8_t * count, bool *type_is_aperture)
274 {
275  uint8_t tmp;
276 
277  write_register(0x80, 0x01);
278  write_register(0xFF, 0x01);
279  write_register(0x00, 0x00);
280 
281  write_register(0xFF, 0x06);
282  write_register(0x83, read_register(0x83) | 0x04);
283  write_register(0xFF, 0x07);
284  write_register(0x81, 0x01);
285 
286  write_register(0x80, 0x01);
287 
288  write_register(0x94, 0x6b);
289  write_register(0x83, 0x00);
290 
291  uint8_t tries = 50;
292  while (read_register(0x83) == 0x00) {
293  tries--;
294  if (tries == 0) {
295  return false;
296  }
297  hal.scheduler->delay(1);
298  }
299  write_register(0x83, 0x01);
300  tmp = read_register(0x92);
301 
302  *count = tmp & 0x7f;
303  *type_is_aperture = (tmp >> 7) & 0x01;
304 
305  write_register(0x81, 0x00);
306  write_register(0xFF, 0x06);
307  write_register(0x83, read_register(0x83) & ~0x04);
308  write_register(0xFF, 0x01);
309  write_register(0x00, 0x01);
310 
311  write_register(0xFF, 0x00);
312  write_register(0x80, 0x00);
313 
314  return true;
315 }
316 
317 // Get sequence step enables
318 // based on VL53L0X_GetSequenceStepEnables()
320 {
321  uint8_t sequence_config = read_register(SYSTEM_SEQUENCE_CONFIG);
322 
323  enables->tcc = (sequence_config >> 4) & 0x1;
324  enables->dss = (sequence_config >> 3) & 0x1;
325  enables->msrc = (sequence_config >> 2) & 0x1;
326  enables->pre_range = (sequence_config >> 6) & 0x1;
327  enables->final_range = (sequence_config >> 7) & 0x1;
328 }
329 
330 // Get the VCSEL pulse period in PCLKs for the given period type.
331 // based on VL53L0X_get_vcsel_pulse_period()
333 {
334 #define decodeVcselPeriod(reg_val) (((reg_val) + 1) << 1)
335  if (_type == VcselPeriodPreRange) {
337  } else if (_type == VcselPeriodFinalRange) {
339  }
340  return 255;
341 }
342 
343 // Convert sequence step timeout from MCLKs to microseconds with given VCSEL period in PCLKs
344 // based on VL53L0X_calc_timeout_us()
345 uint32_t AP_RangeFinder_VL53L0X::timeoutMclksToMicroseconds(uint16_t timeout_period_mclks, uint8_t vcsel_period_pclks)
346 {
347 #define calcMacroPeriod(vcsel_period_pclks) ((((uint32_t)2304 * (vcsel_period_pclks) * 1655) + 500) / 1000)
348  uint32_t macro_period_ns = calcMacroPeriod(vcsel_period_pclks);
349 
350  return ((timeout_period_mclks * macro_period_ns) + (macro_period_ns / 2)) / 1000;
351 }
352 
353 // Decode sequence step timeout in MCLKs from register value
354 // based on VL53L0X_decode_timeout()
355 // Note: the original function returned a uint32_t, but the return value is
356 // always stored in a uint16_t.
357 uint16_t AP_RangeFinder_VL53L0X::decodeTimeout(uint16_t reg_val)
358 {
359  // format: "(LSByte * 2^MSByte) + 1"
360  return (uint16_t)((reg_val & 0x00FF) <<
361  (uint16_t)((reg_val & 0xFF00) >> 8)) + 1;
362 }
363 
364 // Get sequence step timeouts
365 // based on get_sequence_step_timeout(),
366 // but gets all timeouts instead of just the requested one, and also stores
367 // intermediate values
369 {
371 
373  timeouts->msrc_dss_tcc_us =
375  timeouts->pre_range_vcsel_period_pclks);
376 
377  timeouts->pre_range_mclks =
379  timeouts->pre_range_us =
381  timeouts->pre_range_vcsel_period_pclks);
382 
384 
385  timeouts->final_range_mclks =
387 
388  if (enables->pre_range) {
389  timeouts->final_range_mclks -= timeouts->pre_range_mclks;
390  }
391 
392  timeouts->final_range_us =
395 }
396 
397 
398 // Get the measurement timing budget in microseconds
399 // based on VL53L0X_get_measurement_timing_budget_micro_seconds()
400 // in us
402 {
403  SequenceStepEnables enables;
404  SequenceStepTimeouts timeouts;
405 
406  uint16_t const StartOverhead = 1910; // note that this is different than the value in set_
407  uint16_t const EndOverhead = 960;
408  uint16_t const MsrcOverhead = 660;
409  uint16_t const TccOverhead = 590;
410  uint16_t const DssOverhead = 690;
411  uint16_t const PreRangeOverhead = 660;
412  uint16_t const FinalRangeOverhead = 550;
413 
414  // "Start and end overhead times always present"
415  uint32_t budget_us = StartOverhead + EndOverhead;
416 
417  getSequenceStepEnables(&enables);
418  getSequenceStepTimeouts(&enables, &timeouts);
419 
420  if (enables.tcc) {
421  budget_us += (timeouts.msrc_dss_tcc_us + TccOverhead);
422  }
423 
424  if (enables.dss) {
425  budget_us += 2 * (timeouts.msrc_dss_tcc_us + DssOverhead);
426  } else if (enables.msrc) {
427  budget_us += (timeouts.msrc_dss_tcc_us + MsrcOverhead);
428  }
429 
430  if (enables.pre_range) {
431  budget_us += (timeouts.pre_range_us + PreRangeOverhead);
432  }
433 
434  if (enables.final_range) {
435  budget_us += (timeouts.final_range_us + FinalRangeOverhead);
436  }
437 
438  measurement_timing_budget_us = budget_us; // store for internal reuse
439  return budget_us;
440 }
441 
442 // Convert sequence step timeout from microseconds to MCLKs with given VCSEL period in PCLKs
443 // based on VL53L0X_calc_timeout_mclks()
444 uint32_t AP_RangeFinder_VL53L0X::timeoutMicrosecondsToMclks(uint32_t timeout_period_us, uint8_t vcsel_period_pclks)
445 {
446  uint32_t macro_period_ns = calcMacroPeriod(vcsel_period_pclks);
447 
448  return (((timeout_period_us * 1000) + (macro_period_ns / 2)) / macro_period_ns);
449 }
450 
451 // Encode sequence step timeout register value from timeout in MCLKs
452 // based on VL53L0X_encode_timeout()
453 // Note: the original function took a uint16_t, but the argument passed to it
454 // is always a uint16_t.
455 uint16_t AP_RangeFinder_VL53L0X::encodeTimeout(uint16_t timeout_mclks)
456 {
457  // format: "(LSByte * 2^MSByte) + 1"
458 
459  uint32_t ls_byte = 0;
460  uint16_t ms_byte = 0;
461 
462  if (timeout_mclks > 0) {
463  ls_byte = timeout_mclks - 1;
464 
465  while ((ls_byte & 0xFFFFFF00) > 0) {
466  ls_byte >>= 1;
467  ms_byte++;
468  }
469 
470  return (ms_byte << 8) | (ls_byte & 0xFF);
471  }
472  return 0;
473 }
474 
475 // Set the measurement timing budget in microseconds, which is the time allowed
476 // for one measurement; the ST API and this library take care of splitting the
477 // timing budget among the sub-steps in the ranging sequence. A longer timing
478 // budget allows for more accurate measurements. Increasing the budget by a
479 // factor of N decreases the range measurement standard deviation by a factor of
480 // sqrt(N). Defaults to about 33 milliseconds; the minimum is 20 ms.
481 // based on VL53L0X_set_measurement_timing_budget_micro_seconds()
483 {
484  SequenceStepEnables enables;
485  SequenceStepTimeouts timeouts;
486 
487  uint16_t const StartOverhead = 1320; // note that this is different than the value in get_
488  uint16_t const EndOverhead = 960;
489  uint16_t const MsrcOverhead = 660;
490  uint16_t const TccOverhead = 590;
491  uint16_t const DssOverhead = 690;
492  uint16_t const PreRangeOverhead = 660;
493  uint16_t const FinalRangeOverhead = 550;
494 
495  uint32_t const MinTimingBudget = 20000;
496 
497  if (budget_us < MinTimingBudget) { return false; }
498 
499  uint32_t used_budget_us = StartOverhead + EndOverhead;
500 
501  getSequenceStepEnables(&enables);
502  getSequenceStepTimeouts(&enables, &timeouts);
503 
504  if (enables.tcc) {
505  used_budget_us += (timeouts.msrc_dss_tcc_us + TccOverhead);
506  }
507 
508  if (enables.dss) {
509  used_budget_us += 2 * (timeouts.msrc_dss_tcc_us + DssOverhead);
510  } else if (enables.msrc) {
511  used_budget_us += (timeouts.msrc_dss_tcc_us + MsrcOverhead);
512  }
513 
514  if (enables.pre_range) {
515  used_budget_us += (timeouts.pre_range_us + PreRangeOverhead);
516  }
517 
518  if (enables.final_range) {
519  used_budget_us += FinalRangeOverhead;
520 
521  // "Note that the final range timeout is determined by the timing
522  // budget and the sum of all other timeouts within the sequence.
523  // If there is no room for the final range timeout, then an error
524  // will be set. Otherwise the remaining time will be applied to
525  // the final range."
526 
527  if (used_budget_us > budget_us) {
528  // "Requested timeout too big."
529  return false;
530  }
531 
532  uint32_t final_range_timeout_us = budget_us - used_budget_us;
533 
534  // set_sequence_step_timeout() begin
535  // (SequenceStepId == VL53L0X_SEQUENCESTEP_FINAL_RANGE)
536 
537  // "For the final range timeout, the pre-range timeout
538  // must be added. To do this both final and pre-range
539  // timeouts must be expressed in macro periods MClks
540  // because they have different vcsel periods."
541 
542  uint16_t final_range_timeout_mclks =
543  timeoutMicrosecondsToMclks(final_range_timeout_us,
545 
546  if (enables.pre_range) {
547  final_range_timeout_mclks += timeouts.pre_range_mclks;
548  }
549 
551  encodeTimeout(final_range_timeout_mclks));
552 
553  // set_sequence_step_timeout() end
554  measurement_timing_budget_us = budget_us; // store for internal reuse
555  }
556  return true;
557 }
558 
560 {
561  // setup for 2.8V operation
564 
565  // "Set I2C standard mode"
566  write_register(0x88, 0x00);
567 
568  write_register(0x80, 0x01);
569  write_register(0xFF, 0x01);
570  write_register(0x00, 0x00);
572  write_register(0x00, 0x01);
573  write_register(0xFF, 0x00);
574  write_register(0x80, 0x00);
575 
576  // disable SIGNAL_RATE_MSRC (bit 1) and SIGNAL_RATE_PRE_RANGE (bit 4) limit checks
578 
579  // set final range signal rate limit to 0.25 MCPS (million counts per second)
581 
583 
584  uint8_t spad_count;
585  bool spad_type_is_aperture;
586  if (!get_SPAD_info(&spad_count, &spad_type_is_aperture)) {
587  printf("Failed to get SPAD info\n");
588  return;
589  }
590 
591  // The SPAD map (RefGoodSpadMap) is read by VL53L0X_get_info_from_device() in
592  // the API, but the same data seems to be more easily readable from
593  // GLOBAL_CONFIG_SPAD_ENABLES_REF_0 through _6, so read it from there
594  uint8_t ref_spad_map[6];
595  if (!dev->read_registers(GLOBAL_CONFIG_SPAD_ENABLES_REF_0, ref_spad_map, 6)) {
596  printf("Failed to read SPAD map\n");
597  return;
598  }
599 
600  // -- VL53L0X_set_reference_spads() begin (assume NVM values are valid)
601  write_register(0xFF, 0x01);
604  write_register(0xFF, 0x00);
606 
607  uint8_t first_spad_to_enable = spad_type_is_aperture ? 12 : 0; // 12 is the first aperture spad
608  uint8_t spads_enabled = 0;
609 
610  for (uint8_t i = 0; i < 48; i++) {
611  if (i < first_spad_to_enable || spads_enabled == spad_count) {
612  // This bit is lower than the first one that should be enabled, or
613  // (reference_spad_count) bits have already been enabled, so zero this bit
614  ref_spad_map[i / 8] &= ~(1 << (i % 8));
615  } else if ((ref_spad_map[i / 8] >> (i % 8)) & 0x1) {
616  spads_enabled++;
617  }
618  }
619 
620  uint8_t reg_spad_map[7] = { GLOBAL_CONFIG_SPAD_ENABLES_REF_0, };
621  memcpy(&reg_spad_map[1], ref_spad_map, 6);
622  dev->transfer(reg_spad_map, 7, nullptr, 0);
623 
624  for (uint16_t i=0; i<ARRAY_SIZE(tuning_data); i++) {
626  }
627 
631 
632  // -- VL53L0X_SetGpioConfig() end
633 
635 
636  // "Disable MSRC and TCC by default"
637  // MSRC = Minimum Signal Rate Check
638  // TCC = Target CentreCheck
639  // -- VL53L0X_SetSequenceStepEnable() begin
640 
642 
643  // -- VL53L0X_SetSequenceStepEnable() end
644 
645  // "Recalculate timing budget"
647 
648  // VL53L0X_StaticInit() end
649 
650  // VL53L0X_PerformRefCalibration() begin (VL53L0X_perform_ref_calibration())
651 
652  // -- VL53L0X_perform_vhv_calibration() begin
653 
655  if (!performSingleRefCalibration(0x40)) {
656  printf("Failed SingleRefCalibration1\n");
657  return;
658  }
659 
660  // -- VL53L0X_perform_vhv_calibration() end
661 
662  // -- VL53L0X_perform_phase_calibration() begin
663 
665  if (!performSingleRefCalibration(0x00)) {
666  printf("Failed SingleRefCalibration2\n");
667  return;
668  }
669 
670  // -- VL53L0X_perform_phase_calibration() end
671 
672  // "restore the previous Sequence Config"
674 
676 
677  // call timer() every 33ms. We expect new data to be available every 33ms
680 }
681 
682 
683 // based on VL53L0X_perform_single_ref_calibration()
685 {
686  write_register(SYSRANGE_START, 0x01 | vhv_init_byte); // VL53L0X_REG_SYSRANGE_MODE_START_STOP
687 
688  uint8_t tries = 200;
689  while ((read_register(RESULT_INTERRUPT_STATUS) & 0x07) == 0) {
690  if (tries-- == 0) {
691  return false;
692  }
693  hal.scheduler->delay(1);
694  }
695 
697 
699 
700  return true;
701 }
702 
703 
704 // Start continuous ranging measurements
706 {
707  write_register(0x80, 0x01);
708  write_register(0xFF, 0x01);
709  write_register(0x00, 0x00);
711  write_register(0x00, 0x01);
712  write_register(0xFF, 0x00);
713  write_register(0x80, 0x00);
714 
715  // continuous back-to-back mode
716  write_register(SYSRANGE_START, 0x02); // VL53L0X_REG_SYSRANGE_MODE_BACKTOBACK
717 
719 }
720 
721 // read - return last value measured by sensor
722 bool AP_RangeFinder_VL53L0X::get_reading(uint16_t &reading_mm)
723 {
724  if ((read_register(RESULT_INTERRUPT_STATUS) & 0x07) == 0) {
725  if (AP_HAL::millis() - start_ms > 200) {
727  }
728  return false;
729  }
730 
731  // assumptions: Linearity Corrective Gain is 1000 (default);
732  // fractional ranging is not enabled
733  reading_mm = read_register16(RESULT_RANGE_STATUS + 10);
735 
736  return true;
737 }
738 
740 {
741  uint8_t b[3] = { reg, uint8_t(value>>8), uint8_t(value) };
742  dev->transfer(b, 3, nullptr, 0);
743 }
744 
746 {
747  dev->write_register(reg, value);
748 }
749 
751 {
752  uint8_t v = 0;
753  dev->read_registers(reg, &v, 1);
754  return v;
755 }
756 
758 {
759  uint16_t v = 0;
760  dev->transfer(&reg, 1, (uint8_t *)&v, 2);
761  return be16toh(v);
762 }
763 
764 /*
765  update the state of the sensor
766 */
768 {
769  if (counter > 0) {
770  state.distance_cm = sum_mm / (10*counter);
771  sum_mm = 0;
772  counter = 0;
773  update_status();
774  } else {
776  }
777 }
778 
780 {
781  uint16_t range_mm;
782  if (get_reading(range_mm) && range_mm < 8000) {
783  sum_mm += range_mm;
784  counter++;
785  }
786 }
int printf(const char *fmt,...)
Definition: stdio.c:113
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
#define calcMacroPeriod(vcsel_period_pclks)
void write_register(uint8_t reg, uint8_t value)
uint16_t read_register16(uint8_t reg)
AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
bool get_reading(uint16_t &reading_cm)
uint32_t get_bus_id(void) const
Definition: Device.h:60
bool get_SPAD_info(uint8_t *count, bool *type_is_aperture)
uint8_t getVcselPulsePeriod(vcselPeriodType type)
virtual Semaphore * get_semaphore() override=0
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
bool performSingleRefCalibration(uint8_t vhv_init_byte)
uint16_t decodeTimeout(uint16_t reg_val)
static const RegData tuning_data[]
virtual void delay(uint16_t ms)=0
static uint16_t be16toh(be16_t value)
Definition: sparse-endian.h:83
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
uint32_t timeoutMicrosecondsToMclks(uint32_t timeout_period_us, uint8_t vcsel_period_pclks)
uint32_t millis()
Definition: system.cpp:157
#define decodeVcselPeriod(reg_val)
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
AP_RangeFinder_VL53L0X(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
uint16_t encodeTimeout(uint16_t timeout_mclks)
uint32_t timeoutMclksToMicroseconds(uint16_t timeout_period_mclks, uint8_t vcsel_period_pclks)
virtual bool give()=0
float v
Definition: Printf.cpp:15
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
void getSequenceStepEnables(SequenceStepEnables *enables)
bool setMeasurementTimingBudget(uint32_t budget_us)
void getSequenceStepTimeouts(SequenceStepEnables const *enables, SequenceStepTimeouts *timeouts)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
float value
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
void write_register16(uint8_t reg, uint16_t value)
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
uint8_t read_register(uint8_t reg)
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114