APM:Libraries
|
#include <AC_PrecLand_Companion.h>
Public Member Functions | |
AC_PrecLand_Companion (const AC_PrecLand &frontend, AC_PrecLand::precland_state &state) | |
void | init () override |
void | update () override |
bool | get_los_body (Vector3f &ret) override |
uint32_t | los_meas_time_ms () override |
bool | have_los_meas () override |
float | distance_to_target () override |
void | handle_msg (mavlink_message_t *msg) override |
![]() | |
AC_PrecLand_Backend (const AC_PrecLand &frontend, AC_PrecLand::precland_state &state) | |
virtual | ~AC_PrecLand_Backend () |
int8_t | get_bus (void) const |
Private Attributes | |
uint64_t | _timestamp_us |
float | _distance_to_target |
Vector3f | _los_meas_body |
bool | _have_los_meas |
uint32_t | _los_meas_time_ms |
Additional Inherited Members | |
![]() | |
const AC_PrecLand & | _frontend |
AC_PrecLand::precland_state & | _state |
Definition at line 12 of file AC_PrecLand_Companion.h.
AC_PrecLand_Companion::AC_PrecLand_Companion | ( | const AC_PrecLand & | frontend, |
AC_PrecLand::precland_state & | state | ||
) |
Definition at line 7 of file AC_PrecLand_Companion.cpp.
|
overridevirtual |
Reimplemented from AC_PrecLand_Backend.
Definition at line 52 of file AC_PrecLand_Companion.cpp.
|
overridevirtual |
Implements AC_PrecLand_Backend.
Definition at line 32 of file AC_PrecLand_Companion.cpp.
|
overridevirtual |
Reimplemented from AC_PrecLand_Backend.
Definition at line 57 of file AC_PrecLand_Companion.cpp.
|
overridevirtual |
Implements AC_PrecLand_Backend.
Definition at line 46 of file AC_PrecLand_Companion.cpp.
Referenced by get_los_body().
|
overridevirtual |
Implements AC_PrecLand_Backend.
Definition at line 17 of file AC_PrecLand_Companion.cpp.
|
overridevirtual |
Implements AC_PrecLand_Backend.
Definition at line 41 of file AC_PrecLand_Companion.cpp.
|
overridevirtual |
Implements AC_PrecLand_Backend.
Definition at line 25 of file AC_PrecLand_Companion.cpp.
|
private |
Definition at line 42 of file AC_PrecLand_Companion.h.
Referenced by distance_to_target(), and handle_msg().
|
private |
Definition at line 45 of file AC_PrecLand_Companion.h.
Referenced by handle_msg(), have_los_meas(), init(), and update().
|
private |
Definition at line 44 of file AC_PrecLand_Companion.h.
Referenced by get_los_body(), and handle_msg().
|
private |
Definition at line 46 of file AC_PrecLand_Companion.h.
Referenced by handle_msg(), los_meas_time_ms(), and update().
|
private |
Definition at line 41 of file AC_PrecLand_Companion.h.
Referenced by handle_msg().