Browse Source

Rover: create generic vehicle management and move runcam to it

zr-v5.1
Andy Piper 5 years ago committed by Andrew Tridgell
parent
commit
7f6c7fc370
  1. 4
      APMrover2/Parameters.cpp
  2. 2
      APMrover2/Parameters.h
  3. 1
      APMrover2/Rover.cpp
  4. 3
      APMrover2/system.cpp
  5. 1
      APMrover2/wscript

4
APMrover2/Parameters.cpp

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

2
APMrover2/Parameters.h

@ -212,6 +212,8 @@ public: @@ -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;

1
APMrover2/Rover.cpp

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

3
APMrover2/system.cpp

@ -132,6 +132,9 @@ void Rover::init_ardupilot() @@ -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.

1
APMrover2/wscript

@ -9,7 +9,6 @@ def build(bld): @@ -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',

Loading…
Cancel
Save