mirror of https://github.com/ArduPilot/ardupilot
Sub: create generic vehicle management and move runcam to it
add OSD and RCMapper to build
This commit is contained in:
parent
1b7c49b662
commit
1bd6adec23
|
@ -590,6 +590,10 @@ const AP_Param::Info Sub::var_info[] = {
|
|||
// @Path: Parameters.cpp
|
||||
GOBJECT(g2, "", ParametersG2),
|
||||
|
||||
// @Group:
|
||||
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
|
||||
{ AP_PARAM_GROUP, "", Parameters::k_param_vehicle, (const void *)&sub, {group_info : AP_Vehicle::var_info} },
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
|
|
|
@ -210,6 +210,7 @@ public:
|
|||
k_param_lights_steps,
|
||||
k_param_pilot_speed_dn,
|
||||
|
||||
k_param_vehicle = 257, // vehicle common block of parameters
|
||||
};
|
||||
|
||||
AP_Int16 format_version;
|
||||
|
|
|
@ -51,3 +51,4 @@ Sub::Sub()
|
|||
}
|
||||
|
||||
Sub sub;
|
||||
AP_Vehicle& vehicle = sub;
|
||||
|
|
|
@ -99,6 +99,9 @@ void Sub::init_ardupilot()
|
|||
|
||||
relay.init();
|
||||
|
||||
// run all the vehicle initialization routines
|
||||
init_vehicle();
|
||||
|
||||
/*
|
||||
* setup the 'main loop is dead' check. Note that this relies on
|
||||
* the RC library being initialised.
|
||||
|
|
|
@ -19,6 +19,8 @@ def build(bld):
|
|||
'AP_TemperatureSensor',
|
||||
'AP_Arming',
|
||||
'AP_KDECAN',
|
||||
'AP_RCMapper',
|
||||
'AP_OSD',
|
||||
],
|
||||
)
|
||||
|
||||
|
|
Loading…
Reference in New Issue