Browse Source

Mount: use SerialManager for init

mission-4.1.18
Randy Mackay 10 years ago committed by Andrew Tridgell
parent
commit
886cc9aa46
  1. 4
      libraries/AP_Mount/AP_Mount.cpp
  2. 3
      libraries/AP_Mount/AP_Mount.h
  3. 2
      libraries/AP_Mount/AP_Mount_Backend.h

4
libraries/AP_Mount/AP_Mount.cpp

@ -401,7 +401,7 @@ AP_Mount::AP_Mount(const AP_AHRS &ahrs, const struct Location &current_loc) : @@ -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() @@ -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;

3
libraries/AP_Mount/AP_Mount.h

@ -28,6 +28,7 @@ @@ -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: @@ -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();

2
libraries/AP_Mount/AP_Mount_Backend.h

@ -39,7 +39,7 @@ public: @@ -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;

Loading…
Cancel
Save