diff --git a/ArduSub/GCS_Sub.cpp b/ArduSub/GCS_Sub.cpp index 4eab435095..c40196c9ae 100644 --- a/ArduSub/GCS_Sub.cpp +++ b/ArduSub/GCS_Sub.cpp @@ -2,6 +2,11 @@ #include "Sub.h" +uint8_t GCS_Sub::sysid_this_mav() const +{ + return sub.g.sysid_this_mav; +} + void GCS_Sub::update_vehicle_sensor_status_flags() { control_sensors_present |= diff --git a/ArduSub/GCS_Sub.h b/ArduSub/GCS_Sub.h index b2c7bfc5ea..7a8248573b 100644 --- a/ArduSub/GCS_Sub.h +++ b/ArduSub/GCS_Sub.h @@ -34,6 +34,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 diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index aa390403ce..17991ea15f 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -36,15 +36,6 @@ void Sub::init_ardupilot() celsius.init(1); #endif - // identify ourselves correctly with the ground station - mavlink_system.sysid = g.sysid_this_mav; - - // initialise serial port - serial_manager.init(); - - // setup first port early to allow BoardConfig to report errors - gcs().setup_console(); - // init cargo gripper #if GRIPPER_ENABLED == ENABLED g2.gripper.init(); @@ -62,8 +53,6 @@ void Sub::init_ardupilot() barometer.init(); - register_scheduler_delay_callback(); - // setup telem slots with serial ports gcs().setup_uarts();