Browse Source

Copter: Disable option code

Copter: Revert change

Copter: Change mistakes
master
murata 6 years ago committed by Randy Mackay
parent
commit
8644f4d76e
  1. 12
      ArduCopter/config.h
  2. 4
      ArduCopter/mode_brake.cpp
  3. 4
      ArduCopter/mode_guided.cpp
  4. 4
      ArduCopter/mode_guided_nogps.cpp
  5. 4
      ArduCopter/mode_loiter.cpp
  6. 4
      ArduCopter/mode_poshold.cpp
  7. 4
      ArduCopter/mode_rtl.cpp
  8. 4
      ArduCopter/mode_sport.cpp

12
ArduCopter/config.h

@ -704,6 +704,18 @@ @@ -704,6 +704,18 @@
#error Helicopter frame requires acro mode support which is disabled
#endif
#if MODE_SMARTRTL_ENABLED && !MODE_RTL_ENABLED
#error SmartRTL requires ModeRTL which is disabled
#endif
#if ADSB_ENABLED && !MODE_GUIDED_ENABLED
#error ADSB requires ModeGuided which is disabled
#endif
#if MODE_FOLLOW_ENABLED && !MODE_GUIDED_ENABLED
#error Follow requires ModeGuided which is disabled
#endif
//////////////////////////////////////////////////////////////////////////////
// Developer Items
//

4
ArduCopter/mode_brake.cpp

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
#include "Copter.h"
#if MODE_BRAKE_ENABLED == ENABLED
/*
* Init and run calls for brake flight mode
*/
@ -79,3 +81,5 @@ void Copter::ModeBrake::timeout_to_loiter_ms(uint32_t timeout_ms) @@ -79,3 +81,5 @@ void Copter::ModeBrake::timeout_to_loiter_ms(uint32_t timeout_ms)
_timeout_start = millis();
_timeout_ms = timeout_ms;
}
#endif

4
ArduCopter/mode_guided.cpp

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
#include "Copter.h"
#if MODE_GUIDED_ENABLED == ENABLED
/*
* Init and run calls for guided flight mode
*/
@ -785,3 +787,5 @@ float Copter::ModeGuided::crosstrack_error() const @@ -785,3 +787,5 @@ float Copter::ModeGuided::crosstrack_error() const
return 0;
}
}
#endif

4
ArduCopter/mode_guided_nogps.cpp

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
#include "Copter.h"
#if MODE_GUIDED_NOGPS_ENABLED == ENABLED
/*
* Init and run calls for guided_nogps flight mode
*/
@ -19,3 +21,5 @@ void Copter::ModeGuidedNoGPS::run() @@ -19,3 +21,5 @@ void Copter::ModeGuidedNoGPS::run()
// run angle controller
Copter::ModeGuided::angle_control_run();
}
#endif

4
ArduCopter/mode_loiter.cpp

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
#include "Copter.h"
#if MODE_LOITER_ENABLED == ENABLED
/*
* Init and run calls for loiter flight mode
*/
@ -238,3 +240,5 @@ int32_t Copter::ModeLoiter::wp_bearing() const @@ -238,3 +240,5 @@ int32_t Copter::ModeLoiter::wp_bearing() const
{
return loiter_nav->get_bearing_to_target();
}
#endif

4
ArduCopter/mode_poshold.cpp

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
#include "Copter.h"
#if MODE_POSHOLD_ENABLED == ENABLED
/*
* Init and run calls for PosHold flight mode
* PosHold tries to improve upon regular loiter by mixing the pilot input with the loiter controller
@ -667,3 +669,5 @@ void Copter::ModePosHold::poshold_pitch_controller_to_pilot_override() @@ -667,3 +669,5 @@ void Copter::ModePosHold::poshold_pitch_controller_to_pilot_override()
// store final loiter outputs for mixing with pilot input
poshold.controller_final_pitch = poshold.pitch;
}
#endif

4
ArduCopter/mode_rtl.cpp

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
#include "Copter.h"
#if MODE_RTL_ENABLED == ENABLED
/*
* Init and run calls for RTL flight mode
*
@ -492,3 +494,5 @@ int32_t Copter::ModeRTL::wp_bearing() const @@ -492,3 +494,5 @@ int32_t Copter::ModeRTL::wp_bearing() const
{
return wp_nav->get_wp_bearing_to_destination();
}
#endif

4
ArduCopter/mode_sport.cpp

@ -1,5 +1,7 @@ @@ -1,5 +1,7 @@
#include "Copter.h"
#if MODE_SPORT_ENABLED == ENABLED
/*
* Init and run calls for sport flight mode
*/
@ -165,3 +167,5 @@ void Copter::ModeSport::run() @@ -165,3 +167,5 @@ void Copter::ModeSport::run()
break;
}
}
#endif

Loading…
Cancel
Save