Plane: enable attitude and raw logging in HIL modes

This commit is contained in:
Andrew Tridgell 2012-12-04 11:13:33 +11:00
parent dfc252a78d
commit 3bac27b97f
7 changed files with 18 additions and 38 deletions

View File

@ -240,15 +240,11 @@ AP_InertialSensor_Stub ins;
AP_AHRS_DCM ahrs(&ins, g_gps);
#elif HIL_MODE == HIL_MODE_ATTITUDE
AP_InertialSensor_Stub ins;
AP_AHRS_HIL ahrs(&ins, g_gps);
AP_GPS_HIL g_gps_driver(NULL);
AP_Compass_HIL compass; // never used
AP_Baro_BMP085_HIL barometer;
#ifdef DESKTOP_BUILD
#include <SITL.h>
SITL sitl;
#endif
AP_Compass_HIL compass;
AP_GPS_HIL g_gps_driver(NULL);
AP_InertialSensor_Stub ins;
AP_AHRS_HIL ahrs(&ins, g_gps);
#else
#error Unrecognised HIL_MODE setting.
@ -718,10 +714,7 @@ void loop()
if (millis() - perf_mon_timer > 20000) {
if (mainLoop_count != 0) {
if (g.log_bitmask & MASK_LOG_PM)
#if HIL_MODE != HIL_MODE_ATTITUDE
Log_Write_Performance();
#endif
resetPerfData();
}
}
@ -769,13 +762,11 @@ static void fast_loop()
// uses the yaw from the DCM to give more accurate turns
calc_bearing_error();
# if HIL_MODE == HIL_MODE_DISABLED
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST)
Log_Write_Attitude(ahrs.roll_sensor, ahrs.pitch_sensor, ahrs.yaw_sensor);
if (g.log_bitmask & MASK_LOG_RAW)
Log_Write_Raw();
#endif
// inertial navigation
// ------------------
@ -886,13 +877,11 @@ static void medium_loop()
case 3:
medium_loopCounter++;
#if HIL_MODE != HIL_MODE_ATTITUDE
if ((g.log_bitmask & MASK_LOG_ATTITUDE_MED) && !(g.log_bitmask & MASK_LOG_ATTITUDE_FAST))
Log_Write_Attitude(ahrs.roll_sensor, ahrs.pitch_sensor, ahrs.yaw_sensor);
if (g.log_bitmask & MASK_LOG_CTUN)
Log_Write_Control_Tuning();
#endif
if (g.log_bitmask & MASK_LOG_NTUN)
Log_Write_Nav_Tuning();

View File

@ -379,7 +379,6 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
barometer.get_climb_rate());
}
#if HIL_MODE != HIL_MODE_ATTITUDE
static void NOINLINE send_raw_imu1(mavlink_channel_t chan)
{
Vector3f accel = ins.get_accel();
@ -445,8 +444,6 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
ahrs.get_error_yaw());
}
#endif // HIL_MODE != HIL_MODE_ATTITUDE
#ifdef DESKTOP_BUILD
// report simulator state
static void NOINLINE send_simstate(mavlink_channel_t chan)
@ -587,7 +584,6 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
send_vfr_hud(chan);
break;
#if HIL_MODE != HIL_MODE_ATTITUDE
case MSG_RAW_IMU1:
CHECK_PAYLOAD_SIZE(RAW_IMU);
send_raw_imu1(chan);
@ -602,7 +598,6 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
send_raw_imu3(chan);
break;
#endif // HIL_MODE != HIL_MODE_ATTITUDE
case MSG_CURRENT_WAYPOINT:
CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
@ -640,10 +635,8 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
#endif
case MSG_AHRS:
#if HIL_MODE != HIL_MODE_ATTITUDE
CHECK_PAYLOAD_SIZE(AHRS);
send_ahrs(chan);
#endif
break;
case MSG_SIMSTATE:
@ -1803,7 +1796,6 @@ mission_failed:
packet.lat*1.0e-7, packet.lon*1.0e-7, packet.alt*1.0e-3,
vel*1.0e-2, cog*1.0e-2, 0, 10);
#if HIL_MODE == HIL_MODE_SENSORS
// rad/sec
Vector3f gyros;
@ -1831,9 +1823,9 @@ mission_failed:
barometer.setHIL(Temp, y);
#else
// set AHRS hil sensor
#if HIL_MODE == HIL_MODE_ATTITUDE
// set AHRS hil sensor. We don't do this in sensors mode, as
// in that case the attitude is computed via DCM
ahrs.setHil(packet.roll,packet.pitch,packet.yaw,packet.rollspeed,
packet.pitchspeed,packet.yawspeed);

View File

@ -222,7 +222,6 @@ static void Log_Write_Attitude(int16_t log_roll, int16_t log_pitch, uint16_t log
}
// Write a performance monitoring packet. Total length : 19 bytes
#if HIL_MODE != HIL_MODE_ATTITUDE
static void Log_Write_Performance()
{
DataFlash.WriteByte(HEAD_BYTE1);
@ -243,7 +242,6 @@ static void Log_Write_Performance()
DataFlash.WriteInt(pmTest1);
DataFlash.WriteByte(END_BYTE);
}
#endif
// Write a command processing packet. Total length : 19 bytes
//void Log_Write_Cmd(byte num, byte id, byte p1, int32_t alt, int32_t lat, int32_t lng)
@ -282,7 +280,6 @@ static void Log_Write_Startup(byte type)
// Write a control tuning packet. Total length : 22 bytes
#if HIL_MODE != HIL_MODE_ATTITUDE
static void Log_Write_Control_Tuning()
{
Vector3f accel = ins.get_accel();
@ -301,7 +298,6 @@ static void Log_Write_Control_Tuning()
DataFlash.WriteInt((int)(accel.y * 10000));
DataFlash.WriteByte(END_BYTE);
}
#endif
// Write a navigation tuning packet. Total length : 18 bytes
static void Log_Write_Nav_Tuning()
@ -350,7 +346,6 @@ static void Log_Write_GPS( int32_t log_Time, int32_t log_Lattitude, int32_t
}
// Write an raw accel/gyro data packet. Total length : 28 bytes
#if HIL_MODE != HIL_MODE_ATTITUDE
static void Log_Write_Raw()
{
Vector3f gyro = ins.get_gyro();
@ -370,7 +365,6 @@ static void Log_Write_Raw()
DataFlash.WriteByte(END_BYTE);
}
#endif
static void Log_Write_Current()
{

View File

@ -7,16 +7,19 @@ nogps:
make -f Makefile EXTRAFLAGS="-DGPS_PROTOCOL=GPS_PROTOCOL_NONE -DLOGGING_ENABLED=DISABLED"
hil:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DCLI_SLIDER_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE"
hil-apm2:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2"
hilsensors:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_SENSORS -DCLI_SLIDER_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_SENSORS"
hilsensors-apm2:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_SENSORS -DCLI_SLIDER_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED -DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2"
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_SENSORS -DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2"
hilnocli:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DCLI_ENABLED=DISABLED"
nocli:
make -f Makefile EXTRAFLAGS="-DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"

View File

@ -250,8 +250,8 @@ void init_home()
while (!g_gps->new_data || !g_gps->fix) {
g_gps->update();
#if HIL_MODE != HIL_MODE_DISABLED
// update hil gps so we have new_data
gcs_update();
// update hil gps so we have new_data
gcs_update();
#endif
}

View File

@ -190,6 +190,7 @@
#define CONFIG_ADC DISABLED
#undef CONFIG_PITOT_SOURCE
#define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
#undef CONFIG_PITOT_SOURCE_ANALOG_PIN
#define CONFIG_PITOT_SOURCE_ANALOG_PIN -1
#endif

View File

@ -6,6 +6,7 @@ static LowPassFilterInt32 altitude_filter;
static void init_barometer(void)
{
gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer"));
barometer.calibrate(mavlink_delay);
// filter at 100ms sampling, with 0.7Hz cutoff frequency