Rover: ensure ENABLE_SCRIPTING is always defined

This commit is contained in:
Peter Barker 2021-11-15 12:16:29 +11:00 committed by Peter Barker
parent e301595143
commit 5cd2c00ea7
5 changed files with 6 additions and 6 deletions

View File

@ -600,7 +600,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Standard // @User: Standard
AP_GROUPINFO("BAL_PITCH_TRIM", 40, ParametersG2, bal_pitch_trim, 0), AP_GROUPINFO("BAL_PITCH_TRIM", 40, ParametersG2, bal_pitch_trim, 0),
#ifdef ENABLE_SCRIPTING #if ENABLE_SCRIPTING
// @Group: SCR_ // @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp // @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
AP_SUBGROUPINFO(scripting, "SCR_", 41, ParametersG2, AP_Scripting), AP_SUBGROUPINFO(scripting, "SCR_", 41, ParametersG2, AP_Scripting),

View File

@ -383,7 +383,7 @@ public:
// stick mixing for auto modes // stick mixing for auto modes
AP_Int8 stick_mixing; AP_Int8 stick_mixing;
#ifdef ENABLE_SCRIPTING #if ENABLE_SCRIPTING
AP_Scripting scripting; AP_Scripting scripting;
#endif // ENABLE_SCRIPTING #endif // ENABLE_SCRIPTING

View File

@ -139,7 +139,7 @@ Rover::Rover(void) :
{ {
} }
#ifdef ENABLE_SCRIPTING #if ENABLE_SCRIPTING
// set target location (for use by scripting) // set target location (for use by scripting)
bool Rover::set_target_location(const Location& target_loc) bool Rover::set_target_location(const Location& target_loc)
{ {

View File

@ -72,7 +72,7 @@
#include <AP_Torqeedo/AP_Torqeedo.h> #include <AP_Torqeedo/AP_Torqeedo.h>
#include <AP_AIS/AP_AIS.h> #include <AP_AIS/AP_AIS.h>
#ifdef ENABLE_SCRIPTING #if ENABLE_SCRIPTING
#include <AP_Scripting/AP_Scripting.h> #include <AP_Scripting/AP_Scripting.h>
#endif #endif
@ -266,7 +266,7 @@ private:
private: private:
// Rover.cpp // Rover.cpp
#ifdef ENABLE_SCRIPTING #if ENABLE_SCRIPTING
bool set_target_location(const Location& target_loc) override; bool set_target_location(const Location& target_loc) override;
bool set_target_velocity_NED(const Vector3f& vel_ned) override; bool set_target_velocity_NED(const Vector3f& vel_ned) override;
bool set_steering_and_throttle(float steering, float throttle) override; bool set_steering_and_throttle(float steering, float throttle) override;

View File

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