Browse Source

ArduPlane: ensure ENABLE_SCRIPTING is always defined

gps-1.3.1
Peter Barker 3 years ago committed by Peter Barker
parent
commit
203103bae5
  1. 2
      ArduPlane/ArduPlane.cpp
  2. 2
      ArduPlane/Parameters.cpp
  3. 2
      ArduPlane/Parameters.h
  4. 6
      ArduPlane/Plane.h
  5. 2
      ArduPlane/quadplane.cpp
  6. 2
      ArduPlane/system.cpp

2
ArduPlane/ArduPlane.cpp

@ -687,7 +687,7 @@ bool Plane::get_wp_crosstrack_error_m(float &xtrack_error) const @@ -687,7 +687,7 @@ bool Plane::get_wp_crosstrack_error_m(float &xtrack_error) const
return true;
}
#ifdef ENABLE_SCRIPTING
#if ENABLE_SCRIPTING
// set target location (for use by scripting)
bool Plane::set_target_location(const Location& target_loc)
{

2
ArduPlane/Parameters.cpp

@ -1079,7 +1079,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { @@ -1079,7 +1079,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
#ifdef ENABLE_SCRIPTING
#if ENABLE_SCRIPTING
// @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
AP_SUBGROUPINFO(scripting, "SCR_", 14, ParametersG2, AP_Scripting),

2
ArduPlane/Parameters.h

@ -516,7 +516,7 @@ public: @@ -516,7 +516,7 @@ public:
AP_Int32 flight_options;
#ifdef ENABLE_SCRIPTING
#if ENABLE_SCRIPTING
AP_Scripting scripting;
#endif // ENABLE_SCRIPTING

6
ArduPlane/Plane.h

@ -104,7 +104,7 @@ @@ -104,7 +104,7 @@
#include "defines.h"
#include "mode.h"
#ifdef ENABLE_SCRIPTING
#if ENABLE_SCRIPTING
#include <AP_Scripting/AP_Scripting.h>
#endif
@ -1133,7 +1133,7 @@ private: @@ -1133,7 +1133,7 @@ private:
float get_throttle_input(bool no_deadzone=false) const;
float get_adjusted_throttle_input(bool no_deadzone=false) const;
#ifdef ENABLE_SCRIPTING
#if ENABLE_SCRIPTING
// support for NAV_SCRIPT_TIME mission command
bool nav_scripting_active(void) const;
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) override;
@ -1209,7 +1209,7 @@ private: @@ -1209,7 +1209,7 @@ private:
public:
void failsafe_check(void);
#ifdef ENABLE_SCRIPTING
#if ENABLE_SCRIPTING
bool set_target_location(const Location& target_loc) override;
bool get_target_location(Location& target_loc) override;
#endif // ENABLE_SCRIPTING

2
ArduPlane/quadplane.cpp

@ -632,7 +632,7 @@ bool QuadPlane::setup(void) @@ -632,7 +632,7 @@ bool QuadPlane::setup(void)
motors_var_info = AP_MotorsTailsitter::var_info;
break;
case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX:
#ifdef ENABLE_SCRIPTING
#if ENABLE_SCRIPTING
motors = new AP_MotorsMatrix_Scripting_Dynamic(plane.scheduler.get_loop_rate_hz());
motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info;
#endif // ENABLE_SCRIPTING

2
ArduPlane/system.cpp

@ -186,7 +186,7 @@ void Plane::startup_ground(void) @@ -186,7 +186,7 @@ void Plane::startup_ground(void)
);
#endif
#ifdef ENABLE_SCRIPTING
#if ENABLE_SCRIPTING
g2.scripting.init();
#endif // ENABLE_SCRIPTING

Loading…
Cancel
Save