mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
ArduPlane: move initialisation of serial and gcs to AP_Vehicle
This commit is contained in:
parent
ae2578e5c9
commit
5ff1630c63
@ -1,6 +1,11 @@
|
||||
#include "GCS_Plane.h"
|
||||
#include "Plane.h"
|
||||
|
||||
uint8_t GCS_Plane::sysid_this_mav() const
|
||||
{
|
||||
return plane.g.sysid_this_mav;
|
||||
}
|
||||
|
||||
void GCS_Plane::update_vehicle_sensor_status_flags(void)
|
||||
{
|
||||
// first what sensors/controllers we have
|
||||
|
@ -27,6 +27,7 @@ public:
|
||||
|
||||
protected:
|
||||
|
||||
uint8_t sysid_this_mav() const override;
|
||||
void update_vehicle_sensor_status_flags(void) override;
|
||||
uint32_t custom_mode() const override;
|
||||
MAV_TYPE frame_type() const override;
|
||||
|
@ -869,7 +869,7 @@ private:
|
||||
void update_fbwb_speed_height(void);
|
||||
void setup_turn_angle(void);
|
||||
bool reached_loiter_target(void);
|
||||
void set_control_channels(void);
|
||||
void set_control_channels(void) override;
|
||||
void init_rc_in();
|
||||
void init_rc_out_main();
|
||||
void init_rc_out_aux();
|
||||
|
@ -31,16 +31,6 @@ void Plane::init_ardupilot()
|
||||
|
||||
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
|
||||
|
||||
set_control_channels();
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
||||
// initialise serial ports
|
||||
serial_manager.init();
|
||||
gcs().setup_console();
|
||||
|
||||
register_scheduler_delay_callback();
|
||||
|
||||
// setup any board specific drivers
|
||||
BoardConfig.init();
|
||||
#if HAL_WITH_UAVCAN
|
||||
|
Loading…
Reference in New Issue
Block a user