ArduCopter: ensure ENABLE_SCRIPTING is always defined

This commit is contained in:
Peter Barker 2021-11-15 12:16:27 +11:00 committed by Peter Barker
parent 44920856d3
commit ee9aef25fc
5 changed files with 9 additions and 9 deletions

View File

@ -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)
{

View File

@ -157,7 +157,7 @@
#include <AP_RPM/AP_RPM.h>
#endif
#ifdef ENABLE_SCRIPTING
#if ENABLE_SCRIPTING
#include <AP_Scripting/AP_Scripting.h>
#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;

View File

@ -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),

View File

@ -594,7 +594,7 @@ public:
void *autotune_ptr;
#endif
#ifdef ENABLE_SCRIPTING
#if ENABLE_SCRIPTING
AP_Scripting scripting;
#endif // ENABLE_SCRIPTING

View File

@ -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