mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduPlane: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED
This commit is contained in:
parent
238a6e4016
commit
70562021ac
@ -687,7 +687,7 @@ bool Plane::get_wp_crosstrack_error_m(float &xtrack_error) const
|
||||
return true;
|
||||
}
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// set target location (for use by scripting)
|
||||
bool Plane::set_target_location(const Location& target_loc)
|
||||
{
|
||||
@ -727,7 +727,7 @@ bool Plane::get_target_location(Location& target_loc)
|
||||
}
|
||||
return false;
|
||||
}
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
#if OSD_ENABLED
|
||||
// correct AHRS pitch for TRIM_PITCH_CD in non-VTOL modes, and return VTOL view in VTOL
|
||||
|
@ -501,7 +501,7 @@ void Plane::stabilize()
|
||||
plane.stabilize_pitch(speed_scaler);
|
||||
}
|
||||
#endif
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
} else if (control_mode == &mode_auto &&
|
||||
mission.get_current_nav_cmd().id == MAV_CMD_NAV_SCRIPT_TIME) {
|
||||
// scripting is in control of roll and pitch rates and throttle
|
||||
|
@ -1079,7 +1079,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// @Group: SCR_
|
||||
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
|
||||
AP_SUBGROUPINFO(scripting, "SCR_", 14, ParametersG2, AP_Scripting),
|
||||
|
@ -516,9 +516,9 @@ public:
|
||||
|
||||
AP_Int32 flight_options;
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
AP_Scripting scripting;
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
AP_Int8 takeoff_throttle_accel_count;
|
||||
AP_Int8 takeoff_timeout;
|
||||
|
@ -104,7 +104,7 @@
|
||||
#include "defines.h"
|
||||
#include "mode.h"
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
#include <AP_Scripting/AP_Scripting.h>
|
||||
#endif
|
||||
|
||||
@ -517,7 +517,7 @@ private:
|
||||
float terrain_correction;
|
||||
} auto_state;
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// support for scripting nav commands, with verify
|
||||
struct {
|
||||
uint16_t id;
|
||||
@ -940,7 +940,7 @@ private:
|
||||
bool verify_command_callback(const AP_Mission::Mission_Command& cmd);
|
||||
float get_wp_radius() const;
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// nav scripting support
|
||||
void do_nav_script_time(const AP_Mission::Mission_Command& cmd);
|
||||
bool verify_nav_script_time(const AP_Mission::Mission_Command& cmd);
|
||||
@ -1133,7 +1133,7 @@ private:
|
||||
float get_throttle_input(bool no_deadzone=false) const;
|
||||
float get_adjusted_throttle_input(bool no_deadzone=false) const;
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// support for NAV_SCRIPT_TIME mission command
|
||||
bool nav_scripting_active(void) const;
|
||||
bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) override;
|
||||
@ -1209,10 +1209,10 @@ private:
|
||||
|
||||
public:
|
||||
void failsafe_check(void);
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
bool set_target_location(const Location& target_loc) override;
|
||||
bool get_target_location(Location& target_loc) override;
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
};
|
||||
|
||||
|
@ -197,7 +197,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
cmd.content.do_engine_control.height_delay_cm*0.01f);
|
||||
break;
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
case MAV_CMD_NAV_SCRIPT_TIME:
|
||||
do_nav_script_time(cmd);
|
||||
break;
|
||||
@ -298,7 +298,7 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
|
||||
case MAV_CMD_CONDITION_DISTANCE:
|
||||
return verify_within_distance();
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
case MAV_CMD_NAV_SCRIPT_TIME:
|
||||
return verify_nav_script_time(cmd);
|
||||
#endif
|
||||
@ -1118,7 +1118,7 @@ float Plane::get_wp_radius() const
|
||||
return g.waypoint_radius;
|
||||
}
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
/*
|
||||
support for scripted navigation, with verify operation for completion
|
||||
*/
|
||||
@ -1191,4 +1191,4 @@ bool Plane::set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps
|
||||
nav_scripting.throttle_pct = throttle_pct;
|
||||
return true;
|
||||
}
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
@ -86,7 +86,7 @@ void ModeAuto::update()
|
||||
} else {
|
||||
plane.calc_throttle();
|
||||
}
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
} else if (nav_cmd_id == MAV_CMD_NAV_SCRIPT_TIME) {
|
||||
// NAV_SCRIPTING has a desired roll and pitch rate and desired throttle
|
||||
plane.nav_roll_cd = plane.ahrs.roll_sensor;
|
||||
|
@ -632,10 +632,10 @@ bool QuadPlane::setup(void)
|
||||
motors_var_info = AP_MotorsTailsitter::var_info;
|
||||
break;
|
||||
case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX:
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
motors = new AP_MotorsMatrix_Scripting_Dynamic(plane.scheduler.get_loop_rate_hz());
|
||||
motors_var_info = AP_MotorsMatrix_Scripting_Dynamic::var_info;
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
break;
|
||||
default:
|
||||
motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz(), rc_speed);
|
||||
|
@ -186,9 +186,9 @@ void Plane::startup_ground(void)
|
||||
);
|
||||
#endif
|
||||
|
||||
#if ENABLE_SCRIPTING
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
g2.scripting.init();
|
||||
#endif // ENABLE_SCRIPTING
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
||||
// reset last heartbeat time, so we don't trigger failsafe on slow
|
||||
// startup
|
||||
|
Loading…
Reference in New Issue
Block a user