mirror of https://github.com/ArduPilot/ardupilot
Tools: Replay: correct compilation (missing override keywords)
This commit is contained in:
parent
927a0521e3
commit
6c22faa585
|
@ -41,7 +41,7 @@ public:
|
|||
: LR_MsgHandler(_f, _logger,_last_timestamp_usec),
|
||||
ahr2_attitude(_ahr2_attitude) { };
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
Vector3f &ahr2_attitude;
|
||||
|
@ -55,7 +55,7 @@ public:
|
|||
uint64_t &_last_timestamp_usec)
|
||||
: LR_MsgHandler(_f, _logger, _last_timestamp_usec) { };
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
|
||||
|
@ -66,7 +66,7 @@ public:
|
|||
uint64_t &_last_timestamp_usec, AP_Airspeed &_airspeed) :
|
||||
LR_MsgHandler(_f, _logger, _last_timestamp_usec), airspeed(_airspeed) { };
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
AP_Airspeed &airspeed;
|
||||
|
@ -79,7 +79,7 @@ public:
|
|||
uint64_t &_last_timestamp_usec) :
|
||||
LR_MsgHandler(_f, _logger, _last_timestamp_usec) { };
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
|
||||
|
@ -90,7 +90,7 @@ public:
|
|||
uint64_t &_last_timestamp_usec, Vector3f &_attitude)
|
||||
: LR_MsgHandler(_f, _logger, _last_timestamp_usec), attitude(_attitude)
|
||||
{ };
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
Vector3f &attitude;
|
||||
|
@ -105,7 +105,7 @@ public:
|
|||
: LR_MsgHandler(_f, _logger, _last_timestamp_usec),
|
||||
check_state(_check_state)
|
||||
{ };
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
CheckState &check_state;
|
||||
|
@ -119,7 +119,7 @@ public:
|
|||
: LR_MsgHandler(_f, _logger, _last_timestamp_usec)
|
||||
{ };
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
};
|
||||
|
||||
|
@ -131,7 +131,7 @@ public:
|
|||
uint64_t &_last_timestamp_usec)
|
||||
: LR_MsgHandler(_f, _logger, _last_timestamp_usec) { };
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
|
||||
|
@ -165,7 +165,7 @@ public:
|
|||
_gps, _ground_alt_cm),
|
||||
gps(_gps), ground_alt_cm(_ground_alt_cm) { };
|
||||
|
||||
void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
AP_GPS &gps;
|
||||
|
@ -185,7 +185,7 @@ public:
|
|||
: LR_MsgHandler_GPS_Base(_f, _logger, _last_timestamp_usec,
|
||||
_gps, _ground_alt_cm), gps(_gps),
|
||||
ground_alt_cm(_ground_alt_cm) { };
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
private:
|
||||
AP_GPS &gps;
|
||||
uint32_t &ground_alt_cm;
|
||||
|
@ -215,7 +215,7 @@ public:
|
|||
: LR_MsgHandler_GPA_Base(_f, _logger,_last_timestamp_usec,
|
||||
_gps), gps(_gps) { };
|
||||
|
||||
void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
AP_GPS &gps;
|
||||
|
@ -228,7 +228,7 @@ public:
|
|||
uint64_t &_last_timestamp_usec, AP_GPS &_gps)
|
||||
: LR_MsgHandler_GPA_Base(_f, _logger, _last_timestamp_usec,
|
||||
_gps), gps(_gps) { };
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
private:
|
||||
AP_GPS &gps;
|
||||
};
|
||||
|
@ -266,7 +266,7 @@ public:
|
|||
: LR_MsgHandler_IMU_Base(_f, _logger, _last_timestamp_usec,
|
||||
_accel_mask, _gyro_mask, _ins) { };
|
||||
|
||||
void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
class LR_MsgHandler_IMU2 : public LR_MsgHandler_IMU_Base
|
||||
|
@ -279,7 +279,7 @@ public:
|
|||
: LR_MsgHandler_IMU_Base(_f, _logger, _last_timestamp_usec,
|
||||
_accel_mask, _gyro_mask, _ins) {};
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
class LR_MsgHandler_IMU3 : public LR_MsgHandler_IMU_Base
|
||||
|
@ -292,7 +292,7 @@ public:
|
|||
: LR_MsgHandler_IMU_Base(_f, _logger, _last_timestamp_usec,
|
||||
_accel_mask, _gyro_mask, _ins) {};
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
|
||||
|
@ -329,7 +329,7 @@ public:
|
|||
: LR_MsgHandler_IMT_Base(_f, _logger, _last_timestamp_usec,
|
||||
_accel_mask, _gyro_mask, _use_imt, _ins) { };
|
||||
|
||||
void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
class LR_MsgHandler_IMT2 : public LR_MsgHandler_IMT_Base
|
||||
|
@ -343,7 +343,7 @@ public:
|
|||
: LR_MsgHandler_IMT_Base(_f, _logger, _last_timestamp_usec,
|
||||
_accel_mask, _gyro_mask, _use_imt, _ins) { };
|
||||
|
||||
void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
class LR_MsgHandler_IMT3 : public LR_MsgHandler_IMT_Base
|
||||
|
@ -357,7 +357,7 @@ public:
|
|||
: LR_MsgHandler_IMT_Base(_f, _logger, _last_timestamp_usec,
|
||||
_accel_mask, _gyro_mask, _use_imt, _ins) { };
|
||||
|
||||
void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
|
||||
|
@ -382,7 +382,7 @@ public:
|
|||
uint64_t &_last_timestamp_usec, Compass &_compass)
|
||||
: LR_MsgHandler_MAG_Base(_f, _logger, _last_timestamp_usec,_compass) {};
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
class LR_MsgHandler_MAG2 : public LR_MsgHandler_MAG_Base
|
||||
|
@ -392,7 +392,7 @@ public:
|
|||
uint64_t &_last_timestamp_usec, Compass &_compass)
|
||||
: LR_MsgHandler_MAG_Base(_f, _logger, _last_timestamp_usec,_compass) {};
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
};
|
||||
|
||||
|
||||
|
@ -407,7 +407,7 @@ public:
|
|||
vehicle(_vehicle), ahrs(_ahrs) { }
|
||||
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
VehicleType::vehicle_type &vehicle;
|
||||
|
@ -422,7 +422,7 @@ public:
|
|||
uint64_t &_last_timestamp_usec, Vector3f &_inavpos)
|
||||
: LR_MsgHandler(_f, _logger, _last_timestamp_usec), inavpos(_inavpos) {};
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
Vector3f &inavpos;
|
||||
|
@ -439,7 +439,7 @@ public:
|
|||
_set_parameter_callback(set_parameter_callback)
|
||||
{};
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
bool set_parameter(const char *name, const float value);
|
||||
|
@ -453,7 +453,7 @@ public:
|
|||
uint64_t &_last_timestamp_usec)
|
||||
: LR_MsgHandler(_f, _logger, _last_timestamp_usec) { };
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
|
||||
|
@ -469,7 +469,7 @@ public:
|
|||
sim_attitude(_sim_attitude)
|
||||
{ };
|
||||
|
||||
virtual void process_message(uint8_t *msg);
|
||||
void process_message(uint8_t *msg) override;
|
||||
|
||||
private:
|
||||
Vector3f &sim_attitude;
|
||||
|
|
|
@ -34,8 +34,8 @@ public:
|
|||
void set_save_chek_messages(bool _save_chek_messages) { save_chek_messages = _save_chek_messages; }
|
||||
|
||||
uint64_t last_timestamp_us(void) const { return last_timestamp_usec; }
|
||||
virtual bool handle_log_format_msg(const struct log_Format &f);
|
||||
virtual bool handle_msg(const struct log_Format &f, uint8_t *msg);
|
||||
bool handle_log_format_msg(const struct log_Format &f) override;
|
||||
bool handle_msg(const struct log_Format &f, uint8_t *msg) override;
|
||||
|
||||
static bool in_list(const char *type, const char *list[]);
|
||||
|
||||
|
|
|
@ -331,8 +331,8 @@ void Replay::_parse_command_line(uint8_t argc, char * const argv[])
|
|||
class IMUCounter : public AP_LoggerFileReader {
|
||||
public:
|
||||
IMUCounter() {}
|
||||
bool handle_log_format_msg(const struct log_Format &f);
|
||||
bool handle_msg(const struct log_Format &f, uint8_t *msg);
|
||||
bool handle_log_format_msg(const struct log_Format &f) override;
|
||||
bool handle_msg(const struct log_Format &f, uint8_t *msg) override;
|
||||
|
||||
uint64_t last_clock_timestamp = 0;
|
||||
float last_parm_value = 0;
|
||||
|
|
Loading…
Reference in New Issue