mirror of https://github.com/ArduPilot/ardupilot
Plane: Create a scripting object
This commit is contained in:
parent
a7d94ff6c7
commit
3aed07a83a
|
@ -1177,6 +1177,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
|
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
|
||||||
|
|
||||||
|
#ifdef ENABLE_SCRIPTING
|
||||||
|
// Scripting is intentionally not showing up in the parameter docs until it is a more standard feature
|
||||||
|
AP_SUBGROUPINFO(scripting, "SCR_", 14, ParametersG2, AP_Scripting),
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -545,6 +545,10 @@ public:
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_Int32 flight_options;
|
AP_Int32 flight_options;
|
||||||
|
|
||||||
|
#ifdef ENABLE_SCRIPTING
|
||||||
|
AP_Scripting scripting;
|
||||||
|
#endif // ENABLE_SCRIPTING
|
||||||
};
|
};
|
||||||
|
|
||||||
extern const AP_Param::Info var_info[];
|
extern const AP_Param::Info var_info[];
|
||||||
|
|
|
@ -108,6 +108,10 @@
|
||||||
// Local modules
|
// Local modules
|
||||||
#include "defines.h"
|
#include "defines.h"
|
||||||
|
|
||||||
|
#ifdef ENABLE_SCRIPTING
|
||||||
|
#include <AP_Scripting/AP_Scripting.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "RC_Channel.h" // RC Channel Library
|
#include "RC_Channel.h" // RC Channel Library
|
||||||
#include "Parameters.h"
|
#include "Parameters.h"
|
||||||
#include "avoidance_adsb.h"
|
#include "avoidance_adsb.h"
|
||||||
|
|
|
@ -251,6 +251,12 @@ void Plane::startup_ground(void)
|
||||||
);
|
);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef ENABLE_SCRIPTING
|
||||||
|
if (!g2.scripting.init()) {
|
||||||
|
gcs().send_text(MAV_SEVERITY_ERROR, "Scripting failed to start");
|
||||||
|
}
|
||||||
|
#endif // ENABLE_SCRIPTING
|
||||||
|
|
||||||
// reset last heartbeat time, so we don't trigger failsafe on slow
|
// reset last heartbeat time, so we don't trigger failsafe on slow
|
||||||
// startup
|
// startup
|
||||||
failsafe.last_heartbeat_ms = millis();
|
failsafe.last_heartbeat_ms = millis();
|
||||||
|
|
Loading…
Reference in New Issue