mirror of https://github.com/ArduPilot/ardupilot
Rover: correct compilation when AFS enabled
This commit is contained in:
parent
3c6b67349f
commit
a0ba9986a2
|
@ -663,7 +663,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
ParametersG2::ParametersG2(void)
|
||||
:
|
||||
#if ADVANCED_FAILSAFE == ENABLED
|
||||
afs(rover.mission, rover.gps),
|
||||
afs(rover.mode_auto.mission),
|
||||
#endif
|
||||
beacon(rover.serial_manager),
|
||||
motors(rover.ServoRelayEvents),
|
||||
|
|
|
@ -6,12 +6,6 @@
|
|||
|
||||
#if ADVANCED_FAILSAFE == ENABLED
|
||||
|
||||
// Constructor
|
||||
AP_AdvancedFailsafe_Rover::AP_AdvancedFailsafe_Rover(AP_Mission &_mission, const AP_GPS &_gps) :
|
||||
AP_AdvancedFailsafe(_mission, _gps)
|
||||
{}
|
||||
|
||||
|
||||
/*
|
||||
Setup radio_out values for all channels to termination values
|
||||
*/
|
||||
|
|
|
@ -27,7 +27,7 @@
|
|||
class AP_AdvancedFailsafe_Rover : public AP_AdvancedFailsafe
|
||||
{
|
||||
public:
|
||||
AP_AdvancedFailsafe_Rover(AP_Mission &_mission, const AP_GPS &_gps);
|
||||
using AP_AdvancedFailsafe::AP_AdvancedFailsafe;
|
||||
|
||||
// called to set all outputs to termination state
|
||||
void terminate_vehicle(void) override;
|
||||
|
|
|
@ -5,6 +5,8 @@
|
|||
|
||||
#include "Rover.h"
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
/*
|
||||
our failsafe strategy is to detect main loop lockup and switch to
|
||||
passing inputs straight from the RC inputs to RC outputs.
|
||||
|
|
Loading…
Reference in New Issue