Rover: create generic vehicle management and move runcam to it

This commit is contained in:
Andy Piper 2019-12-01 17:02:18 +00:00 committed by Andrew Tridgell
parent e166e90c1d
commit 7f6c7fc370
5 changed files with 10 additions and 1 deletions

View File

@ -371,6 +371,10 @@ const AP_Param::Info Rover::var_info[] = {
GOBJECT(osd, "OSD", AP_OSD),
#endif
// @Group:
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
{ AP_PARAM_GROUP, "", Parameters::k_param_vehicle, (const void *)&rover, {group_info : AP_Vehicle::var_info} },
AP_VAREND
};

View File

@ -212,6 +212,8 @@ public:
k_param_logger = 253, // Logging Group
// 254,255: reserved
k_param_vehicle = 257, // vehicle common block of parameters
};
AP_Int16 format_version;

View File

@ -350,5 +350,6 @@ void Rover::publish_osd_info()
#endif
Rover rover;
AP_Vehicle& vehicle = rover;
AP_HAL_MAIN_CALLBACKS(&rover);

View File

@ -132,6 +132,9 @@ void Rover::init_ardupilot()
camera_mount.init();
#endif
// 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.

View File

@ -9,7 +9,6 @@ def build(bld):
ap_libraries=bld.ap_common_vehicle_libraries() + [
'APM_Control',
'AP_Arming',
'AP_Camera',
'AP_L1_Control',
'AP_Mount',
'AP_Navigation',