APMrover2: move initialisation of serial and gcs to AP_Vehicle

This commit is contained in:
Peter Barker 2020-02-12 12:01:17 +11:00 committed by Andrew Tridgell
parent 2f159288e2
commit a6e1fce4bd
3 changed files with 7 additions and 10 deletions

View File

@ -4,6 +4,11 @@
#include <AP_RangeFinder/AP_RangeFinder_Backend.h> #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 bool GCS_Rover::simple_input_active() const
{ {
if (rover.control_mode != &rover.mode_simple) { if (rover.control_mode != &rover.mode_simple) {

View File

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

View File

@ -19,16 +19,6 @@ void Rover::init_ardupilot()
g2.stats.init(); g2.stats.init();
#endif #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(); BoardConfig.init();
#if HAL_WITH_UAVCAN #if HAL_WITH_UAVCAN
BoardConfig_CAN.init(); BoardConfig_CAN.init();