Skip to content

Commit 02abe02

Browse files
committed
AP_Rangefinder: move TOFSenseF_I2C to I2C base class
1 parent 3a3cd89 commit 02abe02

File tree

3 files changed

+19
-55
lines changed

3 files changed

+19
-55
lines changed

libraries/AP_RangeFinder/AP_RangeFinder.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -602,11 +602,16 @@ __INITFUNC__ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial
602602
addr = params[instance].address;
603603
}
604604
FOREACH_I2C(i) {
605+
auto *device_ptr = hal.i2c_mgr->get_device_ptr(i, addr);
606+
if (device_ptr == nullptr) {
607+
continue;
608+
}
605609
if (_add_backend(AP_RangeFinder_TOFSenseF_I2C::detect(state[instance], params[instance],
606-
hal.i2c_mgr->get_device(i, addr)),
610+
*device_ptr),
607611
instance)) {
608612
break;
609613
}
614+
delete device_ptr;
610615
}
611616
break;
612617
}

libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp

Lines changed: 5 additions & 44 deletions
Original file line numberDiff line numberDiff line change
@@ -20,53 +20,17 @@
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

2826
extern 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
6429
bool 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
9455
bool 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

libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.h

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -5,19 +5,20 @@
55
#if AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED
66

77
#include "AP_RangeFinder.h"
8-
#include "AP_RangeFinder_Backend.h"
9-
10-
#include <AP_HAL/I2CDevice.h>
8+
#include "AP_RangeFinder_Backend_I2C.h"
119

1210
#define TOFSENSEP_I2C_DEFAULT_ADDR 0x08
1311

14-
class AP_RangeFinder_TOFSenseF_I2C : public AP_RangeFinder_Backend
12+
class AP_RangeFinder_TOFSenseF_I2C : public AP_RangeFinder_Backend_I2C
1513
{
1614
public:
1715
// static detection function
1816
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
1917
AP_RangeFinder_Params &_params,
20-
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
18+
class AP_HAL::I2CDevice &dev) {
19+
// this will free the object if configuration fails:
20+
return configure(NEW_NOTHROW AP_RangeFinder_TOFSenseF_I2C(_state, _params, dev));
21+
}
2122

2223
// update state
2324
void update(void) override;
@@ -30,11 +31,9 @@ class AP_RangeFinder_TOFSenseF_I2C : public AP_RangeFinder_Backend
3031

3132
private:
3233
// constructor
33-
AP_RangeFinder_TOFSenseF_I2C(RangeFinder::RangeFinder_State &_state,
34-
AP_RangeFinder_Params &_params,
35-
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
34+
using AP_RangeFinder_Backend_I2C::AP_RangeFinder_Backend_I2C;
3635

37-
bool init(void);
36+
bool init(void) override;
3837
void timer(void);
3938

4039
uint32_t distance_mm;
@@ -43,7 +42,6 @@ class AP_RangeFinder_TOFSenseF_I2C : public AP_RangeFinder_Backend
4342
// get a reading
4443
bool start_reading(void);
4544
bool get_reading(uint32_t &reading_mm, uint16_t &signal_strength, uint16_t &status);
46-
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
4745
};
4846

4947
#endif // AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED

0 commit comments

Comments
 (0)