mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Beacon: added units in the comments documentation, to make the API easier to use
This commit is contained in:
parent
8f7b9323d2
commit
119696bea3
@ -128,7 +128,7 @@ bool AP_Beacon::get_origin(Location &origin_loc) const
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// check for unitialised origin
|
// check for un-initialised origin
|
||||||
if (is_zero(origin_lat) && is_zero(origin_lon) && is_zero(origin_alt)) {
|
if (is_zero(origin_lat) && is_zero(origin_lon) && is_zero(origin_alt)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
@ -142,7 +142,7 @@ bool AP_Beacon::get_origin(Location &origin_loc) const
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return position in NED from position estimate system's origin
|
// return position in NED from position estimate system's origin in meters
|
||||||
bool AP_Beacon::get_vehicle_position_ned(Vector3f &position, float& accuracy_estimate) const
|
bool AP_Beacon::get_vehicle_position_ned(Vector3f &position, float& accuracy_estimate) const
|
||||||
{
|
{
|
||||||
if (!device_ready()) {
|
if (!device_ready()) {
|
||||||
@ -206,7 +206,7 @@ float AP_Beacon::beacon_distance(uint8_t beacon_instance) const
|
|||||||
return beacon_state[beacon_instance].distance;
|
return beacon_state[beacon_instance].distance;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return beacon position
|
// return beacon position in meters
|
||||||
Vector3f AP_Beacon::beacon_position(uint8_t beacon_instance) const
|
Vector3f AP_Beacon::beacon_position(uint8_t beacon_instance) const
|
||||||
{
|
{
|
||||||
if (!device_ready() || beacon_instance >= num_beacons) {
|
if (!device_ready() || beacon_instance >= num_beacons) {
|
||||||
@ -216,7 +216,7 @@ Vector3f AP_Beacon::beacon_position(uint8_t beacon_instance) const
|
|||||||
return beacon_state[beacon_instance].position;
|
return beacon_state[beacon_instance].position;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return last update time from beacon
|
// return last update time from beacon in milliseconds
|
||||||
uint32_t AP_Beacon::beacon_last_update_ms(uint8_t beacon_instance) const
|
uint32_t AP_Beacon::beacon_last_update_ms(uint8_t beacon_instance) const
|
||||||
{
|
{
|
||||||
if (_type == AP_BeaconType_None || beacon_instance >= num_beacons) {
|
if (_type == AP_BeaconType_None || beacon_instance >= num_beacons) {
|
||||||
|
@ -61,10 +61,10 @@ public:
|
|||||||
// update state of all beacons
|
// update state of all beacons
|
||||||
void update(void);
|
void update(void);
|
||||||
|
|
||||||
// return origin of position estimate system
|
// return origin of position estimate system in lat/lon
|
||||||
bool get_origin(Location &origin_loc) const;
|
bool get_origin(Location &origin_loc) const;
|
||||||
|
|
||||||
// return vehicle position in NED from position estimate system's origin
|
// return vehicle position in NED from position estimate system's origin in meters
|
||||||
bool get_vehicle_position_ned(Vector3f& pos, float& accuracy_estimate) const;
|
bool get_vehicle_position_ned(Vector3f& pos, float& accuracy_estimate) const;
|
||||||
|
|
||||||
// return the number of beacons
|
// return the number of beacons
|
||||||
@ -84,10 +84,10 @@ public:
|
|||||||
// return distance to beacon in meters
|
// return distance to beacon in meters
|
||||||
float beacon_distance(uint8_t beacon_instance) const;
|
float beacon_distance(uint8_t beacon_instance) const;
|
||||||
|
|
||||||
// return NED position of beacon relative to the beacon systems origin
|
// return NED position of beacon in meters relative to the beacon systems origin
|
||||||
Vector3f beacon_position(uint8_t beacon_instance) const;
|
Vector3f beacon_position(uint8_t beacon_instance) const;
|
||||||
|
|
||||||
// return last update time from beacon
|
// return last update time from beacon in milliseconds
|
||||||
uint32_t beacon_last_update_ms(uint8_t beacon_instance) const;
|
uint32_t beacon_last_update_ms(uint8_t beacon_instance) const;
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
@ -26,7 +26,9 @@ AP_Beacon_Backend::AP_Beacon_Backend(AP_Beacon &frontend) :
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
// set vehicle position, pos should be in the beacon's local frame
|
// set vehicle position:
|
||||||
|
// pos should be in the beacon's local frame in meters
|
||||||
|
// accuracy_estimate is also in meters
|
||||||
void AP_Beacon_Backend::set_vehicle_position(const Vector3f& pos, float accuracy_estimate)
|
void AP_Beacon_Backend::set_vehicle_position(const Vector3f& pos, float accuracy_estimate)
|
||||||
{
|
{
|
||||||
_frontend.veh_pos_update_ms = AP_HAL::millis();
|
_frontend.veh_pos_update_ms = AP_HAL::millis();
|
||||||
@ -53,7 +55,7 @@ void AP_Beacon_Backend::set_beacon_distance(uint8_t beacon_instance, float dista
|
|||||||
}
|
}
|
||||||
|
|
||||||
// configure beacon's position in meters from origin
|
// configure beacon's position in meters from origin
|
||||||
// pos should be in the beacon's local frame
|
// pos should be in the beacon's local frame (meters)
|
||||||
void AP_Beacon_Backend::set_beacon_position(uint8_t beacon_instance, const Vector3f& pos)
|
void AP_Beacon_Backend::set_beacon_position(uint8_t beacon_instance, const Vector3f& pos)
|
||||||
{
|
{
|
||||||
// sanity check instance
|
// sanity check instance
|
||||||
@ -70,7 +72,7 @@ void AP_Beacon_Backend::set_beacon_position(uint8_t beacon_instance, const Vecto
|
|||||||
_frontend.beacon_state[beacon_instance].position = correct_for_orient_yaw(pos);
|
_frontend.beacon_state[beacon_instance].position = correct_for_orient_yaw(pos);
|
||||||
}
|
}
|
||||||
|
|
||||||
// rotate vector to correct for beacon system yaw orientation
|
// rotate vector (meters) to correct for beacon system yaw orientation
|
||||||
Vector3f AP_Beacon_Backend::correct_for_orient_yaw(const Vector3f &vector)
|
Vector3f AP_Beacon_Backend::correct_for_orient_yaw(const Vector3f &vector)
|
||||||
{
|
{
|
||||||
// exit immediately if no correction
|
// exit immediately if no correction
|
||||||
|
Loading…
Reference in New Issue
Block a user