diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index fca4f124cf..d55e836217 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1094,6 +1094,10 @@ const AP_Param::Info Plane::var_info[] = { // @Path: mode_takeoff.cpp GOBJECT(mode_takeoff, "TKOFF_", ModeTakeoff), + // @Group: + // @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp + { AP_PARAM_GROUP, "", Parameters::k_param_vehicle, (const void *)&plane, {group_info : AP_Vehicle::var_info} }, + AP_VAREND }; diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 7adcdeaf42..8b9d7d9ed9 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -345,6 +345,8 @@ public: k_param_logger = 253, // Logging Group // 254,255: reserved + + k_param_vehicle = 257, // vehicle common block of parameters }; AP_Int16 format_version; @@ -568,7 +570,7 @@ public: #if EFI_ENABLED // EFI Engine Monitor AP_EFI efi; -#endif +#endif }; extern const AP_Param::Info var_info[]; diff --git a/ArduPlane/Plane.cpp b/ArduPlane/Plane.cpp index 3a8200bdcf..dff3166b02 100644 --- a/ArduPlane/Plane.cpp +++ b/ArduPlane/Plane.cpp @@ -31,3 +31,4 @@ Plane::Plane(void) } Plane plane; +AP_Vehicle& vehicle = plane; diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index e558df5bd9..20398fa444 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -137,6 +137,9 @@ void Plane::init_ardupilot() camera_mount.init(); #endif + // run all the vehicle initialization routines + init_vehicle(); + #if LANDING_GEAR_ENABLED == ENABLED // initialise landing gear position g2.landing_gear.init();