Tracker: Change division to multiplication
This commit is contained in:
parent
f2eb188f82
commit
38c6ae3a0e
@ -62,10 +62,10 @@ void Tracker::update_bearing_and_distance()
|
|||||||
|
|
||||||
// calculate altitude difference to vehicle using gps
|
// calculate altitude difference to vehicle using gps
|
||||||
if (g.alt_source == ALT_SOURCE_GPS){
|
if (g.alt_source == ALT_SOURCE_GPS){
|
||||||
nav_status.alt_difference_gps = (vehicle.location_estimate.alt - current_loc.alt) / 100.0f;
|
nav_status.alt_difference_gps = (vehicle.location_estimate.alt - current_loc.alt) * 0.01f;
|
||||||
} else {
|
} else {
|
||||||
// g.alt_source == ALT_SOURCE_GPS_VEH_ONLY
|
// g.alt_source == ALT_SOURCE_GPS_VEH_ONLY
|
||||||
nav_status.alt_difference_gps = vehicle.relative_alt / 100.0f;
|
nav_status.alt_difference_gps = vehicle.relative_alt * 0.01f;
|
||||||
}
|
}
|
||||||
|
|
||||||
// calculate pitch to vehicle
|
// calculate pitch to vehicle
|
||||||
@ -140,7 +140,7 @@ void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg)
|
|||||||
vehicle.location.lng = msg.lon;
|
vehicle.location.lng = msg.lon;
|
||||||
vehicle.location.alt = msg.alt/10;
|
vehicle.location.alt = msg.alt/10;
|
||||||
vehicle.relative_alt = msg.relative_alt/10;
|
vehicle.relative_alt = msg.relative_alt/10;
|
||||||
vehicle.vel = Vector3f(msg.vx/100.0f, msg.vy/100.0f, msg.vz/100.0f);
|
vehicle.vel = Vector3f(msg.vx*0.01f, msg.vy*0.01f, msg.vz*0.01f);
|
||||||
vehicle.last_update_us = AP_HAL::micros();
|
vehicle.last_update_us = AP_HAL::micros();
|
||||||
vehicle.last_update_ms = AP_HAL::millis();
|
vehicle.last_update_ms = AP_HAL::millis();
|
||||||
#if HAL_LOGGING_ENABLED
|
#if HAL_LOGGING_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user