Browse Source

Plane: added HIL_SUPPORT define

disable HIL support on APM2 to save flash space
mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
6c07795b63
  1. 2
      ArduPlane/ArduPlane.cpp
  2. 2
      ArduPlane/Attitude.cpp
  3. 14
      ArduPlane/GCS_Mavlink.cpp
  4. 2
      ArduPlane/Parameters.cpp
  5. 2
      ArduPlane/Parameters.h
  6. 6
      ArduPlane/config.h
  7. 6
      ArduPlane/system.cpp

2
ArduPlane/ArduPlane.cpp

@ -137,10 +137,12 @@ void Plane::ahrs_update()
hal.util->set_soft_armed(arming.is_armed() && hal.util->set_soft_armed(arming.is_armed() &&
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED); hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
#if HIL_SUPPORT
if (g.hil_mode == 1) { if (g.hil_mode == 1) {
// update hil before AHRS update // update hil before AHRS update
gcs_update(); gcs_update();
} }
#endif
ahrs.update(); ahrs.update();

2
ArduPlane/Attitude.cpp

@ -995,6 +995,7 @@ void Plane::set_servos(void)
obc.check_crash_plane(); obc.check_crash_plane();
#endif #endif
#if HIL_SUPPORT
if (g.hil_mode == 1) { if (g.hil_mode == 1) {
// get the servos to the GCS immediately for HIL // get the servos to the GCS immediately for HIL
if (comm_get_txspace(MAVLINK_COMM_0) >= if (comm_get_txspace(MAVLINK_COMM_0) >=
@ -1005,6 +1006,7 @@ void Plane::set_servos(void)
return; return;
} }
} }
#endif
// send values to the PWM timers for output // send values to the PWM timers for output
// ---------------------------------------- // ----------------------------------------

14
ArduPlane/GCS_Mavlink.cpp

@ -69,9 +69,11 @@ void Plane::send_heartbeat(mavlink_channel_t chan)
base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
} }
#if HIL_SUPPORT
if (g.hil_mode == 1) { if (g.hil_mode == 1) {
base_mode |= MAV_MODE_FLAG_HIL_ENABLED; base_mode |= MAV_MODE_FLAG_HIL_ENABLED;
} }
#endif
// we are armed if we are not initialising // we are armed if we are not initialising
if (control_mode != INITIALISING && hal.util->get_soft_armed()) { if (control_mode != INITIALISING && hal.util->get_soft_armed()) {
@ -366,6 +368,7 @@ void Plane::send_servo_out(mavlink_channel_t chan)
void Plane::send_radio_out(mavlink_channel_t chan) void Plane::send_radio_out(mavlink_channel_t chan)
{ {
#if HIL_SUPPORT
if (g.hil_mode==1 && !g.hil_servos) { if (g.hil_mode==1 && !g.hil_servos) {
mavlink_msg_servo_output_raw_send( mavlink_msg_servo_output_raw_send(
chan, chan,
@ -381,6 +384,7 @@ void Plane::send_radio_out(mavlink_channel_t chan)
RC_Channel::rc_channel(7)->radio_out); RC_Channel::rc_channel(7)->radio_out);
return; return;
} }
#endif
mavlink_msg_servo_output_raw_send( mavlink_msg_servo_output_raw_send(
chan, chan,
micros(), micros(),
@ -416,14 +420,16 @@ void Plane::send_vfr_hud(mavlink_channel_t chan)
/* /*
keep last HIL_STATE message to allow sending SIM_STATE keep last HIL_STATE message to allow sending SIM_STATE
*/ */
#if HIL_SUPPORT
static mavlink_hil_state_t last_hil_state; static mavlink_hil_state_t last_hil_state;
#endif
// report simulator state // report simulator state
void Plane::send_simstate(mavlink_channel_t chan) void Plane::send_simstate(mavlink_channel_t chan)
{ {
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
sitl.simstate_send(chan); sitl.simstate_send(chan);
#else #elif HIL_SUPPORT
if (g.hil_mode == 1) { if (g.hil_mode == 1) {
mavlink_msg_simstate_send(chan, mavlink_msg_simstate_send(chan,
last_hil_state.roll, last_hil_state.roll,
@ -637,10 +643,12 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
break; break;
case MSG_SERVO_OUT: case MSG_SERVO_OUT:
#if HIL_SUPPORT
if (plane.g.hil_mode == 1) { if (plane.g.hil_mode == 1) {
CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED); CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED);
plane.send_servo_out(chan); plane.send_servo_out(chan);
} }
#endif
break; break;
case MSG_RADIO_IN: case MSG_RADIO_IN:
@ -937,6 +945,7 @@ GCS_MAVLINK::data_stream_send(void)
if (plane.gcs_out_of_time) return; if (plane.gcs_out_of_time) return;
if (plane.in_mavlink_delay) { if (plane.in_mavlink_delay) {
#if HIL_SUPPORT
if (plane.g.hil_mode == 1) { if (plane.g.hil_mode == 1) {
// in HIL we need to keep sending servo values to ensure // in HIL we need to keep sending servo values to ensure
// the simulator doesn't pause, otherwise our sensor // the simulator doesn't pause, otherwise our sensor
@ -948,6 +957,7 @@ GCS_MAVLINK::data_stream_send(void)
send_message(MSG_RADIO_OUT); send_message(MSG_RADIO_OUT);
} }
} }
#endif
// don't send any other stream types while in the delay callback // don't send any other stream types while in the delay callback
return; return;
} }
@ -1606,6 +1616,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_HIL_STATE: case MAVLINK_MSG_ID_HIL_STATE:
{ {
#if HIL_SUPPORT
if (plane.g.hil_mode != 1) { if (plane.g.hil_mode != 1) {
break; break;
} }
@ -1656,6 +1667,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
wrap_PI(fabsf(packet.yaw - plane.ahrs.yaw)) > ToRad(plane.g.hil_err_limit))) { wrap_PI(fabsf(packet.yaw - plane.ahrs.yaw)) > ToRad(plane.g.hil_err_limit))) {
plane.ahrs.reset_attitude(packet.roll, packet.pitch, packet.yaw); plane.ahrs.reset_attitude(packet.roll, packet.pitch, packet.yaw);
} }
#endif
break; break;
} }

2
ArduPlane/Parameters.cpp

@ -934,12 +934,14 @@ const AP_Param::Info Plane::var_info[] PROGMEM = {
// @User: Standard // @User: Standard
GSCALAR(inverted_flight_ch, "INVERTEDFLT_CH", 0), GSCALAR(inverted_flight_ch, "INVERTEDFLT_CH", 0),
#if HIL_SUPPORT
// @Param: HIL_MODE // @Param: HIL_MODE
// @DisplayName: HIL mode enable // @DisplayName: HIL mode enable
// @Description: This enables and disables hardware in the loop mode. If HIL_MODE is 1 then on the next reboot all sensors are replaced with HIL sensors which come from the GCS. // @Description: This enables and disables hardware in the loop mode. If HIL_MODE is 1 then on the next reboot all sensors are replaced with HIL sensors which come from the GCS.
// @Values: 0:Disabled,1:Enabled // @Values: 0:Disabled,1:Enabled
// @User: Advanced // @User: Advanced
GSCALAR(hil_mode, "HIL_MODE", 0), GSCALAR(hil_mode, "HIL_MODE", 0),
#endif
// @Param: HIL_SERVOS // @Param: HIL_SERVOS
// @DisplayName: HIL Servos enable // @DisplayName: HIL Servos enable

2
ArduPlane/Parameters.h

@ -448,7 +448,9 @@ public:
AP_Int16 pitch_trim_cd; AP_Int16 pitch_trim_cd;
AP_Int16 FBWB_min_altitude_cm; AP_Int16 FBWB_min_altitude_cm;
AP_Int8 hil_servos; AP_Int8 hil_servos;
#if HIL_SUPPORT
AP_Int8 hil_mode; AP_Int8 hil_mode;
#endif
AP_Int8 compass_enabled; AP_Int8 compass_enabled;
AP_Int8 flap_1_percent; AP_Int8 flap_1_percent;

6
ArduPlane/config.h

@ -459,6 +459,12 @@
#define CLI_ENABLED DISABLED #define CLI_ENABLED DISABLED
#endif #endif
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75
#define HIL_SUPPORT DISABLED
#else
#define HIL_SUPPORT ENABLED
#endif
/* /*
build a firmware version string. build a firmware version string.
GIT_VERSION comes from Makefile builds GIT_VERSION comes from Makefile builds

6
ArduPlane/system.cpp

@ -95,12 +95,14 @@ void Plane::init_ardupilot()
// //
load_parameters(); load_parameters();
#if HIL_SUPPORT
if (g.hil_mode == 1) { if (g.hil_mode == 1) {
// set sensors to HIL mode // set sensors to HIL mode
ins.set_hil_mode(); ins.set_hil_mode();
compass.set_hil_mode(); compass.set_hil_mode();
barometer.set_hil_mode(); barometer.set_hil_mode();
} }
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// this must be before BoardConfig.init() so if // this must be before BoardConfig.init() so if
@ -536,6 +538,7 @@ void Plane::check_short_failsafe()
void Plane::startup_INS_ground(void) void Plane::startup_INS_ground(void)
{ {
#if HIL_SUPPORT
if (g.hil_mode == 1) { if (g.hil_mode == 1) {
while (barometer.get_last_update() == 0) { while (barometer.get_last_update() == 0) {
// the barometer begins updating when we get the first // the barometer begins updating when we get the first
@ -544,6 +547,7 @@ void Plane::startup_INS_ground(void)
hal.scheduler->delay(1000); hal.scheduler->delay(1000);
} }
} }
#endif
AP_InertialSensor::Start_style style; AP_InertialSensor::Start_style style;
if (g.skip_gyro_cal) { if (g.skip_gyro_cal) {
@ -679,12 +683,14 @@ void Plane::print_comma(void)
*/ */
void Plane::servo_write(uint8_t ch, uint16_t pwm) void Plane::servo_write(uint8_t ch, uint16_t pwm)
{ {
#if HIL_SUPPORT
if (g.hil_mode==1 && !g.hil_servos) { if (g.hil_mode==1 && !g.hil_servos) {
if (ch < 8) { if (ch < 8) {
RC_Channel::rc_channel(ch)->radio_out = pwm; RC_Channel::rc_channel(ch)->radio_out = pwm;
} }
return; return;
} }
#endif
hal.rcout->enable_ch(ch); hal.rcout->enable_ch(ch);
hal.rcout->write(ch, pwm); hal.rcout->write(ch, pwm);
} }

Loading…
Cancel
Save