From ee9aef25fcec7705529c5b4a89290cf9aee09f57 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 15 Nov 2021 12:16:27 +1100 Subject: [PATCH] ArduCopter: ensure ENABLE_SCRIPTING is always defined --- ArduCopter/Copter.cpp | 2 +- ArduCopter/Copter.h | 4 ++-- ArduCopter/Parameters.cpp | 2 +- ArduCopter/Parameters.h | 2 +- ArduCopter/system.cpp | 8 ++++---- 5 files changed, 9 insertions(+), 9 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index e304a0ac80..814047770d 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -269,7 +269,7 @@ void Copter::fast_loop() AP_Vehicle::fast_loop(); } -#ifdef ENABLE_SCRIPTING +#if ENABLE_SCRIPTING // start takeoff to given altitude (for use by scripting) bool Copter::start_takeoff(float alt) { diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 44b4c64cfe..454ae05043 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -157,7 +157,7 @@ #include #endif -#ifdef ENABLE_SCRIPTING +#if ENABLE_SCRIPTING #include #endif @@ -640,7 +640,7 @@ private: uint8_t &task_count, uint32_t &log_bit) override; void fast_loop() override; -#ifdef ENABLE_SCRIPTING +#if ENABLE_SCRIPTING bool start_takeoff(float alt) override; bool set_target_location(const Location& target_loc) override; bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) override; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index c295c67ad8..9fafce68e2 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -936,7 +936,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPPTR(autotune_ptr, "AUTOTUNE_", 29, ParametersG2, AutoTune), #endif -#ifdef ENABLE_SCRIPTING +#if ENABLE_SCRIPTING // @Group: SCR_ // @Path: ../libraries/AP_Scripting/AP_Scripting.cpp AP_SUBGROUPINFO(scripting, "SCR_", 30, ParametersG2, AP_Scripting), diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index ce45fbfbb4..a7baad20d7 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -594,7 +594,7 @@ public: void *autotune_ptr; #endif -#ifdef ENABLE_SCRIPTING +#if ENABLE_SCRIPTING AP_Scripting scripting; #endif // ENABLE_SCRIPTING diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 816559620e..0c6afb4a51 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -177,7 +177,7 @@ void Copter::init_ardupilot() startup_INS_ground(); -#ifdef ENABLE_SCRIPTING +#if ENABLE_SCRIPTING g2.scripting.init(); #endif // ENABLE_SCRIPTING @@ -464,13 +464,13 @@ void Copter::allocate_motors(void) motors_var_info = AP_MotorsTailsitter::var_info; break; case AP_Motors::MOTOR_FRAME_6DOF_SCRIPTING: -#ifdef ENABLE_SCRIPTING +#if ENABLE_SCRIPTING motors = new AP_MotorsMatrix_6DoF_Scripting(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsMatrix_6DoF_Scripting::var_info; #endif // ENABLE_SCRIPTING break; case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: -#ifdef ENABLE_SCRIPTING +#if ENABLE_SCRIPTING motors = new AP_MotorsMatrix_Scripting_Dynamic(copter.scheduler.get_loop_rate_hz()); motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info; #endif // ENABLE_SCRIPTING @@ -510,7 +510,7 @@ case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: #if FRAME_CONFIG != HELI_FRAME if ((AP_Motors::motor_frame_class)g2.frame_class.get() == AP_Motors::MOTOR_FRAME_6DOF_SCRIPTING) { -#ifdef ENABLE_SCRIPTING +#if ENABLE_SCRIPTING attitude_control = new AC_AttitudeControl_Multi_6DoF(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s()); ac_var_info = AC_AttitudeControl_Multi_6DoF::var_info; #endif // ENABLE_SCRIPTING