diff --git a/libraries/AC_PrecLand/AC_PrecLand_Backend.h b/libraries/AC_PrecLand/AC_PrecLand_Backend.h index aed43860e7..77c1e36729 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Backend.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Backend.h @@ -26,10 +26,10 @@ public: // provides a unit vector towards the target in body frame // returns same as have_los_meas() virtual bool get_los_body(Vector3f& dir_body) = 0; - + // returns system time in milliseconds of last los measurement virtual uint32_t los_meas_time_ms() = 0; - + // return true if there is a valid los measurement available virtual bool have_los_meas() = 0; diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp index f0daee4de2..05c2122950 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp @@ -53,7 +53,7 @@ float AC_PrecLand_Companion::distance_to_target() { return _distance_to_target; } - + void AC_PrecLand_Companion::handle_msg(mavlink_message_t* msg) { // parse mavlink message @@ -62,11 +62,11 @@ void AC_PrecLand_Companion::handle_msg(mavlink_message_t* msg) _timestamp_us = packet.time_usec; _distance_to_target = packet.distance; - + // compute unit vector towards target _los_meas_body = Vector3f(-tanf(packet.angle_y), tanf(packet.angle_x), 1.0f); _los_meas_body /= _los_meas_body.length(); - + _los_meas_time_ms = AP_HAL::millis(); _have_los_meas = true; } diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.h b/libraries/AC_PrecLand/AC_PrecLand_Companion.h index 1a2e0f604f..5b45e03e09 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.h @@ -14,33 +14,33 @@ class AC_PrecLand_Companion : public AC_PrecLand_Backend public: // Constructor AC_PrecLand_Companion(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); - + // perform any required initialisation of backend - void init(); + void init() override; // retrieve updates from sensor - void update(); + void update() override; // provides a unit vector towards the target in body frame // returns same as have_los_meas() - bool get_los_body(Vector3f& ret); - + bool get_los_body(Vector3f& ret) override; + // returns system time in milliseconds of last los measurement - uint32_t los_meas_time_ms(); - + uint32_t los_meas_time_ms() override; + // return true if there is a valid los measurement available - bool have_los_meas(); - + bool have_los_meas() override; + // returns distance to target in meters (0 means distance is not known) float distance_to_target() override; // parses a mavlink message from the companion computer - void handle_msg(mavlink_message_t* msg); + void handle_msg(mavlink_message_t* msg) override; private: uint64_t _timestamp_us; // timestamp from message float _distance_to_target; // distance from the camera to target in meters - + Vector3f _los_meas_body; // unit vector in body frame pointing towards target bool _have_los_meas; // true if there is a valid measurement from the camera uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h index 8c43dac849..61de6484ab 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -23,22 +23,22 @@ public: // Constructor AC_PrecLand_IRLock(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); - + // perform any required initialisation of backend - void init(); + void init() override; // retrieve updates from sensor - void update(); + void update() override; // provides a unit vector towards the target in body frame // returns same as have_los_meas() - bool get_los_body(Vector3f& ret); - + bool get_los_body(Vector3f& ret) override; + // returns system time in milliseconds of last los measurement - uint32_t los_meas_time_ms(); - + uint32_t los_meas_time_ms() override; + // return true if there is a valid los measurement available - bool have_los_meas(); + bool have_los_meas() override; private: AP_IRLock_I2C irlock; diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL.h b/libraries/AC_PrecLand/AC_PrecLand_SITL.h index c9ff394d12..a062f7127c 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL.h +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL.h @@ -17,20 +17,20 @@ public: AC_PrecLand_SITL(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); // perform any required initialisation of backend - void init(); + void init() override; // retrieve updates from sensor - void update(); + void update() override; // provides a unit vector towards the target in body frame // returns same as have_los_meas() - bool get_los_body(Vector3f& ret); + bool get_los_body(Vector3f& ret) override; // returns system time in milliseconds of last los measurement - uint32_t los_meas_time_ms() { return _los_meas_time_ms; } + uint32_t los_meas_time_ms() override { return _los_meas_time_ms; } // return true if there is a valid los measurement available - bool have_los_meas(); + bool have_los_meas() override; private: diff --git a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h index 207b04bf32..2e556d9a22 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h +++ b/libraries/AC_PrecLand/AC_PrecLand_SITL_Gazebo.h @@ -19,20 +19,20 @@ public: AC_PrecLand_SITL_Gazebo(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state); // perform any required initialisation of backend - void init(); + void init() override; // retrieve updates from sensor - void update(); + void update() override; // provides a unit vector towards the target in body frame // returns same as have_los_meas() - bool get_los_body(Vector3f& ret); + bool get_los_body(Vector3f& ret) override; // returns system time in milliseconds of last los measurement - uint32_t los_meas_time_ms(); + uint32_t los_meas_time_ms() override; // return true if there is a valid los measurement available - bool have_los_meas(); + bool have_los_meas() override; private: AP_IRLock_SITL irlock;