APM:Libraries
|
#include <AP_Beacon_Backend.h>
Public Member Functions | |
AP_Beacon_Backend (AP_Beacon &frontend) | |
virtual bool | healthy ()=0 |
virtual void | update ()=0 |
void | set_vehicle_position (const Vector3f &pos, float accuracy_estimate) |
void | set_beacon_distance (uint8_t beacon_instance, float distance) |
void | set_beacon_position (uint8_t beacon_instance, const Vector3f &pos) |
float | get_beacon_origin_lat (void) const |
float | get_beacon_origin_lon (void) const |
float | get_beacon_origin_alt (void) const |
Protected Member Functions | |
Vector3f | correct_for_orient_yaw (const Vector3f &vector) |
Protected Attributes | |
AP_Beacon & | _frontend |
int16_t | orient_yaw_deg |
float | orient_cos_yaw = 0.0f |
float | orient_sin_yaw = 1.0f |
Definition at line 22 of file AP_Beacon_Backend.h.
AP_Beacon_Backend::AP_Beacon_Backend | ( | AP_Beacon & | frontend | ) |
Definition at line 24 of file AP_Beacon_Backend.cpp.
Definition at line 76 of file AP_Beacon_Backend.cpp.
Referenced by set_beacon_position(), and set_vehicle_position().
|
inline |
Definition at line 46 of file AP_Beacon_Backend.h.
Referenced by AP_Beacon_SITL::update().
|
inline |
Definition at line 44 of file AP_Beacon_Backend.h.
Referenced by AP_Beacon_SITL::update().
|
inline |
Definition at line 45 of file AP_Beacon_Backend.h.
Referenced by AP_Beacon_SITL::update().
|
pure virtual |
Implemented in AP_Beacon_Marvelmind, AP_Beacon_Pozyx, and AP_Beacon_SITL.
Referenced by AP_Beacon::healthy().
void AP_Beacon_Backend::set_beacon_distance | ( | uint8_t | beacon_instance, |
float | distance | ||
) |
Definition at line 40 of file AP_Beacon_Backend.cpp.
Referenced by AP_Beacon_Pozyx::parse_buffer(), AP_Beacon_Marvelmind::process_beacons_distances_datagram(), and AP_Beacon_SITL::update().
void AP_Beacon_Backend::set_beacon_position | ( | uint8_t | beacon_instance, |
const Vector3f & | pos | ||
) |
Definition at line 59 of file AP_Beacon_Backend.cpp.
Referenced by AP_Beacon_Pozyx::parse_buffer(), AP_Beacon_Marvelmind::set_stationary_beacons_positions(), and AP_Beacon_SITL::update().
void AP_Beacon_Backend::set_vehicle_position | ( | const Vector3f & | pos, |
float | accuracy_estimate | ||
) |
Definition at line 32 of file AP_Beacon_Backend.cpp.
Referenced by AP_Beacon_Pozyx::parse_buffer(), AP_Beacon_Marvelmind::set_stationary_beacons_positions(), and AP_Beacon_SITL::update().
|
pure virtual |
Implemented in AP_Beacon_Marvelmind, AP_Beacon_Pozyx, and AP_Beacon_SITL.
Referenced by AP_Beacon::update().
|
protected |
Definition at line 51 of file AP_Beacon_Backend.h.
Referenced by correct_for_orient_yaw(), get_beacon_origin_alt(), get_beacon_origin_lat(), get_beacon_origin_lon(), set_beacon_distance(), set_beacon_position(), and set_vehicle_position().
|
protected |
Definition at line 55 of file AP_Beacon_Backend.h.
Referenced by correct_for_orient_yaw().
|
protected |
Definition at line 56 of file AP_Beacon_Backend.h.
Referenced by correct_for_orient_yaw().
|
protected |
Definition at line 54 of file AP_Beacon_Backend.h.
Referenced by correct_for_orient_yaw().