AP_Mount: use DataFlash_Class::instance()
Instead of requiring DataFlash_Class reference to be passed on the init() function, get it from the singleton directly.
This commit is contained in:
parent
53c82b4aaf
commit
b3d8c0fc08
@ -408,14 +408,14 @@ AP_Mount::AP_Mount(const AP_AHRS_TYPE &ahrs, const struct Location ¤t_loc)
|
||||
}
|
||||
|
||||
// init - detect and initialise all mounts
|
||||
void AP_Mount::init(DataFlash_Class *dataflash, const AP_SerialManager& serial_manager)
|
||||
void AP_Mount::init(const AP_SerialManager& serial_manager)
|
||||
{
|
||||
// check init has not been called before
|
||||
if (_num_instances != 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
_dataflash = dataflash;
|
||||
_dataflash = DataFlash_Class::instance();
|
||||
|
||||
// default mount to servo mount if rc output channels to control roll, tilt or pan have been defined
|
||||
if (!state[0]._type.configured()) {
|
||||
|
@ -70,7 +70,7 @@ public:
|
||||
AP_Mount(const AP_AHRS_TYPE &ahrs, const struct Location ¤t_loc);
|
||||
|
||||
// init - detect and initialise all mounts
|
||||
void init(DataFlash_Class *dataflash, const AP_SerialManager& serial_manager);
|
||||
void init(const AP_SerialManager& serial_manager);
|
||||
|
||||
// update - give mount opportunity to update servos. should be called at 10hz or higher
|
||||
void update();
|
||||
|
Loading…
Reference in New Issue
Block a user