mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 18:23:57 -04:00
AP_Compass: RM3100 stop passing frontend for compliance with backend class
This commit is contained in:
parent
8155c8b178
commit
ede80773b9
@ -64,15 +64,14 @@
|
|||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
AP_Compass_Backend *AP_Compass_RM3100::probe(Compass &compass,
|
AP_Compass_Backend *AP_Compass_RM3100::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
|
||||||
bool force_external,
|
bool force_external,
|
||||||
enum Rotation rotation)
|
enum Rotation rotation)
|
||||||
{
|
{
|
||||||
if (!dev) {
|
if (!dev) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
AP_Compass_RM3100 *sensor = new AP_Compass_RM3100(compass, std::move(dev), force_external, rotation);
|
AP_Compass_RM3100 *sensor = new AP_Compass_RM3100(std::move(dev), force_external, rotation);
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
return nullptr;
|
return nullptr;
|
||||||
@ -81,12 +80,10 @@ AP_Compass_Backend *AP_Compass_RM3100::probe(Compass &compass,
|
|||||||
return sensor;
|
return sensor;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Compass_RM3100::AP_Compass_RM3100(Compass &compass,
|
AP_Compass_RM3100::AP_Compass_RM3100(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
|
||||||
AP_HAL::OwnPtr<AP_HAL::Device> _dev,
|
|
||||||
bool _force_external,
|
bool _force_external,
|
||||||
enum Rotation _rotation)
|
enum Rotation _rotation)
|
||||||
: AP_Compass_Backend(compass)
|
: dev(std::move(_dev))
|
||||||
, dev(std::move(_dev))
|
|
||||||
, force_external(_force_external)
|
, force_external(_force_external)
|
||||||
, rotation(_rotation)
|
, rotation(_rotation)
|
||||||
{
|
{
|
||||||
|
@ -29,8 +29,7 @@
|
|||||||
class AP_Compass_RM3100 : public AP_Compass_Backend
|
class AP_Compass_RM3100 : public AP_Compass_Backend
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static AP_Compass_Backend *probe(Compass &compass,
|
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||||
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
|
||||||
bool force_external = false,
|
bool force_external = false,
|
||||||
enum Rotation rotation = ROTATION_NONE);
|
enum Rotation rotation = ROTATION_NONE);
|
||||||
|
|
||||||
@ -39,7 +38,7 @@ public:
|
|||||||
static constexpr const char *name = "RM3100";
|
static constexpr const char *name = "RM3100";
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_Compass_RM3100(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
AP_Compass_RM3100(AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
||||||
bool force_external,
|
bool force_external,
|
||||||
enum Rotation rotation);
|
enum Rotation rotation);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user