mirror of https://github.com/ArduPilot/ardupilot
HIL: when in HIL_MODE_ATTITUDE, we get altitude from gps setHIL
we need to skip the barometer and sonar calls git-svn-id: https://arducopter.googlecode.com/svn/trunk@2891 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
3dd3f1091e
commit
ba21d6d642
|
@ -1315,6 +1315,7 @@ static void update_alt()
|
|||
|
||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||
current_loc.alt = g_gps->altitude;
|
||||
return;
|
||||
#else
|
||||
|
||||
if(g.sonar_enabled){
|
||||
|
|
Loading…
Reference in New Issue