// get_mavlink_channel - provides the mavlink channel associated with a given protocol // instance should be zero if searching for the first instance, 1 for the second, etc // returns true if a channel is found, false if not bool AP_SerialManager::get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const { // check for console if (protocol == SerialProtocol_Console) { mav_chan = MAVLINK_COMM_0; return true; } // check for MAVLink if (protocol_match(protocol, SerialProtocol_MAVLink)) { if (instance == 0) { mav_chan = MAVLINK_COMM_1; return true; } if (instance == 1) { mav_chan = MAVLINK_COMM_2; return true; } if (instance == 2) { mav_chan = MAVLINK_COMM_3; return true; } } // report failure return false; }
// get_mavlink_channel - provides the mavlink channel associated with a given protocol // instance should be zero if searching for the first instance, 1 for the second, etc // returns true if a channel is found, false if not bool AP_SerialManager::get_mavlink_channel(enum SerialProtocol protocol, uint8_t instance, mavlink_channel_t &mav_chan) const { // check for MAVLink if (protocol_match(protocol, SerialProtocol_MAVLink)) { if (instance < MAVLINK_COMM_NUM_BUFFERS) { mav_chan = (mavlink_channel_t)(MAVLINK_COMM_0 + instance); return true; } } // report failure return false; }
// set_console_baud - sets the console's baud rate to the rate specified by the protocol void AP_SerialManager::set_console_baud(enum SerialProtocol protocol, uint8_t instance) const { uint8_t found_instance = 0; // find baud rate of this protocol for (uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) { if (protocol_match(protocol, (enum SerialProtocol)state[i].protocol.get())) { if (instance == found_instance) { // set console's baud rate state[0].uart->begin(map_baudrate(state[i].baud)); return; } found_instance++; } } }
// find_baudrate - searches available serial ports for the first instance that allows the given protocol // instance should be zero if searching for the first instance, 1 for the second, etc // returns baudrate on success, 0 if a serial port cannot be found uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t instance) const { uint8_t found_instance = 0; // search for matching protocol for(uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) { if (protocol_match(protocol, (enum SerialProtocol)state[i].protocol.get())) { if (found_instance == instance) { return map_baudrate(state[i].baud); } found_instance++; } } // if we got this far we did not find the uart return 0; }
// find_serial - searches available serial ports for the first instance that allows the given protocol // instance should be zero if searching for the first instance, 1 for the second, etc // returns uart on success, NULL if a serial port cannot be found AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol, uint8_t instance) const { uint8_t found_instance = 0; // search for matching protocol for(uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) { if (protocol_match(protocol, (enum SerialProtocol)state[i].protocol.get())) { if (found_instance == instance) { return state[i].uart; } found_instance++; } } // if we got this far we did not find the uart return NULL; }