AP_RangeFinder_VL53L0X.cpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. driver for ST VL53L0X lidar
  15. Many thanks to Pololu, https://github.com/pololu/vl53l0x-arduino and
  16. the ST example code
  17. */
  18. #include "AP_RangeFinder_VL53L0X.h"
  19. #include <utility>
  20. #include <AP_HAL/AP_HAL.h>
  21. #include <AP_HAL/utility/sparse-endian.h>
  22. #include <stdio.h>
  23. extern const AP_HAL::HAL& hal;
  24. enum regAddr
  25. {
  26. SYSRANGE_START = 0x00,
  27. SYSTEM_THRESH_HIGH = 0x0C,
  28. SYSTEM_THRESH_LOW = 0x0E,
  29. SYSTEM_SEQUENCE_CONFIG = 0x01,
  30. SYSTEM_RANGE_CONFIG = 0x09,
  31. SYSTEM_INTERMEASUREMENT_PERIOD = 0x04,
  32. SYSTEM_INTERRUPT_CONFIG_GPIO = 0x0A,
  33. GPIO_HV_MUX_ACTIVE_HIGH = 0x84,
  34. SYSTEM_INTERRUPT_CLEAR = 0x0B,
  35. RESULT_INTERRUPT_STATUS = 0x13,
  36. RESULT_RANGE_STATUS = 0x14,
  37. RESULT_CORE_AMBIENT_WINDOW_EVENTS_RTN = 0xBC,
  38. RESULT_CORE_RANGING_TOTAL_EVENTS_RTN = 0xC0,
  39. RESULT_CORE_AMBIENT_WINDOW_EVENTS_REF = 0xD0,
  40. RESULT_CORE_RANGING_TOTAL_EVENTS_REF = 0xD4,
  41. RESULT_PEAK_SIGNAL_RATE_REF = 0xB6,
  42. ALGO_PART_TO_PART_RANGE_OFFSET_MM = 0x28,
  43. I2C_SLAVE_DEVICE_ADDRESS = 0x8A,
  44. MSRC_CONFIG_CONTROL = 0x60,
  45. PRE_RANGE_CONFIG_MIN_SNR = 0x27,
  46. PRE_RANGE_CONFIG_VALID_PHASE_LOW = 0x56,
  47. PRE_RANGE_CONFIG_VALID_PHASE_HIGH = 0x57,
  48. PRE_RANGE_MIN_COUNT_RATE_RTN_LIMIT = 0x64,
  49. FINAL_RANGE_CONFIG_MIN_SNR = 0x67,
  50. FINAL_RANGE_CONFIG_VALID_PHASE_LOW = 0x47,
  51. FINAL_RANGE_CONFIG_VALID_PHASE_HIGH = 0x48,
  52. FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT = 0x44,
  53. PRE_RANGE_CONFIG_SIGMA_THRESH_HI = 0x61,
  54. PRE_RANGE_CONFIG_SIGMA_THRESH_LO = 0x62,
  55. PRE_RANGE_CONFIG_VCSEL_PERIOD = 0x50,
  56. PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI = 0x51,
  57. PRE_RANGE_CONFIG_TIMEOUT_MACROP_LO = 0x52,
  58. SYSTEM_HISTOGRAM_BIN = 0x81,
  59. HISTOGRAM_CONFIG_INITIAL_PHASE_SELECT = 0x33,
  60. HISTOGRAM_CONFIG_READOUT_CTRL = 0x55,
  61. FINAL_RANGE_CONFIG_VCSEL_PERIOD = 0x70,
  62. FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI = 0x71,
  63. FINAL_RANGE_CONFIG_TIMEOUT_MACROP_LO = 0x72,
  64. CROSSTALK_COMPENSATION_PEAK_RATE_MCPS = 0x20,
  65. MSRC_CONFIG_TIMEOUT_MACROP = 0x46,
  66. SOFT_RESET_GO2_SOFT_RESET_N = 0xBF,
  67. IDENTIFICATION_MODEL_ID = 0xC0,
  68. IDENTIFICATION_REVISION_ID = 0xC2,
  69. OSC_CALIBRATE_VAL = 0xF8,
  70. GLOBAL_CONFIG_VCSEL_WIDTH = 0x32,
  71. GLOBAL_CONFIG_SPAD_ENABLES_REF_0 = 0xB0,
  72. GLOBAL_CONFIG_SPAD_ENABLES_REF_1 = 0xB1,
  73. GLOBAL_CONFIG_SPAD_ENABLES_REF_2 = 0xB2,
  74. GLOBAL_CONFIG_SPAD_ENABLES_REF_3 = 0xB3,
  75. GLOBAL_CONFIG_SPAD_ENABLES_REF_4 = 0xB4,
  76. GLOBAL_CONFIG_SPAD_ENABLES_REF_5 = 0xB5,
  77. GLOBAL_CONFIG_REF_EN_START_SELECT = 0xB6,
  78. DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD = 0x4E,
  79. DYNAMIC_SPAD_REF_EN_START_OFFSET = 0x4F,
  80. POWER_MANAGEMENT_GO1_POWER_FORCE = 0x80,
  81. VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV = 0x89,
  82. ALGO_PHASECAL_LIM = 0x30,
  83. ALGO_PHASECAL_CONFIG_TIMEOUT = 0x30,
  84. };
  85. // tuning register settings
  86. const AP_RangeFinder_VL53L0X::RegData AP_RangeFinder_VL53L0X::tuning_data[] =
  87. {
  88. { 0xFF, 0x01 },
  89. { 0x00, 0x00 },
  90. { 0xFF, 0x00 },
  91. { 0x09, 0x00 },
  92. { 0x10, 0x00 },
  93. { 0x11, 0x00 },
  94. { 0x24, 0x01 },
  95. { 0x25, 0xFF },
  96. { 0x75, 0x00 },
  97. { 0xFF, 0x01 },
  98. { 0x4E, 0x2C },
  99. { 0x48, 0x00 },
  100. { 0x30, 0x20 },
  101. { 0xFF, 0x00 },
  102. { 0x30, 0x09 },
  103. { 0x54, 0x00 },
  104. { 0x31, 0x04 },
  105. { 0x32, 0x03 },
  106. { 0x40, 0x83 },
  107. { 0x46, 0x25 },
  108. { 0x60, 0x00 },
  109. { 0x27, 0x00 },
  110. { 0x50, 0x06 },
  111. { 0x51, 0x00 },
  112. { 0x52, 0x96 },
  113. { 0x56, 0x08 },
  114. { 0x57, 0x30 },
  115. { 0x61, 0x00 },
  116. { 0x62, 0x00 },
  117. { 0x64, 0x00 },
  118. { 0x65, 0x00 },
  119. { 0x66, 0xA0 },
  120. { 0xFF, 0x01 },
  121. { 0x22, 0x32 },
  122. { 0x47, 0x14 },
  123. { 0x49, 0xFF },
  124. { 0x4A, 0x00 },
  125. { 0xFF, 0x00 },
  126. { 0x7A, 0x0A },
  127. { 0x7B, 0x00 },
  128. { 0x78, 0x21 },
  129. { 0xFF, 0x01 },
  130. { 0x23, 0x34 },
  131. { 0x42, 0x00 },
  132. { 0x44, 0xFF },
  133. { 0x45, 0x26 },
  134. { 0x46, 0x05 },
  135. { 0x40, 0x40 },
  136. { 0x0E, 0x06 },
  137. { 0x20, 0x1A },
  138. { 0x43, 0x40 },
  139. { 0xFF, 0x00 },
  140. { 0x34, 0x03 },
  141. { 0x35, 0x44 },
  142. { 0xFF, 0x01 },
  143. { 0x31, 0x04 },
  144. { 0x4B, 0x09 },
  145. { 0x4C, 0x05 },
  146. { 0x4D, 0x04 },
  147. { 0xFF, 0x00 },
  148. { 0x44, 0x00 },
  149. { 0x45, 0x20 },
  150. { 0x47, 0x08 },
  151. { 0x48, 0x28 },
  152. { 0x67, 0x00 },
  153. { 0x70, 0x04 },
  154. { 0x71, 0x01 },
  155. { 0x72, 0xFE },
  156. { 0x76, 0x00 },
  157. { 0x77, 0x00 },
  158. { 0xFF, 0x01 },
  159. { 0x0D, 0x01 },
  160. { 0xFF, 0x00 },
  161. { 0x80, 0x01 },
  162. { 0x01, 0xF8 },
  163. { 0xFF, 0x01 },
  164. { 0x8E, 0x01 },
  165. { 0x00, 0x01 },
  166. { 0xFF, 0x00 },
  167. { 0x80, 0x00 },
  168. };
  169. /*
  170. The constructor also initializes the rangefinder. Note that this
  171. constructor is not called until detect() returns true, so we
  172. already know that we should setup the rangefinder
  173. */
  174. AP_RangeFinder_VL53L0X::AP_RangeFinder_VL53L0X(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev)
  175. : AP_RangeFinder_Backend(_state, _params)
  176. , dev(std::move(_dev)) {}
  177. /*
  178. detect if a VL53L0X rangefinder is connected. We'll detect by
  179. trying to take a reading on I2C. If we get a result the sensor is
  180. there.
  181. */
  182. AP_RangeFinder_Backend *AP_RangeFinder_VL53L0X::detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
  183. {
  184. if (!dev) {
  185. return nullptr;
  186. }
  187. AP_RangeFinder_VL53L0X *sensor
  188. = new AP_RangeFinder_VL53L0X(_state, _params, std::move(dev));
  189. if (!sensor) {
  190. delete sensor;
  191. return nullptr;
  192. }
  193. sensor->dev->get_semaphore()->take_blocking();
  194. if (!sensor->check_id() || !sensor->init()) {
  195. sensor->dev->get_semaphore()->give();
  196. delete sensor;
  197. return nullptr;
  198. }
  199. sensor->dev->get_semaphore()->give();
  200. return sensor;
  201. }
  202. // check sensor ID registers
  203. bool AP_RangeFinder_VL53L0X::check_id(void)
  204. {
  205. uint8_t v1, v2;
  206. if (!dev->read_registers(0xC0, &v1, 1) ||
  207. !dev->read_registers(0xC1, &v2, 1) ||
  208. v1 != 0xEE ||
  209. v2 != 0xAA) {
  210. return false;
  211. }
  212. printf("Detected VL53L0X on bus 0x%x\n", dev->get_bus_id());
  213. return true;
  214. }
  215. // Get reference SPAD (single photon avalanche diode) count and type
  216. // based on VL53L0X_get_info_from_device(),
  217. // but only gets reference SPAD count and type
  218. bool AP_RangeFinder_VL53L0X::get_SPAD_info(uint8_t * count, bool *type_is_aperture)
  219. {
  220. uint8_t tmp;
  221. write_register(0x80, 0x01);
  222. write_register(0xFF, 0x01);
  223. write_register(0x00, 0x00);
  224. write_register(0xFF, 0x06);
  225. write_register(0x83, read_register(0x83) | 0x04);
  226. write_register(0xFF, 0x07);
  227. write_register(0x81, 0x01);
  228. write_register(0x80, 0x01);
  229. write_register(0x94, 0x6b);
  230. write_register(0x83, 0x00);
  231. uint8_t tries = 50;
  232. while (read_register(0x83) == 0x00) {
  233. tries--;
  234. if (tries == 0) {
  235. return false;
  236. }
  237. hal.scheduler->delay(1);
  238. }
  239. write_register(0x83, 0x01);
  240. tmp = read_register(0x92);
  241. *count = tmp & 0x7f;
  242. *type_is_aperture = (tmp >> 7) & 0x01;
  243. write_register(0x81, 0x00);
  244. write_register(0xFF, 0x06);
  245. write_register(0x83, read_register(0x83) & ~0x04);
  246. write_register(0xFF, 0x01);
  247. write_register(0x00, 0x01);
  248. write_register(0xFF, 0x00);
  249. write_register(0x80, 0x00);
  250. return true;
  251. }
  252. // Get sequence step enables
  253. // based on VL53L0X_GetSequenceStepEnables()
  254. void AP_RangeFinder_VL53L0X::getSequenceStepEnables(SequenceStepEnables * enables)
  255. {
  256. uint8_t sequence_config = read_register(SYSTEM_SEQUENCE_CONFIG);
  257. enables->tcc = (sequence_config >> 4) & 0x1;
  258. enables->dss = (sequence_config >> 3) & 0x1;
  259. enables->msrc = (sequence_config >> 2) & 0x1;
  260. enables->pre_range = (sequence_config >> 6) & 0x1;
  261. enables->final_range = (sequence_config >> 7) & 0x1;
  262. }
  263. // Get the VCSEL pulse period in PCLKs for the given period type.
  264. // based on VL53L0X_get_vcsel_pulse_period()
  265. uint8_t AP_RangeFinder_VL53L0X::getVcselPulsePeriod(vcselPeriodType _type)
  266. {
  267. #define decodeVcselPeriod(reg_val) (((reg_val) + 1) << 1)
  268. if (_type == VcselPeriodPreRange) {
  269. return decodeVcselPeriod(read_register(PRE_RANGE_CONFIG_VCSEL_PERIOD));
  270. } else if (_type == VcselPeriodFinalRange) {
  271. return decodeVcselPeriod(read_register(FINAL_RANGE_CONFIG_VCSEL_PERIOD));
  272. }
  273. return 255;
  274. }
  275. // Convert sequence step timeout from MCLKs to microseconds with given VCSEL period in PCLKs
  276. // based on VL53L0X_calc_timeout_us()
  277. uint32_t AP_RangeFinder_VL53L0X::timeoutMclksToMicroseconds(uint16_t timeout_period_mclks, uint8_t vcsel_period_pclks)
  278. {
  279. #define calcMacroPeriod(vcsel_period_pclks) ((((uint32_t)2304 * (vcsel_period_pclks) * 1655) + 500) / 1000)
  280. uint32_t macro_period_ns = calcMacroPeriod(vcsel_period_pclks);
  281. return ((timeout_period_mclks * macro_period_ns) + (macro_period_ns / 2)) / 1000;
  282. }
  283. // Decode sequence step timeout in MCLKs from register value
  284. // based on VL53L0X_decode_timeout()
  285. // Note: the original function returned a uint32_t, but the return value is
  286. // always stored in a uint16_t.
  287. uint16_t AP_RangeFinder_VL53L0X::decodeTimeout(uint16_t reg_val)
  288. {
  289. // format: "(LSByte * 2^MSByte) + 1"
  290. return (uint16_t)((reg_val & 0x00FF) <<
  291. (uint16_t)((reg_val & 0xFF00) >> 8)) + 1;
  292. }
  293. // Get sequence step timeouts
  294. // based on get_sequence_step_timeout(),
  295. // but gets all timeouts instead of just the requested one, and also stores
  296. // intermediate values
  297. void AP_RangeFinder_VL53L0X::getSequenceStepTimeouts(SequenceStepEnables const * enables, SequenceStepTimeouts * timeouts)
  298. {
  299. timeouts->pre_range_vcsel_period_pclks = getVcselPulsePeriod(VcselPeriodPreRange);
  300. timeouts->msrc_dss_tcc_mclks = read_register(MSRC_CONFIG_TIMEOUT_MACROP) + 1;
  301. timeouts->msrc_dss_tcc_us =
  302. timeoutMclksToMicroseconds(timeouts->msrc_dss_tcc_mclks,
  303. timeouts->pre_range_vcsel_period_pclks);
  304. timeouts->pre_range_mclks =
  305. decodeTimeout(read_register16(PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI));
  306. timeouts->pre_range_us =
  307. timeoutMclksToMicroseconds(timeouts->pre_range_mclks,
  308. timeouts->pre_range_vcsel_period_pclks);
  309. timeouts->final_range_vcsel_period_pclks = getVcselPulsePeriod(VcselPeriodFinalRange);
  310. timeouts->final_range_mclks =
  311. decodeTimeout(read_register16(FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI));
  312. if (enables->pre_range) {
  313. timeouts->final_range_mclks -= timeouts->pre_range_mclks;
  314. }
  315. timeouts->final_range_us =
  316. timeoutMclksToMicroseconds(timeouts->final_range_mclks,
  317. timeouts->final_range_vcsel_period_pclks);
  318. }
  319. // Get the measurement timing budget in microseconds
  320. // based on VL53L0X_get_measurement_timing_budget_micro_seconds()
  321. // in us
  322. uint32_t AP_RangeFinder_VL53L0X::getMeasurementTimingBudget(void)
  323. {
  324. SequenceStepEnables enables;
  325. SequenceStepTimeouts timeouts;
  326. uint16_t const StartOverhead = 1910; // note that this is different than the value in set_
  327. uint16_t const EndOverhead = 960;
  328. uint16_t const MsrcOverhead = 660;
  329. uint16_t const TccOverhead = 590;
  330. uint16_t const DssOverhead = 690;
  331. uint16_t const PreRangeOverhead = 660;
  332. uint16_t const FinalRangeOverhead = 550;
  333. // "Start and end overhead times always present"
  334. uint32_t budget_us = StartOverhead + EndOverhead;
  335. getSequenceStepEnables(&enables);
  336. getSequenceStepTimeouts(&enables, &timeouts);
  337. if (enables.tcc) {
  338. budget_us += (timeouts.msrc_dss_tcc_us + TccOverhead);
  339. }
  340. if (enables.dss) {
  341. budget_us += 2 * (timeouts.msrc_dss_tcc_us + DssOverhead);
  342. } else if (enables.msrc) {
  343. budget_us += (timeouts.msrc_dss_tcc_us + MsrcOverhead);
  344. }
  345. if (enables.pre_range) {
  346. budget_us += (timeouts.pre_range_us + PreRangeOverhead);
  347. }
  348. if (enables.final_range) {
  349. budget_us += (timeouts.final_range_us + FinalRangeOverhead);
  350. }
  351. measurement_timing_budget_us = budget_us; // store for internal reuse
  352. return budget_us;
  353. }
  354. // Convert sequence step timeout from microseconds to MCLKs with given VCSEL period in PCLKs
  355. // based on VL53L0X_calc_timeout_mclks()
  356. uint32_t AP_RangeFinder_VL53L0X::timeoutMicrosecondsToMclks(uint32_t timeout_period_us, uint8_t vcsel_period_pclks)
  357. {
  358. uint32_t macro_period_ns = calcMacroPeriod(vcsel_period_pclks);
  359. return (((timeout_period_us * 1000) + (macro_period_ns / 2)) / macro_period_ns);
  360. }
  361. // Encode sequence step timeout register value from timeout in MCLKs
  362. // based on VL53L0X_encode_timeout()
  363. // Note: the original function took a uint16_t, but the argument passed to it
  364. // is always a uint16_t.
  365. uint16_t AP_RangeFinder_VL53L0X::encodeTimeout(uint16_t timeout_mclks)
  366. {
  367. // format: "(LSByte * 2^MSByte) + 1"
  368. uint32_t ls_byte = 0;
  369. uint16_t ms_byte = 0;
  370. if (timeout_mclks > 0) {
  371. ls_byte = timeout_mclks - 1;
  372. while ((ls_byte & 0xFFFFFF00) > 0) {
  373. ls_byte >>= 1;
  374. ms_byte++;
  375. }
  376. return (ms_byte << 8) | (ls_byte & 0xFF);
  377. }
  378. return 0;
  379. }
  380. // Set the measurement timing budget in microseconds, which is the time allowed
  381. // for one measurement; the ST API and this library take care of splitting the
  382. // timing budget among the sub-steps in the ranging sequence. A longer timing
  383. // budget allows for more accurate measurements. Increasing the budget by a
  384. // factor of N decreases the range measurement standard deviation by a factor of
  385. // sqrt(N). Defaults to about 33 milliseconds; the minimum is 20 ms.
  386. // based on VL53L0X_set_measurement_timing_budget_micro_seconds()
  387. bool AP_RangeFinder_VL53L0X::setMeasurementTimingBudget(uint32_t budget_us)
  388. {
  389. SequenceStepEnables enables;
  390. SequenceStepTimeouts timeouts;
  391. uint16_t const StartOverhead = 1320; // note that this is different than the value in get_
  392. uint16_t const EndOverhead = 960;
  393. uint16_t const MsrcOverhead = 660;
  394. uint16_t const TccOverhead = 590;
  395. uint16_t const DssOverhead = 690;
  396. uint16_t const PreRangeOverhead = 660;
  397. uint16_t const FinalRangeOverhead = 550;
  398. uint32_t const MinTimingBudget = 20000;
  399. if (budget_us < MinTimingBudget) { return false; }
  400. uint32_t used_budget_us = StartOverhead + EndOverhead;
  401. getSequenceStepEnables(&enables);
  402. getSequenceStepTimeouts(&enables, &timeouts);
  403. if (enables.tcc) {
  404. used_budget_us += (timeouts.msrc_dss_tcc_us + TccOverhead);
  405. }
  406. if (enables.dss) {
  407. used_budget_us += 2 * (timeouts.msrc_dss_tcc_us + DssOverhead);
  408. } else if (enables.msrc) {
  409. used_budget_us += (timeouts.msrc_dss_tcc_us + MsrcOverhead);
  410. }
  411. if (enables.pre_range) {
  412. used_budget_us += (timeouts.pre_range_us + PreRangeOverhead);
  413. }
  414. if (enables.final_range) {
  415. used_budget_us += FinalRangeOverhead;
  416. // "Note that the final range timeout is determined by the timing
  417. // budget and the sum of all other timeouts within the sequence.
  418. // If there is no room for the final range timeout, then an error
  419. // will be set. Otherwise the remaining time will be applied to
  420. // the final range."
  421. if (used_budget_us > budget_us) {
  422. // "Requested timeout too big."
  423. return false;
  424. }
  425. uint32_t final_range_timeout_us = budget_us - used_budget_us;
  426. // set_sequence_step_timeout() begin
  427. // (SequenceStepId == VL53L0X_SEQUENCESTEP_FINAL_RANGE)
  428. // "For the final range timeout, the pre-range timeout
  429. // must be added. To do this both final and pre-range
  430. // timeouts must be expressed in macro periods MClks
  431. // because they have different vcsel periods."
  432. uint16_t final_range_timeout_mclks =
  433. timeoutMicrosecondsToMclks(final_range_timeout_us,
  434. timeouts.final_range_vcsel_period_pclks);
  435. if (enables.pre_range) {
  436. final_range_timeout_mclks += timeouts.pre_range_mclks;
  437. }
  438. write_register16(FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI,
  439. encodeTimeout(final_range_timeout_mclks));
  440. // set_sequence_step_timeout() end
  441. measurement_timing_budget_us = budget_us; // store for internal reuse
  442. }
  443. return true;
  444. }
  445. bool AP_RangeFinder_VL53L0X::init()
  446. {
  447. // setup for 2.8V operation
  448. write_register(VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV,
  449. read_register(VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV) | 0x01);
  450. // "Set I2C standard mode"
  451. write_register(0x88, 0x00);
  452. write_register(0x80, 0x01);
  453. write_register(0xFF, 0x01);
  454. write_register(0x00, 0x00);
  455. stop_variable = read_register(0x91);
  456. write_register(0x00, 0x01);
  457. write_register(0xFF, 0x00);
  458. write_register(0x80, 0x00);
  459. // disable SIGNAL_RATE_MSRC (bit 1) and SIGNAL_RATE_PRE_RANGE (bit 4) limit checks
  460. write_register(MSRC_CONFIG_CONTROL, read_register(MSRC_CONFIG_CONTROL) | 0x12);
  461. // set final range signal rate limit to 0.25 MCPS (million counts per second)
  462. write_register16(FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT, uint16_t(0.25 * (1 << 7)));
  463. write_register(SYSTEM_SEQUENCE_CONFIG, 0xFF);
  464. uint8_t spad_count;
  465. bool spad_type_is_aperture;
  466. if (!get_SPAD_info(&spad_count, &spad_type_is_aperture)) {
  467. printf("VL53L0X: Failed to get SPAD info\n");
  468. return false;
  469. }
  470. // The SPAD map (RefGoodSpadMap) is read by VL53L0X_get_info_from_device() in
  471. // the API, but the same data seems to be more easily readable from
  472. // GLOBAL_CONFIG_SPAD_ENABLES_REF_0 through _6, so read it from there
  473. uint8_t ref_spad_map[6];
  474. if (!dev->read_registers(GLOBAL_CONFIG_SPAD_ENABLES_REF_0, ref_spad_map, 6)) {
  475. printf("VL53L0X: Failed to read SPAD map\n");
  476. return false;
  477. }
  478. // -- VL53L0X_set_reference_spads() begin (assume NVM values are valid)
  479. write_register(0xFF, 0x01);
  480. write_register(DYNAMIC_SPAD_REF_EN_START_OFFSET, 0x00);
  481. write_register(DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD, 0x2C);
  482. write_register(0xFF, 0x00);
  483. write_register(GLOBAL_CONFIG_REF_EN_START_SELECT, 0xB4);
  484. uint8_t first_spad_to_enable = spad_type_is_aperture ? 12 : 0; // 12 is the first aperture spad
  485. uint8_t spads_enabled = 0;
  486. for (uint8_t i = 0; i < 48; i++) {
  487. if (i < first_spad_to_enable || spads_enabled == spad_count) {
  488. // This bit is lower than the first one that should be enabled, or
  489. // (reference_spad_count) bits have already been enabled, so zero this bit
  490. ref_spad_map[i / 8] &= ~(1 << (i % 8));
  491. } else if ((ref_spad_map[i / 8] >> (i % 8)) & 0x1) {
  492. spads_enabled++;
  493. }
  494. }
  495. uint8_t reg_spad_map[7] = { GLOBAL_CONFIG_SPAD_ENABLES_REF_0, };
  496. memcpy(&reg_spad_map[1], ref_spad_map, 6);
  497. dev->transfer(reg_spad_map, 7, nullptr, 0);
  498. for (uint16_t i=0; i<ARRAY_SIZE(tuning_data); i++) {
  499. write_register(tuning_data[i].reg, tuning_data[i].value);
  500. }
  501. write_register(SYSTEM_INTERRUPT_CONFIG_GPIO, 0x04);
  502. write_register(GPIO_HV_MUX_ACTIVE_HIGH, read_register(GPIO_HV_MUX_ACTIVE_HIGH) & ~0x10); // active low
  503. write_register(SYSTEM_INTERRUPT_CLEAR, 0x01);
  504. // -- VL53L0X_SetGpioConfig() end
  505. measurement_timing_budget_us = getMeasurementTimingBudget();
  506. // "Disable MSRC and TCC by default"
  507. // MSRC = Minimum Signal Rate Check
  508. // TCC = Target CentreCheck
  509. // -- VL53L0X_SetSequenceStepEnable() begin
  510. write_register(SYSTEM_SEQUENCE_CONFIG, 0xE8);
  511. // -- VL53L0X_SetSequenceStepEnable() end
  512. // "Recalculate timing budget"
  513. setMeasurementTimingBudget(measurement_timing_budget_us);
  514. // VL53L0X_StaticInit() end
  515. // VL53L0X_PerformRefCalibration() begin (VL53L0X_perform_ref_calibration())
  516. // -- VL53L0X_perform_vhv_calibration() begin
  517. write_register(SYSTEM_SEQUENCE_CONFIG, 0x01);
  518. if (!performSingleRefCalibration(0x40)) {
  519. printf("VL53L0X: Failed SingleRefCalibration1\n");
  520. return false;
  521. }
  522. // -- VL53L0X_perform_vhv_calibration() end
  523. // -- VL53L0X_perform_phase_calibration() begin
  524. write_register(SYSTEM_SEQUENCE_CONFIG, 0x02);
  525. if (!performSingleRefCalibration(0x00)) {
  526. printf("VL53L0X: Failed SingleRefCalibration2\n");
  527. return false;
  528. }
  529. // -- VL53L0X_perform_phase_calibration() end
  530. // "restore the previous Sequence Config"
  531. write_register(SYSTEM_SEQUENCE_CONFIG, 0xE8);
  532. start_continuous();
  533. // call timer() every 33ms. We expect new data to be available every 33ms
  534. dev->register_periodic_callback(33000,
  535. FUNCTOR_BIND_MEMBER(&AP_RangeFinder_VL53L0X::timer, void));
  536. return true;
  537. }
  538. // based on VL53L0X_perform_single_ref_calibration()
  539. bool AP_RangeFinder_VL53L0X::performSingleRefCalibration(uint8_t vhv_init_byte)
  540. {
  541. write_register(SYSRANGE_START, 0x01 | vhv_init_byte); // VL53L0X_REG_SYSRANGE_MODE_START_STOP
  542. uint8_t tries = 200;
  543. while ((read_register(RESULT_INTERRUPT_STATUS) & 0x07) == 0) {
  544. if (tries-- == 0) {
  545. return false;
  546. }
  547. hal.scheduler->delay(1);
  548. }
  549. write_register(SYSTEM_INTERRUPT_CLEAR, 0x01);
  550. write_register(SYSRANGE_START, 0x00);
  551. return true;
  552. }
  553. // Start continuous ranging measurements
  554. void AP_RangeFinder_VL53L0X::start_continuous(void)
  555. {
  556. write_register(0x80, 0x01);
  557. write_register(0xFF, 0x01);
  558. write_register(0x00, 0x00);
  559. write_register(0x91, stop_variable);
  560. write_register(0x00, 0x01);
  561. write_register(0xFF, 0x00);
  562. write_register(0x80, 0x00);
  563. // continuous back-to-back mode
  564. write_register(SYSRANGE_START, 0x02); // VL53L0X_REG_SYSRANGE_MODE_BACKTOBACK
  565. start_ms = AP_HAL::millis();
  566. }
  567. // read - return last value measured by sensor
  568. bool AP_RangeFinder_VL53L0X::get_reading(uint16_t &reading_mm)
  569. {
  570. if ((read_register(RESULT_INTERRUPT_STATUS) & 0x07) == 0) {
  571. if (AP_HAL::millis() - start_ms > 200) {
  572. start_continuous();
  573. }
  574. return false;
  575. }
  576. // assumptions: Linearity Corrective Gain is 1000 (default);
  577. // fractional ranging is not enabled
  578. reading_mm = read_register16(RESULT_RANGE_STATUS + 10);
  579. write_register(SYSTEM_INTERRUPT_CLEAR, 0x01);
  580. return true;
  581. }
  582. void AP_RangeFinder_VL53L0X::write_register16(uint8_t reg, uint16_t value)
  583. {
  584. uint8_t b[3] = { reg, uint8_t(value>>8), uint8_t(value) };
  585. dev->transfer(b, 3, nullptr, 0);
  586. }
  587. void AP_RangeFinder_VL53L0X::write_register(uint8_t reg, uint8_t value)
  588. {
  589. dev->write_register(reg, value);
  590. }
  591. uint8_t AP_RangeFinder_VL53L0X::read_register(uint8_t reg)
  592. {
  593. uint8_t v = 0;
  594. dev->read_registers(reg, &v, 1);
  595. return v;
  596. }
  597. uint16_t AP_RangeFinder_VL53L0X::read_register16(uint8_t reg)
  598. {
  599. uint16_t v = 0;
  600. dev->transfer(&reg, 1, (uint8_t *)&v, 2);
  601. return be16toh(v);
  602. }
  603. /*
  604. update the state of the sensor
  605. */
  606. void AP_RangeFinder_VL53L0X::update(void)
  607. {
  608. if (counter > 0) {
  609. state.distance_cm = sum_mm / (10*counter);
  610. state.last_reading_ms = AP_HAL::millis();
  611. sum_mm = 0;
  612. counter = 0;
  613. update_status();
  614. } else {
  615. set_status(RangeFinder::RangeFinder_NoData);
  616. }
  617. }
  618. void AP_RangeFinder_VL53L0X::timer(void)
  619. {
  620. uint16_t range_mm;
  621. if (get_reading(range_mm) && range_mm < 8000) {
  622. sum_mm += range_mm;
  623. counter++;
  624. }
  625. }