2020#define TOFSENSEP_I2C_COMMAND_TAKE_RANGE_READING 0x24
2121#define TOFSENSEP_I2C_COMMAND_SIGNAL_STATUS 0x28
2222
23- #include < utility>
24-
2523#include < AP_HAL/AP_HAL.h>
2624#include < AP_HAL/utility/sparse-endian.h>
2725
2826extern const AP_HAL::HAL& hal;
2927
30- AP_RangeFinder_TOFSenseF_I2C::AP_RangeFinder_TOFSenseF_I2C (RangeFinder::RangeFinder_State &_state,
31- AP_RangeFinder_Params &_params,
32- AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
33- : AP_RangeFinder_Backend(_state, _params)
34- , _dev(std::move(dev))
35- {
36- }
37-
38- // detect if a TOFSenseP rangefinder is connected. We'll detect by
39- // trying to take a reading on I2C. If we get a result the sensor is
40- // there.
41- AP_RangeFinder_Backend *AP_RangeFinder_TOFSenseF_I2C::detect (RangeFinder::RangeFinder_State &_state,
42- AP_RangeFinder_Params &_params,
43- AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
44- {
45- if (!dev) {
46- return nullptr ;
47- }
48-
49- AP_RangeFinder_TOFSenseF_I2C *sensor
50- = NEW_NOTHROW AP_RangeFinder_TOFSenseF_I2C (_state, _params, std::move (dev));
51- if (!sensor) {
52- return nullptr ;
53- }
54-
55- if (!sensor->init ()) {
56- delete sensor;
57- return nullptr ;
58- }
59-
60- return sensor;
61- }
62-
6328// initialise sensor
6429bool AP_RangeFinder_TOFSenseF_I2C::init (void )
6530{
66- _dev-> get_semaphore ()-> take_blocking ( );
31+ WITH_SEMAPHORE (dev. get_semaphore ());
6732
6833 if (!start_reading ()) {
69- _dev->get_semaphore ()->give ();
7034 return false ;
7135 }
7236
@@ -78,13 +42,10 @@ bool AP_RangeFinder_TOFSenseF_I2C::init(void)
7842 uint16_t signal_strength;
7943
8044 if (!get_reading (reading_mm, signal_strength, status)) {
81- _dev->get_semaphore ()->give ();
8245 return false ;
8346 }
8447
85- _dev->get_semaphore ()->give ();
86-
87- _dev->register_periodic_callback (100000 ,
48+ dev.register_periodic_callback (100000 ,
8849 FUNCTOR_BIND_MEMBER (&AP_RangeFinder_TOFSenseF_I2C::timer, void ));
8950
9051 return true ;
@@ -93,10 +54,10 @@ bool AP_RangeFinder_TOFSenseF_I2C::init(void)
9354// start_reading() - ask sensor to make a range reading
9455bool AP_RangeFinder_TOFSenseF_I2C::start_reading ()
9556{
96- uint8_t cmd[] = {TOFSENSEP_I2C_COMMAND_TAKE_RANGE_READING, TOFSENSEP_I2C_COMMAND_SIGNAL_STATUS};
57+ const uint8_t cmd[] = {TOFSENSEP_I2C_COMMAND_TAKE_RANGE_READING, TOFSENSEP_I2C_COMMAND_SIGNAL_STATUS};
9758
9859 // send command to take reading
99- return _dev-> transfer (cmd, sizeof (cmd), nullptr , 0 );
60+ return dev. transfer (cmd, sizeof (cmd), nullptr , 0 );
10061}
10162
10263// read - return last value measured by sensor
@@ -109,7 +70,7 @@ bool AP_RangeFinder_TOFSenseF_I2C::get_reading(uint32_t &reading_mm, uint16_t &s
10970 } packet;
11071
11172 // take range reading and read back results
112- const bool ret = _dev-> transfer (nullptr , 0 , (uint8_t *) &packet, sizeof (packet));
73+ const bool ret = dev. transfer (nullptr , 0 , (uint8_t *) &packet, sizeof (packet));
11374
11475 if (ret) {
11576 // combine results into distance
0 commit comments