AP_Mount: remove redundant constructors

just copy in the one from the parent class
This commit is contained in:
Peter Barker 2023-03-06 09:09:30 +11:00 committed by Peter Barker
parent 9cda7b5ccc
commit 518fece88d
7 changed files with 6 additions and 22 deletions

View File

@ -64,9 +64,7 @@ class AP_Mount_Alexmos : public AP_Mount_Backend
{
public:
//constructor
AP_Mount_Alexmos(AP_Mount &frontend, AP_Mount_Params &params, uint8_t instance):
AP_Mount_Backend(frontend, params, instance)
{}
using AP_Mount_Backend::AP_Mount_Backend;
// init - performs any required initialisation for this instance
void init() override;

View File

@ -11,10 +11,6 @@ extern const AP_HAL::HAL& hal;
#define AP_MOUNT_GREMSY_SEARCH_MS 60000 // search for gimbal for 1 minute after startup
#define AP_MOUNT_GREMSY_ATTITUDE_INTERVAL_US 20000 // send ATTITUDE and AUTOPILOT_STATE_FOR_GIMBAL_DEVICE at 50hz
AP_Mount_Gremsy::AP_Mount_Gremsy(AP_Mount &frontend, AP_Mount_Params &params, uint8_t instance) :
AP_Mount_Backend(frontend, params, instance)
{}
// update mount position
void AP_Mount_Gremsy::update()
{

View File

@ -16,7 +16,7 @@ class AP_Mount_Gremsy : public AP_Mount_Backend
public:
// Constructor
AP_Mount_Gremsy(AP_Mount &frontend, AP_Mount_Params &params, uint8_t instance);
using AP_Mount_Backend::AP_Mount_Backend;
// init
void init() override {}

View File

@ -9,11 +9,6 @@ extern const AP_HAL::HAL& hal;
#define AP_MOUNT_STORM32_RESEND_MS 1000 // resend angle targets to gimbal once per second
#define AP_MOUNT_STORM32_SEARCH_MS 60000 // search for gimbal for 1 minute after startup
AP_Mount_SToRM32::AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount_Params &params, uint8_t instance) :
AP_Mount_Backend(frontend, params, instance),
_chan(MAVLINK_COMM_0)
{}
// update mount position - should be called periodically
void AP_Mount_SToRM32::update()
{

View File

@ -15,7 +15,7 @@ class AP_Mount_SToRM32 : public AP_Mount_Backend
public:
// Constructor
AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount_Params &params, uint8_t instance);
using AP_Mount_Backend::AP_Mount_Backend;
// init - performs any required initialisation for this instance
void init() override {}
@ -43,7 +43,7 @@ private:
bool _initialised; // true once the driver has been initialised
uint8_t _sysid; // sysid of gimbal
uint8_t _compid; // component id of gimbal
mavlink_channel_t _chan; // mavlink channel used to communicate with gimbal
mavlink_channel_t _chan = MAVLINK_COMM_0; // mavlink channel used to communicate with gimbal
uint32_t _last_send; // system time of last do_mount_control sent to gimbal
MountTarget _angle_rad; // latest angle target
};

View File

@ -6,11 +6,6 @@
#include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
#include <AP_SerialManager/AP_SerialManager.h>
AP_Mount_SToRM32_serial::AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount_Params &params, uint8_t instance) :
AP_Mount_Backend(frontend, params, instance),
_reply_type(ReplyType_UNKNOWN)
{}
// init - performs any required initialisation for this instance
void AP_Mount_SToRM32_serial::init()
{

View File

@ -18,7 +18,7 @@ class AP_Mount_SToRM32_serial : public AP_Mount_Backend
public:
// Constructor
AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount_Params &params, uint8_t instance);
using AP_Mount_Backend::AP_Mount_Backend;
// init - performs any required initialisation for this instance
void init() override;
@ -135,7 +135,7 @@ private:
uint8_t _reply_length;
uint8_t _reply_counter;
ReplyType _reply_type;
ReplyType _reply_type = ReplyType_UNKNOWN;
union PACKED SToRM32_reply {