AC_PrecLand: Move accessors code to the .h file

This commit is contained in:
Dr.-Ing. Amilcar do Carmo Lucas 2024-02-15 14:25:44 +01:00 committed by Andrew Tridgell
parent 4d7fc1fe46
commit 87435473b5
6 changed files with 7 additions and 44 deletions

View File

@ -30,23 +30,6 @@ bool AC_PrecLand_Companion::get_los_body(Vector3f& ret) {
return false;
}
// returns system time in milliseconds of last los measurement
uint32_t AC_PrecLand_Companion::los_meas_time_ms() {
return _los_meas_time_ms;
}
// return true if there is a valid los measurement available
bool AC_PrecLand_Companion::have_los_meas()
{
return _have_los_meas;
}
// return distance to target
float AC_PrecLand_Companion::distance_to_target()
{
return _distance_to_target;
}
void AC_PrecLand_Companion::handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
{
_distance_to_target = packet.distance;

View File

@ -31,13 +31,13 @@ public:
bool get_los_body(Vector3f& ret) override;
// returns system time in milliseconds of last los measurement
uint32_t los_meas_time_ms() override;
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() override;
bool have_los_meas() override { return _have_los_meas; }
// returns distance to target in meters (0 means distance is not known)
float distance_to_target() override;
float distance_to_target() override { return _distance_to_target; }
// parses a mavlink message from the companion computer
void handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;

View File

@ -45,14 +45,4 @@ bool AC_PrecLand_IRLock::get_los_body(Vector3f& ret) {
return false;
}
// returns system time in milliseconds of last los measurement
uint32_t AC_PrecLand_IRLock::los_meas_time_ms() {
return _los_meas_time_ms;
}
// return true if there is a valid los measurement available
bool AC_PrecLand_IRLock::have_los_meas() {
return _have_los_meas;
}
#endif // AC_PRECLAND_IRLOCK_ENABLED

View File

@ -36,10 +36,10 @@ public:
bool get_los_body(Vector3f& ret) override;
// returns system time in milliseconds of last los measurement
uint32_t los_meas_time_ms() override;
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() override;
bool have_los_meas() override { return _have_los_meas; }
private:
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL

View File

@ -45,14 +45,4 @@ bool AC_PrecLand_SITL_Gazebo::get_los_body(Vector3f& ret) {
return false;
}
// returns system time in milliseconds of last los measurement
uint32_t AC_PrecLand_SITL_Gazebo::los_meas_time_ms() {
return _los_meas_time_ms;
}
// return true if there is a valid los measurement available
bool AC_PrecLand_SITL_Gazebo::have_los_meas() {
return _have_los_meas;
}
#endif // AC_PRECLAND_SITL_GAZEBO_ENABLED

View File

@ -31,10 +31,10 @@ public:
bool get_los_body(Vector3f& ret) override;
// returns system time in milliseconds of last los measurement
uint32_t los_meas_time_ms() override;
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() override;
bool have_los_meas() override { return _have_los_meas; }
private:
AP_IRLock_SITL_Gazebo irlock;