AP_Mount: stop passing serial manager through to init()
This commit is contained in:
parent
6cecf15e6a
commit
2d1357b44c
@ -408,7 +408,7 @@ AP_Mount::AP_Mount(const struct Location ¤t_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)
|
||||
|
||||
// init new instance
|
||||
if (_backends[instance] != nullptr) {
|
||||
_backends[instance]->init(serial_manager);
|
||||
_backends[instance]->init();
|
||||
if (!primary_set) {
|
||||
_primary = instance;
|
||||
primary_set = true;
|
||||
|
@ -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:
|
||||
};
|
||||
|
||||
// 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();
|
||||
|
@ -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;
|
||||
|
@ -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;
|
||||
|
@ -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;
|
||||
|
@ -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;
|
||||
|
@ -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
|
||||
{}
|
||||
|
||||
// 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;
|
||||
|
@ -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;
|
||||
|
@ -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;
|
||||
|
@ -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;
|
||||
|
@ -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());
|
||||
|
@ -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…
Reference in New Issue
Block a user