SITL: add missing override keywords

This commit is contained in:
Peter Barker 2019-02-22 10:12:05 +11:00 committed by Francisco Ferreira
parent 5aa5add4bf
commit 166291cfef
17 changed files with 18 additions and 18 deletions

View File

@ -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) {

View File

@ -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) {

View File

@ -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) {

View File

@ -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);

View File

@ -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) {

View File

@ -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:
/*

View File

@ -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) {

View File

@ -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) {

View File

@ -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) {

View File

@ -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) {

View File

@ -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) {

View File

@ -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) {

View File

@ -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) {

View File

@ -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) {

View File

@ -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) {

View File

@ -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) {

View File

@ -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) {