// init - performs any required initialisation for this instance void AP_Mount_SToRM32::init(const AP_SerialManager& serial_manager) { // get_mavlink_channel for MAVLink2 if (serial_manager.get_mavlink_channel(AP_SerialManager::SerialProtocol_MAVLink2, _chan)) { _initialised = true; set_mode((enum MAV_MOUNT_MODE)_state._default_mode.get()); } }
/* setup a UART, handling begin() and init() */ void GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager::SerialProtocol protocol, uint8_t instance) { // search for serial port AP_HAL::UARTDriver *uart; uart = serial_manager.find_serial(protocol, instance); if (uart == NULL) { // return immediately if not found return; } // get associated mavlink channel mavlink_channel_t mav_chan; if (!serial_manager.get_mavlink_channel(protocol, instance, mav_chan)) { // return immediately in unlikely case mavlink channel cannot be found return; } /* Now try to cope with SiK radios that may be stuck in bootloader mode because CTS was held while powering on. This tells the bootloader to wait for a firmware. It affects any SiK radio with CTS connected that is externally powered. To cope we send 0x30 0x20 at 115200 on startup, which tells the bootloader to reset and boot normally */ uart->begin(115200); AP_HAL::UARTDriver::flow_control old_flow_control = uart->get_flow_control(); uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); for (uint8_t i=0; i<3; i++) { hal.scheduler->delay(1); uart->write(0x30); uart->write(0x20); } // since tcdrain() and TCSADRAIN may not be implemented... hal.scheduler->delay(1); uart->set_flow_control(old_flow_control); // now change back to desired baudrate uart->begin(serial_manager.find_baudrate(protocol, instance)); // and init the gcs instance init(uart, mav_chan); }