Tracker: Changing name of altitude_difference to alt_difference_baro

This commit is contained in:
stefanlynka 2016-05-24 17:31:59 +09:00 committed by Randy Mackay
parent 600c23f3bf
commit fd61a903f9
3 changed files with 6 additions and 6 deletions

View File

@ -134,7 +134,7 @@ void Tracker::send_nav_controller_output(mavlink_channel_t chan)
nav_status.bearing,
nav_status.bearing,
nav_status.distance,
nav_status.altitude_difference,
nav_status.alt_difference_baro,
0,
0);
}

View File

@ -159,7 +159,7 @@ private:
float bearing; // bearing to vehicle in centi-degrees
float distance; // distance to vehicle in meters
float pitch; // pitch to vehicle in degrees (positive means vehicle is above tracker, negative means below)
float altitude_difference; // altitude difference between tracker and vehicle in meters. positive value means vehicle is above tracker
float alt_difference_baro; // altitude difference between tracker and vehicle in meters. positive value means vehicle is above tracker
float altitude_offset; // offset in meters which is added to tracker altitude to align altitude measurements with vehicle's barometer
bool manual_control_yaw : 1;// true if tracker yaw is under manual control
bool manual_control_pitch : 1;// true if tracker pitch is manually controlled

View File

@ -60,7 +60,7 @@ void Tracker::update_bearing_and_distance()
// calculate pitch to vehicle
// To-Do: remove need for check of control_mode
if (control_mode != SCAN && !nav_status.manual_control_pitch) {
nav_status.pitch = degrees(atan2f(nav_status.altitude_difference, nav_status.distance));
nav_status.pitch = degrees(atan2f(nav_status.alt_difference_baro, nav_status.distance));
}
}
@ -140,14 +140,14 @@ void Tracker::tracking_update_pressure(const mavlink_scaled_pressure_t &msg)
// calculate altitude difference based on difference in barometric pressure
float alt_diff = barometer.get_altitude_difference(local_pressure, aircraft_pressure);
if (!isnan(alt_diff)) {
nav_status.altitude_difference = alt_diff + nav_status.altitude_offset;
nav_status.alt_difference_baro = alt_diff + nav_status.altitude_offset;
}
if (nav_status.need_altitude_calibration) {
// we have done a baro calibration - zero the altitude
// difference to the aircraft
nav_status.altitude_offset = -nav_status.altitude_difference;
nav_status.altitude_difference = 0;
nav_status.altitude_offset = -nav_status.alt_difference_baro;
nav_status.alt_difference_baro = 0;
nav_status.need_altitude_calibration = false;
}