Browse Source

AP_Mount: stop passing serial manager through to init()

master
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
2d1357b44c
  1. 4
      libraries/AP_Mount/AP_Mount.cpp
  2. 3
      libraries/AP_Mount/AP_Mount.h
  3. 5
      libraries/AP_Mount/AP_Mount_Alexmos.cpp
  4. 2
      libraries/AP_Mount/AP_Mount_Alexmos.h
  5. 2
      libraries/AP_Mount/AP_Mount_Backend.h
  6. 2
      libraries/AP_Mount/AP_Mount_SToRM32.h
  7. 5
      libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp
  8. 2
      libraries/AP_Mount/AP_Mount_SToRM32_serial.h
  9. 2
      libraries/AP_Mount/AP_Mount_Servo.cpp
  10. 2
      libraries/AP_Mount/AP_Mount_Servo.h
  11. 2
      libraries/AP_Mount/AP_Mount_SoloGimbal.cpp
  12. 2
      libraries/AP_Mount/AP_Mount_SoloGimbal.h

4
libraries/AP_Mount/AP_Mount.cpp

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

3
libraries/AP_Mount/AP_Mount.h

@ -23,7 +23,6 @@ @@ -23,7 +23,6 @@
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_SerialManager/AP_SerialManager.h>
// maximum number of mounts
#define AP_MOUNT_MAX_INSTANCES 1
@ -74,7 +73,7 @@ public: @@ -74,7 +73,7 @@ public:
};
// init - detect and initialise all mounts
void init(const AP_SerialManager& serial_manager);
void init();
// update - give mount opportunity to update servos. should be called at 10hz or higher
void update();

5
libraries/AP_Mount/AP_Mount_Alexmos.cpp

@ -1,10 +1,13 @@ @@ -1,10 +1,13 @@
#include "AP_Mount_Alexmos.h"
#include <AP_GPS/AP_GPS.h>
#include <AP_SerialManager/AP_SerialManager.h>
extern const AP_HAL::HAL& hal;
void AP_Mount_Alexmos::init(const AP_SerialManager& serial_manager)
void AP_Mount_Alexmos::init()
{
const AP_SerialManager& serial_manager = AP::serialmanager();
// check for alexmos protcol
if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_AlexMos, 0))) {
_initialised = true;

2
libraries/AP_Mount/AP_Mount_Alexmos.h

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

2
libraries/AP_Mount/AP_Mount_Backend.h

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

2
libraries/AP_Mount/AP_Mount_SToRM32.h

@ -22,7 +22,7 @@ public: @@ -22,7 +22,7 @@ public:
AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
// init - performs any required initialisation for this instance
void init(const AP_SerialManager& serial_manager) override {}
void init() override {}
// update mount position - should be called periodically
void update() override;

5
libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp

@ -3,6 +3,7 @@ @@ -3,6 +3,7 @@
#include <GCS_MAVLink/GCS_MAVLink.h>
#include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_SerialManager/AP_SerialManager.h>
extern const AP_HAL::HAL& hal;
@ -12,8 +13,10 @@ AP_Mount_SToRM32_serial::AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::m @@ -12,8 +13,10 @@ AP_Mount_SToRM32_serial::AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::m
{}
// init - performs any required initialisation for this instance
void AP_Mount_SToRM32_serial::init(const AP_SerialManager& serial_manager)
void AP_Mount_SToRM32_serial::init()
{
const AP_SerialManager& serial_manager = AP::serialmanager();
_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_SToRM32, 0);
if (_port) {
_initialised = true;

2
libraries/AP_Mount/AP_Mount_SToRM32_serial.h

@ -21,7 +21,7 @@ public: @@ -21,7 +21,7 @@ public:
AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
// init - performs any required initialisation for this instance
void init(const AP_SerialManager& serial_manager) override;
void init() override;
// update mount position - should be called periodically
void update() override;

2
libraries/AP_Mount/AP_Mount_Servo.cpp

@ -4,7 +4,7 @@ @@ -4,7 +4,7 @@
extern const AP_HAL::HAL& hal;
// init - performs any required initialisation for this instance
void AP_Mount_Servo::init(const AP_SerialManager& serial_manager)
void AP_Mount_Servo::init()
{
if (_instance == 0) {
_roll_idx = SRV_Channel::k_mount_roll;

2
libraries/AP_Mount/AP_Mount_Servo.h

@ -24,7 +24,7 @@ public: @@ -24,7 +24,7 @@ public:
}
// init - performs any required initialisation for this instance
void init(const AP_SerialManager& serial_manager) override;
void init() override;
// update mount position - should be called periodically
void update() override;

2
libraries/AP_Mount/AP_Mount_SoloGimbal.cpp

@ -17,7 +17,7 @@ AP_Mount_SoloGimbal::AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_sta @@ -17,7 +17,7 @@ AP_Mount_SoloGimbal::AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_sta
{}
// init - performs any required initialisation for this instance
void AP_Mount_SoloGimbal::init(const AP_SerialManager& serial_manager)
void AP_Mount_SoloGimbal::init()
{
_initialised = true;
set_mode((enum MAV_MOUNT_MODE)_state._default_mode.get());

2
libraries/AP_Mount/AP_Mount_SoloGimbal.h

@ -24,7 +24,7 @@ public: @@ -24,7 +24,7 @@ public:
AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
// init - performs any required initialisation for this instance
void init(const AP_SerialManager& serial_manager) override;
void init() override;
// update mount position - should be called periodically
void update() override;

Loading…
Cancel
Save