Skip to content

Commit

Permalink
Tracker: Change division to multiplication
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura authored and peterbarker committed Jan 2, 2025
1 parent f2eb188 commit 38c6ae3
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions AntennaTracker/tracking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,10 +62,10 @@ void Tracker::update_bearing_and_distance()

// calculate altitude difference to vehicle using 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 {
// 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
Expand Down Expand Up @@ -140,7 +140,7 @@ void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg)
vehicle.location.lng = msg.lon;
vehicle.location.alt = msg.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_ms = AP_HAL::millis();
#if HAL_LOGGING_ENABLED
Expand Down

0 comments on commit 38c6ae3

Please sign in to comment.