Browse Source

Tracker: use enum class for AltFrame enumeration

mission-4.1.18
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
6e67481355
  1. 8
      AntennaTracker/GCS_Mavlink.cpp
  2. 2
      AntennaTracker/system.cpp

8
AntennaTracker/GCS_Mavlink.cpp

@ -457,7 +457,7 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
int32_t(1.0e7f*packet.x), // in as DD converted to * t7 int32_t(1.0e7f*packet.x), // in as DD converted to * t7
int32_t(1.0e7f*packet.y), // in as DD converted to * t7 int32_t(1.0e7f*packet.y), // in as DD converted to * t7
int32_t(packet.z*1.0e2f), // in as m converted to cm int32_t(packet.z*1.0e2f), // in as m converted to cm
Location::ALT_FRAME_ABSOLUTE Location::AltFrame::ABSOLUTE
}; };
break; break;
} }
@ -469,7 +469,7 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
int32_t(1.0e7f*ToDeg(packet.x/(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat), int32_t(1.0e7f*ToDeg(packet.x/(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat),
int32_t(1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng), int32_t(1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng),
int32_t(-packet.z*1.0e2f), int32_t(-packet.z*1.0e2f),
Location::ALT_FRAME_ABOVE_HOME Location::AltFrame::ABOVE_HOME
}; };
break; break;
} }
@ -482,7 +482,7 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
int32_t(1.0e7f*ToDeg(packet.x/(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat), int32_t(1.0e7f*ToDeg(packet.x/(RADIUS_OF_EARTH*cosf(ToRad(home.lat/1.0e7f)))) + home.lat),
int32_t(1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng), int32_t(1.0e7f*ToDeg(packet.y/RADIUS_OF_EARTH) + home.lng),
int32_t(packet.z*1.0e2f), int32_t(packet.z*1.0e2f),
Location::ALT_FRAME_ABOVE_HOME Location::AltFrame::ABOVE_HOME
}; };
break; break;
} }
@ -494,7 +494,7 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
int32_t(1.0e7f * packet.x), // in as DD converted to * t7 int32_t(1.0e7f * packet.x), // in as DD converted to * t7
int32_t(1.0e7f * packet.y), // in as DD converted to * t7 int32_t(1.0e7f * packet.y), // in as DD converted to * t7
int32_t(packet.z * 1.0e2f), int32_t(packet.z * 1.0e2f),
Location::ALT_FRAME_ABOVE_HOME Location::AltFrame::ABOVE_HOME
}; };
break; break;
} }

2
AntennaTracker/system.cpp

@ -146,7 +146,7 @@ bool Tracker::get_home_eeprom(struct Location &loc)
int32_t(wp_storage.read_uint32(5)), int32_t(wp_storage.read_uint32(5)),
int32_t(wp_storage.read_uint32(9)), int32_t(wp_storage.read_uint32(9)),
int32_t(wp_storage.read_uint32(1)), int32_t(wp_storage.read_uint32(1)),
Location::ALT_FRAME_ABSOLUTE Location::AltFrame::ABSOLUTE
}; };
return true; return true;

Loading…
Cancel
Save