Browse Source

Plane: create generic vehicle management and move runcam to it

c415-sdk
Andy Piper 5 years ago committed by Andrew Tridgell
parent
commit
eca398e7a2
  1. 4
      ArduPlane/Parameters.cpp
  2. 4
      ArduPlane/Parameters.h
  3. 1
      ArduPlane/Plane.cpp
  4. 3
      ArduPlane/system.cpp

4
ArduPlane/Parameters.cpp

@ -1094,6 +1094,10 @@ const AP_Param::Info Plane::var_info[] = { @@ -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
};

4
ArduPlane/Parameters.h

@ -345,6 +345,8 @@ public: @@ -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: @@ -568,7 +570,7 @@ public:
#if EFI_ENABLED
// EFI Engine Monitor
AP_EFI efi;
#endif
#endif
};
extern const AP_Param::Info var_info[];

1
ArduPlane/Plane.cpp

@ -31,3 +31,4 @@ Plane::Plane(void) @@ -31,3 +31,4 @@ Plane::Plane(void)
}
Plane plane;
AP_Vehicle& vehicle = plane;

3
ArduPlane/system.cpp

@ -137,6 +137,9 @@ void Plane::init_ardupilot() @@ -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();

Loading…
Cancel
Save