Browse Source

APMrover2: move initialisation of serial and gcs to AP_Vehicle

zr-v5.1
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
a6e1fce4bd
  1. 5
      APMrover2/GCS_Rover.cpp
  2. 2
      APMrover2/GCS_Rover.h
  3. 10
      APMrover2/system.cpp

5
APMrover2/GCS_Rover.cpp

@ -4,6 +4,11 @@ @@ -4,6 +4,11 @@
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
uint8_t GCS_Rover::sysid_this_mav() const
{
return rover.g.sysid_this_mav;
}
bool GCS_Rover::simple_input_active() const
{
if (rover.control_mode != &rover.mode_simple) {

2
APMrover2/GCS_Rover.h

@ -38,6 +38,8 @@ public: @@ -38,6 +38,8 @@ public:
protected:
uint8_t sysid_this_mav() const override;
GCS_MAVLINK_Rover *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params,
AP_HAL::UARTDriver &uart) override {
return new GCS_MAVLINK_Rover(params, uart);

10
APMrover2/system.cpp

@ -19,16 +19,6 @@ void Rover::init_ardupilot() @@ -19,16 +19,6 @@ void Rover::init_ardupilot()
g2.stats.init();
#endif
mavlink_system.sysid = g.sysid_this_mav;
// initialise serial ports
serial_manager.init();
// setup first port early to allow BoardConfig to report errors
gcs().setup_console();
register_scheduler_delay_callback();
BoardConfig.init();
#if HAL_WITH_UAVCAN
BoardConfig_CAN.init();

Loading…
Cancel
Save