mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
GCS_MAVLink: move initialisation of serial and gcs to AP_Vehicle
This commit is contained in:
parent
2ede027635
commit
727c12c388
@ -33,6 +33,11 @@ const MAV_MISSION_TYPE GCS_MAVLINK::supported_mission_types[] = {
|
||||
MAV_MISSION_TYPE_FENCE,
|
||||
};
|
||||
|
||||
void GCS::init()
|
||||
{
|
||||
mavlink_system.sysid = sysid_this_mav();
|
||||
}
|
||||
|
||||
/*
|
||||
send a text message to all GCS
|
||||
*/
|
||||
|
@ -870,6 +870,7 @@ public:
|
||||
return 200;
|
||||
}
|
||||
|
||||
void init();
|
||||
void setup_console();
|
||||
void setup_uarts();
|
||||
|
||||
@ -908,6 +909,8 @@ public:
|
||||
|
||||
protected:
|
||||
|
||||
virtual uint8_t sysid_this_mav() const = 0;
|
||||
|
||||
virtual GCS_MAVLINK *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
||||
AP_HAL::UARTDriver &uart) = 0;
|
||||
|
||||
|
@ -64,6 +64,8 @@ public:
|
||||
|
||||
protected:
|
||||
|
||||
uint8_t sysid_this_mav() const override { return 1; }
|
||||
|
||||
GCS_MAVLINK_Dummy *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
||||
AP_HAL::UARTDriver &uart) override {
|
||||
return new GCS_MAVLINK_Dummy(params, uart);
|
||||
|
@ -28,6 +28,7 @@ static MAVLink_routing routing;
|
||||
void setup(void)
|
||||
{
|
||||
hal.console->printf("routing test startup...");
|
||||
gcs().init();
|
||||
gcs().setup_console();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user