mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED
This commit is contained in:
parent
c2c1417657
commit
238a6e4016
|
@ -269,7 +269,7 @@ void Copter::fast_loop()
|
|||
AP_Vehicle::fast_loop();
|
||||
}
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// start takeoff to given altitude (for use by scripting)
|
||||
bool Copter::start_takeoff(float alt)
|
||||
{
|
||||
|
@ -394,7 +394,7 @@ bool Copter::set_circle_rate(float rate_dps)
|
|||
return true;
|
||||
}
|
||||
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
|
||||
// rc_loops - reads user input from transmitter/receiver
|
||||
|
|
|
@ -157,7 +157,7 @@
|
|||
#include <AP_RPM/AP_RPM.h>
|
||||
#endif
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
#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;
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
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;
|
||||
|
@ -651,7 +651,7 @@ private:
|
|||
bool set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs) override;
|
||||
bool get_circle_radius(float &radius_m) override;
|
||||
bool set_circle_rate(float rate_dps) override;
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
void rc_loop();
|
||||
void throttle_loop();
|
||||
void update_batt_compass(void);
|
||||
|
|
|
@ -936,7 +936,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
AP_SUBGROUPPTR(autotune_ptr, "AUTOTUNE_", 29, ParametersG2, AutoTune),
|
||||
#endif
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// @Group: SCR_
|
||||
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
|
||||
AP_SUBGROUPINFO(scripting, "SCR_", 30, ParametersG2, AP_Scripting),
|
||||
|
|
|
@ -594,9 +594,9 @@ public:
|
|||
void *autotune_ptr;
|
||||
#endif
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
AP_Scripting scripting;
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
AP_Float tuning_min;
|
||||
AP_Float tuning_max;
|
||||
|
|
|
@ -177,9 +177,9 @@ void Copter::init_ardupilot()
|
|||
|
||||
startup_INS_ground();
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
g2.scripting.init();
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
// set landed flags
|
||||
set_land_complete(true);
|
||||
|
@ -464,16 +464,16 @@ void Copter::allocate_motors(void)
|
|||
motors_var_info = AP_MotorsTailsitter::var_info;
|
||||
break;
|
||||
case AP_Motors::MOTOR_FRAME_6DOF_SCRIPTING:
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
motors = new AP_MotorsMatrix_6DoF_Scripting(copter.scheduler.get_loop_rate_hz());
|
||||
motors_var_info = AP_MotorsMatrix_6DoF_Scripting::var_info;
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
break;
|
||||
case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX:
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
motors = new AP_MotorsMatrix_Scripting_Dynamic(copter.scheduler.get_loop_rate_hz());
|
||||
motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info;
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
break;
|
||||
#else // FRAME_CONFIG == HELI_FRAME
|
||||
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
|
||||
|
@ -510,10 +510,10 @@ 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) {
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
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
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
} else {
|
||||
attitude_control = new AC_AttitudeControl_Multi(*ahrs_view, aparm, *motors, scheduler.get_loop_period_s());
|
||||
ac_var_info = AC_AttitudeControl_Multi::var_info;
|
||||
|
|
Loading…
Reference in New Issue