void GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan) { _port = port; chan = mav_chan; switch (chan) { case MAVLINK_COMM_0: mavlink_comm_0_port = _port; initialised = true; break; case MAVLINK_COMM_1: mavlink_comm_1_port = _port; initialised = true; break; case MAVLINK_COMM_2: #if MAVLINK_COMM_NUM_BUFFERS > 2 mavlink_comm_2_port = _port; initialised = true; break; #endif default: // do nothing for unsupport mavlink channels break; } _queued_parameter = NULL; reset_cli_timeout(); }
void GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan) { if (!valid_channel(mav_chan)) { return; } _port = port; chan = mav_chan; mavlink_comm_port[chan] = _port; initialised = true; _queued_parameter = NULL; reset_cli_timeout(); }
void GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan) { // sanity check chan if (mav_chan >= MAVLINK_COMM_NUM_BUFFERS) { return; } _port = port; chan = mav_chan; mavlink_comm_port[chan] = _port; initialised = true; _queued_parameter = NULL; reset_cli_timeout(); }
void GCS_MAVLINK::init(AP_HAL::UARTDriver *port) { GCS_Class::init(port); if (port == (AP_HAL::BetterStream*)hal.uartA) { mavlink_comm_0_port = port; chan = MAVLINK_COMM_0; initialised = true; } else if (port == (AP_HAL::BetterStream*)hal.uartC) { mavlink_comm_1_port = port; chan = MAVLINK_COMM_1; initialised = true; #if MAVLINK_COMM_NUM_BUFFERS > 2 } else if (port == (AP_HAL::BetterStream*)hal.uartD) { mavlink_comm_2_port = port; chan = MAVLINK_COMM_2; initialised = true; #endif } _queued_parameter = NULL; reset_cli_timeout(); }