Browse Source

AntennaTracker: adjust for changed logging APIs

master
Andrew Tridgell 9 years ago
parent
commit
71b121837a
  1. 1
      AntennaTracker/AntennaTracker.cpp
  2. 2
      AntennaTracker/sensors.cpp
  3. 2
      AntennaTracker/tracking.cpp

1
AntennaTracker/AntennaTracker.cpp

@ -120,7 +120,6 @@ void Tracker::ten_hz_logging_loop() @@ -120,7 +120,6 @@ void Tracker::ten_hz_logging_loop()
{
if (should_log(MASK_LOG_IMU)) {
DataFlash.Log_Write_IMU(ins);
DataFlash.Log_Write_IMUDT(ins);
}
if (should_log(MASK_LOG_ATTITUDE)) {
Log_Write_Attitude();

2
AntennaTracker/sensors.cpp

@ -126,7 +126,7 @@ void Tracker::update_GPS(void) @@ -126,7 +126,7 @@ void Tracker::update_GPS(void)
// log GPS data
if (should_log(MASK_LOG_GPS)) {
DataFlash.Log_Write_GPS(gps, 0, current_loc.alt);
DataFlash.Log_Write_GPS(gps, 0);
}
}
}

2
AntennaTracker/tracking.cpp

@ -124,7 +124,7 @@ void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg) @@ -124,7 +124,7 @@ void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg)
// log vehicle as GPS2
if (should_log(MASK_LOG_GPS)) {
DataFlash.Log_Write_GPS(gps, 1, vehicle.location.alt);
DataFlash.Log_Write_GPS(gps, 1);
}
}

Loading…
Cancel
Save