Mount: use SerialManager for init

This commit is contained in:
Randy Mackay 2015-01-19 22:38:17 +09:00 committed by Andrew Tridgell
parent 19aa8939de
commit 886cc9aa46
3 changed files with 5 additions and 4 deletions

View File

@ -401,7 +401,7 @@ AP_Mount::AP_Mount(const AP_AHRS &ahrs, const struct Location &current_loc) :
}
// init - detect and initialise all mounts
void AP_Mount::init()
void AP_Mount::init(const AP_SerialManager& serial_manager)
{
// check init has not been called before
if (_num_instances != 0) {
@ -433,7 +433,7 @@ void AP_Mount::init()
// init new instance
if (_backends[instance] != NULL) {
_backends[instance]->init();
_backends[instance]->init(serial_manager);
if (!primary_set) {
_primary = instance;
primary_set = true;

View File

@ -28,6 +28,7 @@
#include <AP_AHRS.h>
#include <GCS_MAVLink.h>
#include <RC_Channel.h>
#include <AP_SerialManager.h>
// maximum number of mounts
#define AP_MOUNT_MAX_INSTANCES 1
@ -60,7 +61,7 @@ public:
AP_Mount(const AP_AHRS &ahrs, const struct Location &current_loc);
// init - detect and initialise all mounts
void init();
void init(const AP_SerialManager& serial_manager);
// update - give mount opportunity to update servos. should be called at 10hz or higher
void update();

View File

@ -39,7 +39,7 @@ public:
virtual ~AP_Mount_Backend(void) {}
// init - performs any required initialisation for this instance
virtual void init() = 0;
virtual void init(const AP_SerialManager& serial_manager) = 0;
// update mount position - should be called periodically
virtual void update() = 0;