mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RangeFinder: removed create() method for objects
See discussion here: https://github.com/ArduPilot/ardupilot/issues/7331 we were getting some uninitialised variables. While it only showed up in AP_SbusOut, it means we can't be sure it won't happen on other objects, so safest to remove the approach Thanks to assistance from Lucas, Peter and Francisco
This commit is contained in:
parent
7122cae589
commit
ffced7d591
@ -33,13 +33,7 @@ class RangeFinder
|
||||
friend class AP_RangeFinder_Backend;
|
||||
|
||||
public:
|
||||
static RangeFinder create(AP_SerialManager &_serial_manager,
|
||||
enum Rotation orientation_default)
|
||||
{
|
||||
return RangeFinder(_serial_manager, orientation_default);
|
||||
}
|
||||
|
||||
constexpr RangeFinder(RangeFinder &&other) = default;
|
||||
RangeFinder(AP_SerialManager &_serial_manager, enum Rotation orientation_default);
|
||||
|
||||
/* Do not allow copies */
|
||||
RangeFinder(const RangeFinder &other) = delete;
|
||||
@ -166,8 +160,6 @@ public:
|
||||
|
||||
|
||||
private:
|
||||
RangeFinder(AP_SerialManager &_serial_manager, enum Rotation orientation_default);
|
||||
|
||||
RangeFinder_State state[RANGEFINDER_MAX_INSTANCES];
|
||||
AP_RangeFinder_Backend *drivers[RANGEFINDER_MAX_INSTANCES];
|
||||
uint8_t num_instances:3;
|
||||
|
@ -10,8 +10,8 @@ void loop();
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
static AP_SerialManager serial_manager = AP_SerialManager::create();
|
||||
static RangeFinder sonar = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
|
||||
static AP_SerialManager serial_manager;
|
||||
static RangeFinder sonar{serial_manager, ROTATION_PITCH_270};
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user