Browse Source

Copter: fix for HAL_SITL rename

master
Andrew Tridgell 10 years ago
parent
commit
5a36b9955e
  1. 4
      ArduCopter/ArduCopter.pde
  2. 4
      ArduCopter/GCS_Mavlink.pde
  3. 2
      ArduCopter/Log.pde
  4. 2
      ArduCopter/Parameters.pde
  5. 4
      ArduCopter/motors.pde

4
ArduCopter/ArduCopter.pde

@ -91,7 +91,7 @@ @@ -91,7 +91,7 @@
// AP_HAL
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_VRBRAIN.h>
#include <AP_HAL_FLYMAPLE.h>
@ -275,7 +275,7 @@ AP_AHRS_NavEKF ahrs(ins, barometer, gps, sonar); @@ -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

4
ArduCopter/GCS_Mavlink.pde

@ -323,7 +323,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) @@ -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) @@ -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

2
ArduCopter/Log.pde

@ -378,7 +378,7 @@ static void Log_Write_Attitude() @@ -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
}

2
ArduCopter/Parameters.pde

@ -908,7 +908,7 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -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

4
ArduCopter/motors.pde

@ -141,7 +141,7 @@ static bool init_arm_motors(bool arming_from_gcs) @@ -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() @@ -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

Loading…
Cancel
Save