ArduSub: move initialisation of serial and gcs to AP_Vehicle

This commit is contained in:
Peter Barker 2020-02-12 12:01:18 +11:00 committed by Andrew Tridgell
parent 5ff1630c63
commit e5858555de
3 changed files with 7 additions and 11 deletions

View File

@ -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 |=

View File

@ -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

View File

@ -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();