mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-05 21:23:58 -04:00
Plane: updates for OBC API change
This commit is contained in:
parent
4c5e59c098
commit
d37f1a1376
@ -106,13 +106,6 @@ AP_HAL::BetterStream* cliSerial;
|
||||
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Outback Challenge Failsafe Support
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
APM_OBC obc;
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// the rate we run the main loop at
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -561,6 +554,13 @@ AP_Mission mission(ahrs,
|
||||
&exit_mission_callback,
|
||||
MISSION_START_BYTE, MISSION_END_BYTE);
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Outback Challenge Failsafe Support
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
APM_OBC obc(mission, barometer, gps);
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Waypoint distances
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -909,9 +909,7 @@ static void obc_fs_check(void)
|
||||
{
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
// perform OBC failsafe checks
|
||||
obc.check(OBC_MODE(control_mode),
|
||||
failsafe.last_heartbeat_ms,
|
||||
gps, mission);
|
||||
obc.check(OBC_MODE(control_mode), failsafe.last_heartbeat_ms);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -814,19 +814,6 @@ static void set_servos(void)
|
||||
channel_pitch->radio_out = elevon.trim2 + (BOOL_TO_SIGN(g.reverse_ch2_elevon) * (ch2 * 500.0/ SERVO_MAX));
|
||||
}
|
||||
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
// this is to allow the failsafe module to deliberately crash
|
||||
// the plane. Only used in extreme circumstances to meet the
|
||||
// OBC rules
|
||||
if (obc.crash_plane()) {
|
||||
channel_roll->servo_out = -4500;
|
||||
channel_pitch->servo_out = -4500;
|
||||
channel_rudder->servo_out = -4500;
|
||||
channel_throttle->servo_out = 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// push out the PWM values
|
||||
if (g.mix_mode == 0) {
|
||||
channel_roll->calc_pwm();
|
||||
@ -916,6 +903,29 @@ static void set_servos(void)
|
||||
channel_rudder->radio_out = channel_rudder->radio_in;
|
||||
}
|
||||
|
||||
#if OBC_FAILSAFE == ENABLED
|
||||
// this is to allow the failsafe module to deliberately crash
|
||||
// the plane. Only used in extreme circumstances to meet the
|
||||
// OBC rules
|
||||
if (obc.crash_plane()) {
|
||||
channel_roll->servo_out = -4500;
|
||||
channel_pitch->servo_out = -4500;
|
||||
channel_rudder->servo_out = -4500;
|
||||
channel_throttle->servo_out = 0;
|
||||
channel_roll->calc_pwm();
|
||||
channel_pitch->calc_pwm();
|
||||
channel_rudder->calc_pwm();
|
||||
channel_throttle->calc_pwm();
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_flap_auto, 100);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_flap, 100);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_aileron, 4500);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_rudder, 4500);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_elevator, 4500);
|
||||
RC_Channel_aux::set_servo_out(RC_Channel_aux::k_elevator_with_input, 4500);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
if (g.flaperon_output != MIXING_DISABLED && g.elevon_output == MIXING_DISABLED && g.mix_mode == 0) {
|
||||
flaperon_update(auto_flap_percent);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user