mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
AP_Mount: add override keyword where required
This commit is contained in:
parent
f2070da335
commit
be53782ef1
@ -71,16 +71,16 @@ public:
|
||||
{}
|
||||
|
||||
// init - performs any required initialisation for this instance
|
||||
virtual void init(const AP_SerialManager& serial_manager);
|
||||
virtual void init(const AP_SerialManager& serial_manager) override;
|
||||
|
||||
// update mount position - should be called periodically
|
||||
virtual void update();
|
||||
virtual void update() override;
|
||||
|
||||
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
|
||||
virtual bool has_pan_control() const;
|
||||
virtual bool has_pan_control() const override;
|
||||
|
||||
// set_mode - sets mount's mode
|
||||
virtual void set_mode(enum MAV_MOUNT_MODE mode) ;
|
||||
virtual void set_mode(enum MAV_MOUNT_MODE mode) override;
|
||||
|
||||
// send_mount_status - called to allow mounts to send their status to GCS via MAVLink
|
||||
virtual void send_mount_status(mavlink_channel_t chan) override;
|
||||
|
@ -25,16 +25,16 @@ public:
|
||||
AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
|
||||
|
||||
// init - performs any required initialisation for this instance
|
||||
virtual void init(const AP_SerialManager& serial_manager) {}
|
||||
virtual void init(const AP_SerialManager& serial_manager) override {}
|
||||
|
||||
// update mount position - should be called periodically
|
||||
virtual void update();
|
||||
virtual void update() override;
|
||||
|
||||
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
|
||||
virtual bool has_pan_control() const;
|
||||
virtual bool has_pan_control() const override;
|
||||
|
||||
// set_mode - sets mount's mode
|
||||
virtual void set_mode(enum MAV_MOUNT_MODE mode);
|
||||
virtual void set_mode(enum MAV_MOUNT_MODE mode) override;
|
||||
|
||||
// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
|
||||
virtual void send_mount_status(mavlink_channel_t chan) override;
|
||||
|
@ -23,19 +23,19 @@ public:
|
||||
AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
|
||||
|
||||
// init - performs any required initialisation for this instance
|
||||
virtual void init(const AP_SerialManager& serial_manager);
|
||||
virtual void init(const AP_SerialManager& serial_manager) override;
|
||||
|
||||
// update mount position - should be called periodically
|
||||
virtual void update();
|
||||
virtual void update() override;
|
||||
|
||||
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
|
||||
virtual bool has_pan_control() const;
|
||||
virtual bool has_pan_control() const override;
|
||||
|
||||
// set_mode - sets mount's mode
|
||||
virtual void set_mode(enum MAV_MOUNT_MODE mode);
|
||||
virtual void set_mode(enum MAV_MOUNT_MODE mode) override;
|
||||
|
||||
// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
|
||||
virtual void send_mount_status(mavlink_channel_t chan);
|
||||
virtual void send_mount_status(mavlink_channel_t chan) override;
|
||||
|
||||
private:
|
||||
|
||||
|
@ -25,16 +25,16 @@ public:
|
||||
}
|
||||
|
||||
// init - performs any required initialisation for this instance
|
||||
virtual void init(const AP_SerialManager& serial_manager);
|
||||
virtual void init(const AP_SerialManager& serial_manager) override;
|
||||
|
||||
// update mount position - should be called periodically
|
||||
virtual void update();
|
||||
virtual void update() override;
|
||||
|
||||
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
|
||||
virtual bool has_pan_control() const { return _flags.pan_control; }
|
||||
virtual bool has_pan_control() const override { return _flags.pan_control; }
|
||||
|
||||
// set_mode - sets mount's mode
|
||||
virtual void set_mode(enum MAV_MOUNT_MODE mode);
|
||||
virtual void set_mode(enum MAV_MOUNT_MODE mode) override;
|
||||
|
||||
// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
|
||||
virtual void send_mount_status(mavlink_channel_t chan) override;
|
||||
|
@ -25,16 +25,16 @@ public:
|
||||
AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance);
|
||||
|
||||
// init - performs any required initialisation for this instance
|
||||
virtual void init(const AP_SerialManager& serial_manager);
|
||||
virtual void init(const AP_SerialManager& serial_manager) override;
|
||||
|
||||
// update mount position - should be called periodically
|
||||
virtual void update();
|
||||
virtual void update() override;
|
||||
|
||||
// has_pan_control - returns true if this mount can control it's pan (required for multicopters)
|
||||
virtual bool has_pan_control() const;
|
||||
virtual bool has_pan_control() const override;
|
||||
|
||||
// set_mode - sets mount's mode
|
||||
virtual void set_mode(enum MAV_MOUNT_MODE mode);
|
||||
virtual void set_mode(enum MAV_MOUNT_MODE mode) override;
|
||||
|
||||
// send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message
|
||||
virtual void send_mount_status(mavlink_channel_t chan) override;
|
||||
@ -47,7 +47,7 @@ public:
|
||||
// send a GIMBAL_REPORT message to the GCS
|
||||
void send_gimbal_report(mavlink_channel_t chan) override;
|
||||
|
||||
virtual void update_fast();
|
||||
virtual void update_fast() override;
|
||||
|
||||
private:
|
||||
// internal variables
|
||||
|
@ -95,10 +95,10 @@ private:
|
||||
|
||||
void readVehicleDeltaAngle(uint8_t ins_index, Vector3f &dAng);
|
||||
|
||||
void _acal_save_calibrations();
|
||||
bool _acal_get_ready_to_sample();
|
||||
bool _acal_get_saving();
|
||||
AccelCalibrator* _acal_get_calibrator(uint8_t instance);
|
||||
void _acal_save_calibrations() override;
|
||||
bool _acal_get_ready_to_sample() override;
|
||||
bool _acal_get_saving() override;
|
||||
AccelCalibrator* _acal_get_calibrator(uint8_t instance) override;
|
||||
|
||||
gimbal_mode_t get_mode();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user