mirror of https://github.com/ArduPilot/ardupilot
AP_Beacon: stop passing serialmanager into beacon constructor
This commit is contained in:
parent
d3eae308da
commit
39b7f63140
|
@ -74,8 +74,7 @@ const AP_Param::GroupInfo AP_Beacon::var_info[] = {
|
|||
AP_GROUPEND
|
||||
};
|
||||
|
||||
AP_Beacon::AP_Beacon(AP_SerialManager &_serial_manager) :
|
||||
serial_manager(_serial_manager)
|
||||
AP_Beacon::AP_Beacon()
|
||||
{
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
if (_singleton != nullptr) {
|
||||
|
|
|
@ -17,7 +17,6 @@
|
|||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_Common/Location.h>
|
||||
|
||||
class AP_Beacon_Backend;
|
||||
|
@ -31,7 +30,7 @@ class AP_Beacon
|
|||
public:
|
||||
friend class AP_Beacon_Backend;
|
||||
|
||||
AP_Beacon(AP_SerialManager &_serial_manager);
|
||||
AP_Beacon();
|
||||
|
||||
// get singleton instance
|
||||
static AP_Beacon *get_singleton() { return _singleton; }
|
||||
|
@ -130,7 +129,6 @@ private:
|
|||
|
||||
// external references
|
||||
AP_Beacon_Backend *_driver;
|
||||
AP_SerialManager &serial_manager;
|
||||
|
||||
// last known position
|
||||
Vector3f veh_pos_ned;
|
||||
|
|
|
@ -16,6 +16,7 @@
|
|||
#include "AP_Beacon_Backend.h"
|
||||
// debug
|
||||
#include <stdio.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
|
||||
/*
|
||||
base class constructor.
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Beacon/AP_Beacon_Marvelmind.h>
|
||||
#include <AP_Beacon/AP_Beacon.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <stdio.h>
|
||||
|
||||
void setup();
|
||||
|
@ -15,7 +16,7 @@ void set_object_value_and_report(const void *object_pointer,
|
|||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
static AP_SerialManager serial_manager;
|
||||
AP_Beacon beacon{serial_manager};
|
||||
AP_Beacon beacon;
|
||||
|
||||
// try to set the object value but provide diagnostic if it failed
|
||||
void set_object_value_and_report(const void *object_pointer,
|
||||
|
|
Loading…
Reference in New Issue