mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Beacon: update comments to clarify frame
also minor formatting fix
This commit is contained in:
parent
716e7622be
commit
276e56e618
@ -26,8 +26,8 @@ AP_Beacon_Backend::AP_Beacon_Backend(AP_Beacon &frontend) :
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
// set vehicle position:
|
// set vehicle position
|
||||||
// pos should be in the beacon's local frame in meters
|
// pos should be in meters in NED frame from the beacon's local origin
|
||||||
// accuracy_estimate is also 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)
|
||||||
{
|
{
|
||||||
@ -36,7 +36,7 @@ void AP_Beacon_Backend::set_vehicle_position(const Vector3f& pos, float accuracy
|
|||||||
_frontend.veh_pos_ned = correct_for_orient_yaw(pos);
|
_frontend.veh_pos_ned = correct_for_orient_yaw(pos);
|
||||||
}
|
}
|
||||||
|
|
||||||
// set individual beacon distance in meters
|
// set individual beacon distance from vehicle in meters in NED frame
|
||||||
void AP_Beacon_Backend::set_beacon_distance(uint8_t beacon_instance, float distance)
|
void AP_Beacon_Backend::set_beacon_distance(uint8_t beacon_instance, float distance)
|
||||||
{
|
{
|
||||||
// sanity check instance
|
// sanity check instance
|
||||||
@ -54,8 +54,8 @@ void AP_Beacon_Backend::set_beacon_distance(uint8_t beacon_instance, float dista
|
|||||||
_frontend.beacon_state[beacon_instance].healthy = true;
|
_frontend.beacon_state[beacon_instance].healthy = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// configure beacon's position in meters from origin
|
// set beacon's position
|
||||||
// pos should be in the beacon's local frame (meters)
|
// pos should be in meters in NED from the beacon's local origin
|
||||||
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
|
||||||
|
@ -31,14 +31,16 @@ public:
|
|||||||
// update
|
// update
|
||||||
virtual void update() = 0;
|
virtual void update() = 0;
|
||||||
|
|
||||||
// set vehicle position, pos should be in the beacon's local frame
|
// set vehicle position
|
||||||
|
// pos should be in meters in NED frame from the beacon's local origin
|
||||||
|
// accuracy_estimate is also in meters
|
||||||
void set_vehicle_position(const Vector3f& pos, float accuracy_estimate);
|
void set_vehicle_position(const Vector3f& pos, float accuracy_estimate);
|
||||||
|
|
||||||
// set individual beacon distance in meters
|
// set individual beacon distance from vehicle in meters in NED frame
|
||||||
void set_beacon_distance(uint8_t beacon_instance, float distance);
|
void set_beacon_distance(uint8_t beacon_instance, float distance);
|
||||||
|
|
||||||
// configure beacon's position in meters from origin
|
// set beacon's position
|
||||||
// pos should be in the beacon's local frame
|
// pos should be in meters in NED from the beacon's local origin
|
||||||
void set_beacon_position(uint8_t beacon_instance, const Vector3f& pos);
|
void set_beacon_position(uint8_t beacon_instance, const Vector3f& pos);
|
||||||
|
|
||||||
float get_beacon_origin_lat(void) const { return _frontend.origin_lat; }
|
float get_beacon_origin_lat(void) const { return _frontend.origin_lat; }
|
||||||
|
@ -108,7 +108,6 @@ void AP_Beacon_SITL::update(void)
|
|||||||
set_beacon_distance(beacon_id, beac_veh_offset.length());
|
set_beacon_distance(beacon_id, beac_veh_offset.length());
|
||||||
set_vehicle_position(veh_pos3d, 0.5f);
|
set_vehicle_position(veh_pos3d, 0.5f);
|
||||||
last_update_ms = now;
|
last_update_ms = now;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD
|
#endif // CONFIG_HAL_BOARD
|
||||||
|
Loading…
Reference in New Issue
Block a user