mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Tracker: fix formatting and gps based alt difference
This commit is contained in:
parent
1293b16589
commit
68e4a83f44
@ -58,15 +58,14 @@ void Tracker::update_bearing_and_distance()
|
|||||||
nav_status.distance = get_distance(current_loc, vehicle.location_estimate);
|
nav_status.distance = get_distance(current_loc, vehicle.location_estimate);
|
||||||
|
|
||||||
// calculate altitude difference to vehicle using gps
|
// calculate altitude difference to vehicle using gps
|
||||||
nav_status.alt_difference_gps = vehicle.location.alt - current_loc.alt;
|
nav_status.alt_difference_gps = (vehicle.location.alt - current_loc.alt) / 100.0f;
|
||||||
|
|
||||||
// calculate pitch to vehicle
|
// calculate pitch to vehicle
|
||||||
// To-Do: remove need for check of control_mode
|
// To-Do: remove need for check of control_mode
|
||||||
if (control_mode != SCAN && !nav_status.manual_control_pitch) {
|
if (control_mode != SCAN && !nav_status.manual_control_pitch) {
|
||||||
if(g.alt_source == 0){
|
if (g.alt_source == 0) {
|
||||||
nav_status.pitch = degrees(atan2f(nav_status.alt_difference_baro, nav_status.distance));
|
nav_status.pitch = degrees(atan2f(nav_status.alt_difference_baro, nav_status.distance));
|
||||||
}
|
} else {
|
||||||
else{
|
|
||||||
nav_status.pitch = degrees(atan2f(nav_status.alt_difference_gps, nav_status.distance));
|
nav_status.pitch = degrees(atan2f(nav_status.alt_difference_gps, nav_status.distance));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user