diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 99ce030a2a..eac44d3957 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -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 }; diff --git a/APMrover2/Parameters.h b/APMrover2/Parameters.h index c3fb7eca7f..e523f72d72 100644 --- a/APMrover2/Parameters.h +++ b/APMrover2/Parameters.h @@ -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; diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index 372e88fa58..995e199500 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -350,5 +350,6 @@ void Rover::publish_osd_info() #endif Rover rover; +AP_Vehicle& vehicle = rover; AP_HAL_MAIN_CALLBACKS(&rover); diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index c2656309d9..bd26d7e9c2 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -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. diff --git a/APMrover2/wscript b/APMrover2/wscript index f8d6b8e14f..169b29d1f4 100644 --- a/APMrover2/wscript +++ b/APMrover2/wscript @@ -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',