mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: add missing override keywords
This commit is contained in:
parent
5aa5add4bf
commit
166291cfef
@ -27,7 +27,7 @@ public:
|
||||
BalanceBot(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -30,7 +30,7 @@ public:
|
||||
Balloon(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -32,7 +32,7 @@ public:
|
||||
CRRCSim(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -66,7 +66,7 @@ class Calibration : public Aircraft {
|
||||
public:
|
||||
Calibration(const char *home_str, const char *frame_str);
|
||||
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
return new Calibration(home_str, frame_str);
|
||||
|
@ -32,7 +32,7 @@ public:
|
||||
FlightAxis(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -31,7 +31,7 @@ public:
|
||||
Gazebo(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
@ -39,7 +39,7 @@ public:
|
||||
}
|
||||
|
||||
/* Create and set in/out socket for Gazebo simulator */
|
||||
void set_interface_ports(const char* address, const int port_in, const int port_out);
|
||||
void set_interface_ports(const char* address, const int port_in, const int port_out) override;
|
||||
|
||||
private:
|
||||
/*
|
||||
|
@ -30,7 +30,7 @@ public:
|
||||
Helicopter(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -32,7 +32,7 @@ public:
|
||||
JSBSim(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -31,7 +31,7 @@ public:
|
||||
Morse(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -32,7 +32,7 @@ public:
|
||||
MultiCopter(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -32,7 +32,7 @@ public:
|
||||
Plane(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
virtual void update(const struct sitl_input &input);
|
||||
virtual void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -30,7 +30,7 @@ public:
|
||||
SimRover(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -30,7 +30,7 @@ public:
|
||||
Sailboat(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -31,7 +31,7 @@ public:
|
||||
SingleCopter(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -28,7 +28,7 @@ namespace SITL {
|
||||
class Tracker : public Aircraft {
|
||||
public:
|
||||
Tracker(const char *home_str, const char *frame_str);
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -32,7 +32,7 @@ public:
|
||||
XPlane(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
@ -32,7 +32,7 @@ public:
|
||||
last_letter(const char *home_str, const char *frame_str);
|
||||
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input);
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *home_str, const char *frame_str) {
|
||||
|
Loading…
Reference in New Issue
Block a user