mirror of https://github.com/ArduPilot/ardupilot
Rover: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED
This commit is contained in:
parent
60932e04d5
commit
9a5520a811
|
@ -600,7 +600,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("BAL_PITCH_TRIM", 40, ParametersG2, bal_pitch_trim, 0),
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// @Group: SCR_
|
||||
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
|
||||
AP_SUBGROUPINFO(scripting, "SCR_", 41, ParametersG2, AP_Scripting),
|
||||
|
|
|
@ -383,9 +383,9 @@ public:
|
|||
// stick mixing for auto modes
|
||||
AP_Int8 stick_mixing;
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
AP_Scripting scripting;
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
// waypoint navigation
|
||||
AR_WPNav wp_nav;
|
||||
|
|
|
@ -139,7 +139,7 @@ Rover::Rover(void) :
|
|||
{
|
||||
}
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// set target location (for use by scripting)
|
||||
bool Rover::set_target_location(const Location& target_loc)
|
||||
{
|
||||
|
@ -218,7 +218,7 @@ bool Rover::get_control_output(AP_Vehicle::ControlOutput control_output, float &
|
|||
}
|
||||
return false;
|
||||
}
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
/*
|
||||
|
|
|
@ -72,7 +72,7 @@
|
|||
#include <AP_Torqeedo/AP_Torqeedo.h>
|
||||
#include <AP_AIS/AP_AIS.h>
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
#include <AP_Scripting/AP_Scripting.h>
|
||||
#endif
|
||||
|
||||
|
@ -266,12 +266,12 @@ private:
|
|||
private:
|
||||
|
||||
// Rover.cpp
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
bool set_target_location(const Location& target_loc) override;
|
||||
bool set_target_velocity_NED(const Vector3f& vel_ned) override;
|
||||
bool set_steering_and_throttle(float steering, float throttle) override;
|
||||
bool get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value) override;
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
void stats_update();
|
||||
void ahrs_update();
|
||||
void gcs_failsafe_check(void);
|
||||
|
|
|
@ -163,9 +163,9 @@ void Rover::startup_ground(void)
|
|||
);
|
||||
#endif
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
g2.scripting.init();
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
// we don't want writes to the serial port to cause us to pause
|
||||
// so set serial ports non-blocking once we are ready to drive
|
||||
|
|
Loading…
Reference in New Issue