mirror of https://github.com/ArduPilot/ardupilot
HIL: fixed altitude calculation
ACM uses a zero home altitude, so we need an offset when using GPS for altitude git-svn-id: https://arducopter.googlecode.com/svn/trunk@2910 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
60bf2182e4
commit
98980d6f61
|
@ -171,7 +171,7 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
|
||||||
AP_GPS_HIL g_gps_driver(NULL);
|
AP_GPS_HIL g_gps_driver(NULL);
|
||||||
AP_Compass_HIL compass; // never used
|
AP_Compass_HIL compass; // never used
|
||||||
AP_IMU_Shim imu; // never used
|
AP_IMU_Shim imu; // never used
|
||||||
|
static int32_t gps_base_alt;
|
||||||
#else
|
#else
|
||||||
#error Unrecognised HIL_MODE setting.
|
#error Unrecognised HIL_MODE setting.
|
||||||
#endif // HIL MODE
|
#endif // HIL MODE
|
||||||
|
@ -1314,7 +1314,7 @@ static void update_alt()
|
||||||
altitude_sensor = BARO;
|
altitude_sensor = BARO;
|
||||||
|
|
||||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||||
current_loc.alt = g_gps->altitude;
|
current_loc.alt = g_gps->altitude - gps_base_alt;
|
||||||
return;
|
return;
|
||||||
#else
|
#else
|
||||||
|
|
||||||
|
|
|
@ -899,9 +899,15 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
// set gps hil sensor
|
// set gps hil sensor
|
||||||
g_gps->setHIL(packet.usec/1000.0,packet.lat,packet.lon,packet.alt,
|
g_gps->setHIL(packet.usec/1000.0,packet.lat,packet.lon,packet.alt,
|
||||||
packet.v,packet.hdg,0,0);
|
packet.v,packet.hdg,0,0);
|
||||||
|
if (gps_base_alt == 0) {
|
||||||
|
gps_base_alt = packet.alt*100;
|
||||||
|
}
|
||||||
current_loc.lng = packet.lon * T7;
|
current_loc.lng = packet.lon * T7;
|
||||||
current_loc.lat = packet.lat * T7;
|
current_loc.lat = packet.lat * T7;
|
||||||
current_loc.alt = packet.alt * 10;
|
current_loc.alt = g_gps->altitude - gps_base_alt;
|
||||||
|
if (!home_is_set) {
|
||||||
|
init_home();
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||||
|
|
Loading…
Reference in New Issue