diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 5d8b29ebdd..c8da8e039f 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -91,7 +91,7 @@ // AP_HAL #include #include -#include +#include #include #include #include @@ -275,7 +275,7 @@ AP_AHRS_NavEKF ahrs(ins, barometer, gps, sonar); AP_AHRS_DCM ahrs(ins, barometer, gps); #endif -#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL SITL sitl; #endif diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 1e43b7dd3e..a059d481de 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -323,7 +323,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) // report simulator state static void NOINLINE send_simstate(mavlink_channel_t chan) { -#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL sitl.simstate_send(chan); #endif } @@ -606,7 +606,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) break; case MSG_SIMSTATE: -#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL CHECK_PAYLOAD_SIZE(SIMSTATE); send_simstate(chan); #endif diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index b798d6cc47..e761a41cf2 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -378,7 +378,7 @@ static void Log_Write_Attitude() #endif DataFlash.Log_Write_AHRS2(ahrs); #endif -#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL sitl.Log_Write_SIMSTATE(DataFlash); #endif } diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index bd7738e0c7..e8602d1641 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -908,7 +908,7 @@ const AP_Param::Info var_info[] PROGMEM = { GOBJECT(sprayer, "SPRAY_", AC_Sprayer), #endif -#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL GOBJECT(sitl, "SIM_", SITL), #endif diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 7f18523ce7..bdd26951d6 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -141,7 +141,7 @@ static bool init_arm_motors(bool arming_from_gcs) update_notify(); } -#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL +#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL gcs_send_text_P(SEVERITY_HIGH, PSTR("ARMING MOTORS")); #endif @@ -746,7 +746,7 @@ static void init_disarm_motors() return; } -#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL +#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS")); #endif