Browse Source

ArduCopter: move initialisation of serial and gcs to AP_Vehicle

zr-v5.1
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
ae2578e5c9
  1. 5
      ArduCopter/GCS_Copter.cpp
  2. 2
      ArduCopter/GCS_Copter.h
  3. 11
      ArduCopter/system.cpp

5
ArduCopter/GCS_Copter.cpp

@ -2,6 +2,11 @@ @@ -2,6 +2,11 @@
#include "Copter.h"
uint8_t GCS_Copter::sysid_this_mav() const
{
return copter.g.sysid_this_mav;
}
const char* GCS_Copter::frame_string() const
{
return copter.get_frame_string();

2
ArduCopter/GCS_Copter.h

@ -39,6 +39,8 @@ public: @@ -39,6 +39,8 @@ public:
protected:
uint8_t sysid_this_mav() const override;
// minimum amount of time (in microseconds) that must remain in
// the main scheduler loop before we are allowed to send any
// mavlink messages. We want to prioritise the main flight

11
ArduCopter/system.cpp

@ -21,17 +21,6 @@ void Copter::init_ardupilot() @@ -21,17 +21,6 @@ void Copter::init_ardupilot()
g2.stats.init();
#endif
// identify ourselves correctly with the ground station
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