Browse Source

Copter: correct nullptr dereference in sensor-config error loop

master
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
332e878bae
  1. 3
      ArduCopter/GCS_Mavlink.cpp

3
ArduCopter/GCS_Mavlink.cpp

@ -173,6 +173,9 @@ void GCS_MAVLINK_Copter::send_nav_controller_output() const @@ -173,6 +173,9 @@ void GCS_MAVLINK_Copter::send_nav_controller_output() const
int16_t GCS_MAVLINK_Copter::vfr_hud_throttle() const
{
if (copter.motors == nullptr) {
return 0;
}
return (int16_t)(copter.motors->get_throttle() * 100);
}

Loading…
Cancel
Save