mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_PrecLand: Move accessors code to the .h file
This commit is contained in:
parent
4d7fc1fe46
commit
87435473b5
@ -30,23 +30,6 @@ bool AC_PrecLand_Companion::get_los_body(Vector3f& ret) {
|
|||||||
return false;
|
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)
|
void AC_PrecLand_Companion::handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
|
||||||
{
|
{
|
||||||
_distance_to_target = packet.distance;
|
_distance_to_target = packet.distance;
|
||||||
|
@ -31,13 +31,13 @@ public:
|
|||||||
bool get_los_body(Vector3f& ret) override;
|
bool get_los_body(Vector3f& ret) override;
|
||||||
|
|
||||||
// returns system time in milliseconds of last los measurement
|
// 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
|
// 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)
|
// 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
|
// parses a mavlink message from the companion computer
|
||||||
void handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
|
void handle_msg(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
|
||||||
|
@ -45,14 +45,4 @@ bool AC_PrecLand_IRLock::get_los_body(Vector3f& ret) {
|
|||||||
return false;
|
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
|
#endif // AC_PRECLAND_IRLOCK_ENABLED
|
||||||
|
@ -36,10 +36,10 @@ public:
|
|||||||
bool get_los_body(Vector3f& ret) override;
|
bool get_los_body(Vector3f& ret) override;
|
||||||
|
|
||||||
// returns system time in milliseconds of last los measurement
|
// 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
|
// 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:
|
private:
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
@ -45,14 +45,4 @@ bool AC_PrecLand_SITL_Gazebo::get_los_body(Vector3f& ret) {
|
|||||||
return false;
|
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
|
#endif // AC_PRECLAND_SITL_GAZEBO_ENABLED
|
||||||
|
@ -31,10 +31,10 @@ public:
|
|||||||
bool get_los_body(Vector3f& ret) override;
|
bool get_los_body(Vector3f& ret) override;
|
||||||
|
|
||||||
// returns system time in milliseconds of last los measurement
|
// 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
|
// 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:
|
private:
|
||||||
AP_IRLock_SITL_Gazebo irlock;
|
AP_IRLock_SITL_Gazebo irlock;
|
||||||
|
Loading…
Reference in New Issue
Block a user