mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: integrate SerialManager
call SerialManager init_console on startup use SerialManager's set_block_writes_all
This commit is contained in:
parent
5f432eaa2d
commit
3a1465c9d1
@ -59,6 +59,7 @@
|
||||
#include <AP_AutoTune.h>
|
||||
#include <GCS.h>
|
||||
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
#include <AP_SerialManager.h> // Serial manager library
|
||||
#include <AP_Mount.h> // Camera/Antenna mount
|
||||
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||
#include <DataFlash.h>
|
||||
@ -258,6 +259,7 @@ static bool in_calibration;
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// GCS selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
static AP_SerialManager serial_manager;
|
||||
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
||||
static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS];
|
||||
|
||||
|
@ -107,9 +107,9 @@ public:
|
||||
k_param_gps,
|
||||
k_param_autotune_level,
|
||||
k_param_rally,
|
||||
k_param_serial0_baud,
|
||||
k_param_serial1_baud,
|
||||
k_param_serial2_baud,
|
||||
k_param_serial0_baud, // deprecated
|
||||
k_param_serial1_baud, // deprecated
|
||||
k_param_serial2_baud, // deprecated
|
||||
k_param_takeoff_tdrag_elevator,
|
||||
k_param_takeoff_tdrag_speed1,
|
||||
k_param_takeoff_rotate_speed,
|
||||
@ -153,7 +153,7 @@ public:
|
||||
k_param_serial0_baud_old, // deprecated
|
||||
k_param_gcs2, // stream rates for uartD
|
||||
k_param_serial2_baud_old, // deprecated
|
||||
k_param_serial2_protocol,
|
||||
k_param_serial2_protocol, // deprecated
|
||||
|
||||
// 120: Fly-by-wire control
|
||||
//
|
||||
@ -187,6 +187,7 @@ public:
|
||||
k_param_curr_amp_offset,
|
||||
k_param_NavEKF, // Extended Kalman Filter Inertial Navigation Group
|
||||
k_param_mission, // mission library
|
||||
k_param_serial_manager, // serial manager library
|
||||
|
||||
//
|
||||
// 150: Navigation parameters
|
||||
@ -320,12 +321,6 @@ public:
|
||||
//
|
||||
AP_Int16 sysid_this_mav;
|
||||
AP_Int16 sysid_my_gcs;
|
||||
AP_Int16 serial0_baud;
|
||||
AP_Int16 serial1_baud;
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
AP_Int16 serial2_baud;
|
||||
AP_Int8 serial2_protocol;
|
||||
#endif
|
||||
AP_Int8 telem_delay;
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
|
@ -38,38 +38,9 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @User: Advanced
|
||||
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
|
||||
|
||||
// @Param: SERIAL0_BAUD
|
||||
// @DisplayName: USB Console Baud Rate
|
||||
// @Description: The baud rate used on the USB console. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,500:500000,921:921600,1500:1500000
|
||||
// @User: Standard
|
||||
GSCALAR(serial0_baud, "SERIAL0_BAUD", SERIAL0_BAUD/1000),
|
||||
|
||||
// @Param: SERIAL1_BAUD
|
||||
// @DisplayName: Telemetry Baud Rate
|
||||
// @Description: The baud rate used on the first telemetry port. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,500:500000,921:921600,1500:1500000
|
||||
// @User: Standard
|
||||
GSCALAR(serial1_baud, "SERIAL1_BAUD", SERIAL1_BAUD/1000),
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
// @Param: SERIAL2_BAUD
|
||||
// @DisplayName: Telemetry Baud Rate
|
||||
// @Description: The baud rate used on the second telemetry port. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,500:500000,921:921600,1500:1500000
|
||||
// @User: Standard
|
||||
GSCALAR(serial2_baud, "SERIAL2_BAUD", SERIAL2_BAUD/1000),
|
||||
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
// @Param: SERIAL2_PROTOCOL
|
||||
// @DisplayName: SERIAL2 protocol selection
|
||||
// @Description: Control what protocol telemetry 2 port should be used for
|
||||
// @Values: 1:GCS Mavlink,2:Frsky D-PORT,3:Frsky S-PORT
|
||||
// @User: Standard
|
||||
GSCALAR(serial2_protocol, "SERIAL2_PROTOCOL", SERIAL2_MAVLINK),
|
||||
#endif // FRSKY_TELEM_ENABLED
|
||||
|
||||
#endif // MAVLINK_COMM_NUM_BUFFERS
|
||||
// @Group: SERIAL
|
||||
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
|
||||
GOBJECT(serial_manager, "SERIAL", AP_SerialManager),
|
||||
|
||||
// @Param: AUTOTUNE_LEVEL
|
||||
// @DisplayName: Autotune level
|
||||
@ -1189,6 +1160,9 @@ const AP_Param::ConversionInfo conversion_table[] PROGMEM = {
|
||||
{ Parameters::k_param_log_bitmask_old, 0, AP_PARAM_INT16, "LOG_BITMASK" },
|
||||
{ Parameters::k_param_rally_limit_km_old, 0, AP_PARAM_FLOAT, "RALLY_LIMIT_KM" },
|
||||
{ Parameters::k_param_rally_total_old, 0, AP_PARAM_INT8, "RALLY_TOTAL" },
|
||||
{ Parameters::k_param_serial0_baud, 0, AP_PARAM_INT16, "SERIAL0_BAUD" },
|
||||
{ Parameters::k_param_serial1_baud, 0, AP_PARAM_INT16, "SERIAL1_BAUD" },
|
||||
{ Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },
|
||||
};
|
||||
|
||||
static void load_parameters(void)
|
||||
|
@ -60,10 +60,6 @@
|
||||
#define CONFIG_BARO HAL_BARO_DEFAULT
|
||||
#define CONFIG_COMPASS HAL_COMPASS_DEFAULT
|
||||
|
||||
#ifdef HAL_SERIAL0_BAUD_DEFAULT
|
||||
# define SERIAL0_BAUD HAL_SERIAL0_BAUD_DEFAULT
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// HIL_MODE OPTIONAL
|
||||
|
||||
@ -82,19 +78,6 @@
|
||||
# define MAV_SYSTEM_ID 1
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Serial port speeds.
|
||||
//
|
||||
#ifndef SERIAL0_BAUD
|
||||
# define SERIAL0_BAUD 115200
|
||||
#endif
|
||||
#ifndef SERIAL1_BAUD
|
||||
# define SERIAL1_BAUD 57600
|
||||
#endif
|
||||
#ifndef SERIAL2_BAUD
|
||||
# define SERIAL2_BAUD 57600
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FrSky telemetry support
|
||||
//
|
||||
@ -482,20 +465,6 @@
|
||||
#define CLI_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
#ifndef SERIAL_BUFSIZE
|
||||
# define SERIAL_BUFSIZE 512
|
||||
#endif
|
||||
|
||||
#ifndef SERIAL1_BUFSIZE
|
||||
# define SERIAL1_BUFSIZE 256
|
||||
#endif
|
||||
|
||||
#ifndef SERIAL2_BUFSIZE
|
||||
# define SERIAL2_BUFSIZE 256
|
||||
#endif
|
||||
|
||||
/*
|
||||
build a firmware version string.
|
||||
GIT_VERSION comes from Makefile builds
|
||||
|
@ -201,10 +201,4 @@ enum {
|
||||
ATT_CONTROL_APMCONTROL = 1
|
||||
};
|
||||
|
||||
enum Serial2Protocol {
|
||||
SERIAL2_MAVLINK = 1,
|
||||
SERIAL2_FRSKY_DPORT = 2,
|
||||
SERIAL2_FRSKY_SPORT = 3 // not supported yet
|
||||
};
|
||||
|
||||
#endif // _DEFINES_H
|
||||
|
@ -70,12 +70,8 @@ static void run_cli(AP_HAL::UARTDriver *port)
|
||||
|
||||
static void init_ardupilot()
|
||||
{
|
||||
// Console serial port
|
||||
//
|
||||
// The console port buffers are defined to be sufficiently large to support
|
||||
// the MAVLink protocol efficiently
|
||||
//
|
||||
hal.uartA->begin(SERIAL0_BAUD, 128, SERIAL_BUFSIZE);
|
||||
// initialise serial port
|
||||
serial_manager.init_console();
|
||||
|
||||
cliSerial->printf_P(PSTR("\n\nInit " FIRMWARE_STRING
|
||||
"\n\nFree RAM: %u\n"),
|
||||
@ -95,14 +91,14 @@ static void init_ardupilot()
|
||||
|
||||
BoardConfig.init();
|
||||
|
||||
// initialise serial ports
|
||||
serial_manager.init();
|
||||
|
||||
// allow servo set on all channels except first 4
|
||||
ServoRelayEvents.set_channel_mask(0xFFF0);
|
||||
|
||||
set_control_channels();
|
||||
|
||||
// reset the uartA baud rate after parameter load
|
||||
hal.uartA->begin(map_baudrate(g.serial0_baud));
|
||||
|
||||
// keep a record of how many resets have happened. This can be
|
||||
// used to detect in-flight resets
|
||||
g.num_resets.set_and_save(g.num_resets+1);
|
||||
@ -117,23 +113,24 @@ static void init_ardupilot()
|
||||
battery.init();
|
||||
|
||||
// init the GCS
|
||||
gcs[0].init(hal.uartA);
|
||||
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_Console);
|
||||
|
||||
// we start by assuming USB connected, as we initialed the serial
|
||||
// port with SERIAL0_BAUD. check_usb_mux() fixes this if need be.
|
||||
usb_connected = true;
|
||||
check_usb_mux();
|
||||
|
||||
// we have a 2nd serial port for telemetry
|
||||
gcs[1].setup_uart(hal.uartC, map_baudrate(g.serial1_baud), 128, SERIAL1_BUFSIZE);
|
||||
// setup serial port for telem1
|
||||
gcs[1].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink1);
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
if (g.serial2_protocol == SERIAL2_FRSKY_DPORT ||
|
||||
g.serial2_protocol == SERIAL2_FRSKY_SPORT) {
|
||||
frsky_telemetry.init(hal.uartD, (AP_Frsky_Telem::FrSkyProtocol)g.serial2_protocol.get());
|
||||
} else {
|
||||
gcs[2].setup_uart(hal.uartD, map_baudrate(g.serial2_baud), 128, SERIAL2_BUFSIZE);
|
||||
}
|
||||
// setup serial port for telem2
|
||||
gcs[2].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink2);
|
||||
#endif
|
||||
|
||||
// setup frsky
|
||||
#if FRSKY_TELEM_ENABLED == ENABLED
|
||||
frsky_telemetry.init(serial_manager);
|
||||
#endif
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
@ -179,7 +176,7 @@ static void init_ardupilot()
|
||||
ahrs.set_airspeed(&airspeed);
|
||||
|
||||
// GPS Initialization
|
||||
gps.init(&DataFlash);
|
||||
gps.init(&DataFlash, serial_manager);
|
||||
|
||||
init_rc_in(); // sets up rc channels from radio
|
||||
init_rc_out(); // sets up the timer libs
|
||||
@ -187,7 +184,7 @@ static void init_ardupilot()
|
||||
relay.init();
|
||||
|
||||
// initialise camera mount
|
||||
camera_mount.init();
|
||||
camera_mount.init(serial_manager);
|
||||
|
||||
#if FENCE_TRIGGERED_PIN > 0
|
||||
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
|
||||
@ -200,14 +197,16 @@ static void init_ardupilot()
|
||||
*/
|
||||
hal.scheduler->register_timer_failsafe(failsafe_check, 1000);
|
||||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
const prog_char_t *msg = PSTR("\nPress ENTER 3 times to start interactive setup\n");
|
||||
cliSerial->println_P(msg);
|
||||
if (gcs[1].initialised) {
|
||||
hal.uartC->println_P(msg);
|
||||
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
|
||||
gcs[1].get_uart()->println_P(msg);
|
||||
}
|
||||
if (num_gcs > 2 && gcs[2].initialised) {
|
||||
hal.uartD->println_P(msg);
|
||||
if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != NULL)) {
|
||||
gcs[2].get_uart()->println_P(msg);
|
||||
}
|
||||
#endif // CLI_ENABLED
|
||||
|
||||
startup_ground();
|
||||
if (should_log(MASK_LOG_CMD))
|
||||
@ -279,12 +278,7 @@ static void startup_ground(void)
|
||||
// we don't want writes to the serial port to cause us to pause
|
||||
// mid-flight, so set the serial ports non-blocking once we are
|
||||
// ready to fly
|
||||
hal.uartA->set_blocking_writes(false);
|
||||
hal.uartB->set_blocking_writes(false);
|
||||
hal.uartC->set_blocking_writes(false);
|
||||
if (hal.uartD != NULL) {
|
||||
hal.uartD->set_blocking_writes(false);
|
||||
}
|
||||
serial_manager.set_blocking_writes_all(false);
|
||||
|
||||
gcs_send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY."));
|
||||
}
|
||||
@ -583,9 +577,9 @@ static void check_usb_mux(void)
|
||||
// SERIAL0_BAUD, but when connected as a TTL serial port we run it
|
||||
// at SERIAL1_BAUD.
|
||||
if (usb_connected) {
|
||||
hal.uartA->begin(SERIAL0_BAUD);
|
||||
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_Console);
|
||||
} else {
|
||||
hal.uartA->begin(map_baudrate(g.serial1_baud));
|
||||
serial_manager.set_console_baud(AP_SerialManager::SerialProtocol_MAVLink1);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user