mirror of https://github.com/ArduPilot/ardupilot
Tracker: move scripting up to AP_Vehicle
This commit is contained in:
parent
6da7cfcf4e
commit
7a14427d26
|
@ -505,12 +505,6 @@ const AP_Param::Info Tracker::var_info[] = {
|
||||||
|
|
||||||
GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),
|
GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
|
||||||
// @Group: SCR_
|
|
||||||
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
|
|
||||||
GOBJECT(scripting, "SCR_", AP_Scripting),
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// @Param: CMD_TOTAL
|
// @Param: CMD_TOTAL
|
||||||
// @DisplayName: Number of loaded mission items
|
// @DisplayName: Number of loaded mission items
|
||||||
// @Description: Set to 1 if HOME location has been loaded by the ground station. Do not change this manually.
|
// @Description: Set to 1 if HOME location has been loaded by the ground station. Do not change this manually.
|
||||||
|
@ -619,6 +613,11 @@ void Tracker::load_parameters(void)
|
||||||
AP_Param::convert_class(g.k_param_stats_old, &stats, stats.var_info, 0, 0, true);
|
AP_Param::convert_class(g.k_param_stats_old, &stats, stats.var_info, 0, 0, true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_SCRIPTING_ENABLED
|
||||||
|
// PARAMETER_CONVERSION - Added: Jan-2024
|
||||||
|
AP_Param::convert_class(g.k_param_scripting_old, &scripting, scripting.var_info, 0, 0, true);
|
||||||
|
#endif
|
||||||
|
|
||||||
hal.console->printf("load_all took %luus\n", (unsigned long)(AP_HAL::micros() - before));
|
hal.console->printf("load_all took %luus\n", (unsigned long)(AP_HAL::micros() - before));
|
||||||
|
|
||||||
#if HAL_HAVE_SAFETY_SWITCH
|
#if HAL_HAVE_SAFETY_SWITCH
|
||||||
|
|
|
@ -115,7 +115,7 @@ public:
|
||||||
k_param_servo_channels,
|
k_param_servo_channels,
|
||||||
|
|
||||||
k_param_stats_old = 218,
|
k_param_stats_old = 218,
|
||||||
k_param_scripting = 219,
|
k_param_scripting_old = 219,
|
||||||
|
|
||||||
//
|
//
|
||||||
// 220: Waypoint data
|
// 220: Waypoint data
|
||||||
|
|
|
@ -53,10 +53,6 @@
|
||||||
|
|
||||||
#include "AP_Arming.h"
|
#include "AP_Arming.h"
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
|
||||||
#include <AP_Scripting/AP_Scripting.h>
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "mode.h"
|
#include "mode.h"
|
||||||
|
|
||||||
class Tracker : public AP_Vehicle {
|
class Tracker : public AP_Vehicle {
|
||||||
|
@ -115,10 +111,6 @@ private:
|
||||||
ModeServoTest mode_servotest;
|
ModeServoTest mode_servotest;
|
||||||
ModeStop mode_stop;
|
ModeStop mode_stop;
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
|
||||||
AP_Scripting scripting;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Vehicle state
|
// Vehicle state
|
||||||
struct {
|
struct {
|
||||||
bool location_valid; // true if we have a valid location for the vehicle
|
bool location_valid; // true if we have a valid location for the vehicle
|
||||||
|
|
|
@ -28,10 +28,6 @@ void Tracker::init_ardupilot()
|
||||||
log_init();
|
log_init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
|
||||||
scripting.init();
|
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
|
||||||
|
|
||||||
// initialise compass
|
// initialise compass
|
||||||
AP::compass().set_log_bit(MASK_LOG_COMPASS);
|
AP::compass().set_log_bit(MASK_LOG_COMPASS);
|
||||||
AP::compass().init();
|
AP::compass().init();
|
||||||
|
|
Loading…
Reference in New Issue