Browse Source

Rover: move devo telemetry handling to GCS

master
Peter Barker 6 years ago committed by Peter Barker
parent
commit
9c36887a90
  1. 5
      APMrover2/Rover.h
  2. 8
      APMrover2/system.cpp

5
APMrover2/Rover.h

@ -37,7 +37,6 @@ @@ -37,7 +37,6 @@
#include <AP_Camera/AP_Camera.h> // Camera triggering
#include <AP_Compass/AP_Compass.h> // ArduPilot Mega Magnetometer Library
#include <AP_Declination/AP_Declination.h> // Compass declination library
#include <AP_Devo_Telem/AP_Devo_Telem.h>
#include <AP_GPS/AP_GPS.h> // ArduPilot GPS library
#include <AP_InertialSensor/AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
#include <AP_L1_Control/AP_L1_Control.h>
@ -298,10 +297,6 @@ private: @@ -298,10 +297,6 @@ private:
FUNCTOR_BIND_MEMBER(&Rover::handle_battery_failsafe, void, const char*, const int8_t),
_failsafe_priorities};
#if DEVO_TELEM_ENABLED == ENABLED
AP_DEVO_Telem devo_telemetry;
#endif
// 3D Location vectors
// Location structure defined in AP_Common
// The home location used for RTL. The location is set when we first get stable GPS lock

8
APMrover2/system.cpp

@ -80,10 +80,6 @@ void Rover::init_ardupilot() @@ -80,10 +80,6 @@ void Rover::init_ardupilot()
// setup telem slots with serial ports
gcs().setup_uarts(serial_manager);
#if DEVO_TELEM_ENABLED == ENABLED
devo_telemetry.init();
#endif
#if OSD_ENABLED == ENABLED
osd.init();
#endif
@ -256,10 +252,6 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason) @@ -256,10 +252,6 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason)
// but it should be harmless to disable the fence temporarily in these situations as well
g2.fence.manual_recovery_start();
#if DEVO_TELEM_ENABLED == ENABLED
devo_telemetry.update_control_mode(control_mode->mode_number());
#endif
#if CAMERA == ENABLED
camera.set_is_auto_mode(control_mode->mode_number() == Mode::Number::AUTO);
#endif

Loading…
Cancel
Save