AP_Compass: RM3100 stop passing frontend for compliance with backend class

This commit is contained in:
thomass 2019-02-07 23:13:13 +01:00 committed by Andrew Tridgell
parent 8155c8b178
commit ede80773b9
2 changed files with 6 additions and 10 deletions

View File

@ -64,15 +64,14 @@
extern const AP_HAL::HAL &hal;
AP_Compass_Backend *AP_Compass_RM3100::probe(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::Device> dev,
AP_Compass_Backend *AP_Compass_RM3100::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external,
enum Rotation rotation)
{
if (!dev) {
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()) {
delete sensor;
return nullptr;
@ -81,12 +80,10 @@ AP_Compass_Backend *AP_Compass_RM3100::probe(Compass &compass,
return sensor;
}
AP_Compass_RM3100::AP_Compass_RM3100(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::Device> _dev,
AP_Compass_RM3100::AP_Compass_RM3100(AP_HAL::OwnPtr<AP_HAL::Device> _dev,
bool _force_external,
enum Rotation _rotation)
: AP_Compass_Backend(compass)
, dev(std::move(_dev))
: dev(std::move(_dev))
, force_external(_force_external)
, rotation(_rotation)
{

View File

@ -29,8 +29,7 @@
class AP_Compass_RM3100 : public AP_Compass_Backend
{
public:
static AP_Compass_Backend *probe(Compass &compass,
AP_HAL::OwnPtr<AP_HAL::Device> dev,
static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,
bool force_external = false,
enum Rotation rotation = ROTATION_NONE);
@ -39,7 +38,7 @@ public:
static constexpr const char *name = "RM3100";
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,
enum Rotation rotation);