void downstream_handler(mavlink_channel_t from, mavlink_message_t* msg) { switch (msg->msgid) { case MAVLINK_MSG_ID_HEARTBEAT: downstream_handle_heartbeat(msg); _mavlink_resend_uart(downstream_channel, msg); break; case MAVLINK_MSG_ID_GPS_RAW_INT: downstream_handle_gps(msg); _mavlink_resend_uart(downstream_channel, msg); break; default: _mavlink_resend_uart(downstream_channel, msg); } }
//TODO: handle full txspace properly void DataFlash_MAVLink::send_log_block(uint32_t block_address) { mavlink_channel_t chan = mavlink_channel_t(_chan - MAVLINK_COMM_0); if (!_initialised || comm_get_txspace(chan) < 255){ return; } mavlink_message_t msg; mavlink_status_t *chan_status = mavlink_get_channel_status(chan); uint8_t saved_seq = chan_status->current_tx_seq; chan_status->current_tx_seq = mavlink.seq++; Debug("Data Sent!!\n"); uint16_t len = mavlink_msg_remote_log_data_block_pack(mavlink.system_id, mavlink.component_id, &msg, 255, //GCS SYS ID 0, _block_max_size, _block_num[block_address], _buf[block_address]); if(comm_get_txspace(chan) < len){ return; } chan_status->current_tx_seq = saved_seq; _mavlink_resend_uart(chan, &msg); }
/* forward a MAVLink message to the right port. This also automatically learns the route for the sender if it is not already known. This returns true if the message should be processed locally Theory of MAVLink routing: When a flight controller receives a message it should process it locally if any of these conditions hold: 1a) the message has no target_system field 1b) the message has a target_system of zero 1c) the message has the flight controllers target system and has no target_component field 1d) the message has the flight controllers target system and has the flight controllers target_component 1e) the message has the flight controllers target system and the flight controller has not seen any messages on any of its links from a system that has the messages target_system/target_component combination When a flight controller receives a message it should forward it onto another different link if any of these conditions hold for that link: 2a) the message has no target_system field 2b) the message has a target_system of zero 2c) the message does not have the flight controllers target_system and the flight controller has seen a message from the messages target_system on the link 2d) the message has the flight controllers target_system and has a target_component field and the flight controllers has seen a message from the target_system/target_component combination on the link Note: This proposal assumes that ground stations will not send command packets to a non-broadcast destination (sysid/compid combination) until they have received at least one package from that destination over the link. This is essential to prevent a flight controller from acting on a message that is not meant for it. For example, a PARAM_SET cannot be sent to a specific sysid/compid combination until the GCS has seen a packet from that sysid/compid combination on the link. The GCS must also reset what sysid/compid combinations it has seen on a link when it sees a SYSTEM_TIME message with a decrease in time_boot_ms from a particular sysid/compid. That is essential to detect a reset of the flight controller, which implies a reset of its routing table. */ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavlink_message_t* msg) { // learn new routes learn_route(in_channel, msg); if (msg->msgid == MAVLINK_MSG_ID_HEARTBEAT) { // heartbeat needs special handling handle_heartbeat(in_channel, msg); return true; } // extract the targets for this packet int16_t target_system = -1; int16_t target_component = -1; get_targets(msg, target_system, target_component); bool broadcast_system = (target_system == 0 || target_system == -1); bool broadcast_component = (target_component == 0 || target_component == -1); bool match_system = broadcast_system || (target_system == mavlink_system.sysid); bool match_component = match_system && (broadcast_component || (target_component == mavlink_system.compid)); bool process_locally = match_system && match_component; if (process_locally && !broadcast_system && !broadcast_component) { // nothing more to do - it can only be for us return true; } // forward on any channels matching the targets bool forwarded = false; for (uint8_t i=0; i<num_routes; i++) { if (broadcast_system || (target_system == routes[i].sysid && (broadcast_component || target_component == routes[i].compid))) { if (in_channel != routes[i].channel) { if (comm_get_txspace(routes[i].channel) >= ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES) { #if ROUTING_DEBUG ::printf("fwd msg %u from chan %u on chan %u sysid=%u compid=%u\n", msg->msgid, (unsigned)in_channel, (unsigned)routes[i].channel, (unsigned)target_system, (unsigned)target_component); #endif _mavlink_resend_uart(routes[i].channel, msg); } forwarded = true; } } } if (!forwarded && match_system) { process_locally = true; } return process_locally; }
//TODO: handle full txspace properly bool DataFlash_MAVLink::send_log_block(struct dm_block &block) { mavlink_channel_t chan = mavlink_channel_t(_chan - MAVLINK_COMM_0); if (!_initialised) { return false; } if (!HAVE_PAYLOAD_SPACE(chan, REMOTE_LOG_DATA_BLOCK)) { return false; } if (comm_get_txspace(chan) < 500) { return false; } #if CONFIG_HAL_BOARD == HAL_BOARD_SITL if (rand() < 0.1) { return false; } #endif #if DF_MAVLINK_DISABLE_INTERRUPTS irqstate_t istate = irqsave(); #endif // DM_packing: 267039 events, 0 overruns, 8440834us elapsed, 31us avg, min 31us max 32us 0.488us rms hal.util->perf_begin(_perf_packing); mavlink_message_t msg; mavlink_status_t *chan_status = mavlink_get_channel_status(chan); uint8_t saved_seq = chan_status->current_tx_seq; chan_status->current_tx_seq = mavlink_seq++; // Debug("Sending block (%d)", block.seqno); mavlink_msg_remote_log_data_block_pack(mavlink_system.sysid, MAV_COMP_ID_LOG, &msg, _target_system_id, _target_component_id, block.seqno, block.buf); hal.util->perf_end(_perf_packing); #if DF_MAVLINK_DISABLE_INTERRUPTS irqrestore(istate); #endif block.last_sent = AP_HAL::millis(); chan_status->current_tx_seq = saved_seq; // _last_send_time is set even if we fail to send the packet; if // the txspace is repeatedly chockas we should not add to the // problem and stop attempting to log _last_send_time = AP_HAL::millis(); _mavlink_resend_uart(chan, &msg); return true; }
bool MavlinkParametersManager::send_uavcan() { /* Send parameter values received from the UAVCAN topic */ if (_uavcan_parameter_value_sub < 0) { _uavcan_parameter_value_sub = orb_subscribe(ORB_ID(uavcan_parameter_value)); } bool param_value_ready; orb_check(_uavcan_parameter_value_sub, ¶m_value_ready); if (param_value_ready) { struct uavcan_parameter_value_s value; orb_copy(ORB_ID(uavcan_parameter_value), _uavcan_parameter_value_sub, &value); // Check if we received a matching parameter, drop it from the list and request the next if (value.param_index == _uavcan_open_request_list->req.param_index && value.node_id == _uavcan_open_request_list->req.node_id) { dequeue_uavcan_request(); request_next_uavcan_parameter(); } mavlink_param_value_t msg; msg.param_count = value.param_count; msg.param_index = value.param_index; /* * coverity[buffer_size_warning : FALSE] * * The MAVLink spec does not require the string to be NUL-terminated if it * has length 16. In this case the receiving end needs to terminate it * when copying it. */ strncpy(msg.param_id, value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); if (value.param_type == MAV_PARAM_TYPE_REAL32) { msg.param_type = MAVLINK_TYPE_FLOAT; msg.param_value = value.real_value; } else { int32_t val; val = (int32_t)value.int_value; memcpy(&msg.param_value, &val, sizeof(int32_t)); msg.param_type = MAVLINK_TYPE_INT32_T; } // Re-pack the message with the UAVCAN node ID mavlink_message_t mavlink_packet; mavlink_msg_param_value_encode_chan(mavlink_system.sysid, value.node_id, _mavlink->get_channel(), &mavlink_packet, &msg); _mavlink_resend_uart(_mavlink->get_channel(), &mavlink_packet); return true; } return false; }
/* special handling for heartbeat messages. To ensure routing propagation heartbeat messages need to be forwarded on all channels except channels where the sysid/compid of the heartbeat could come from */ void MAVLink_routing::handle_heartbeat(mavlink_channel_t in_channel, const mavlink_message_t* msg) { if (msg->compid == MAV_COMP_ID_GIMBAL) { return; } uint16_t mask = GCS_MAVLINK::active_channel_mask(); // don't send on the incoming channel. This should only matter if // the routing table is full mask &= ~(1U<<(in_channel-MAVLINK_COMM_0)); // mask out channels that do not want the heartbeat to be forwarded mask &= ~no_route_mask; // mask out channels that are known sources for this sysid/compid for (uint8_t i=0; i<num_routes; i++) { if (routes[i].sysid == msg->sysid && routes[i].compid == msg->compid) { mask &= ~(1U<<((unsigned)(routes[i].channel-MAVLINK_COMM_0))); } } if (mask == 0) { // nothing to send to return; } // send on the remaining channels for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) { if (mask & (1U<<i)) { mavlink_channel_t channel = (mavlink_channel_t)(MAVLINK_COMM_0 + i); if (comm_get_txspace(channel) >= ((uint16_t)msg->len) + GCS_MAVLINK::packet_overhead_chan(channel)) { #if ROUTING_DEBUG ::printf("fwd HB from chan %u on chan %u from sysid=%u compid=%u\n", (unsigned)in_channel, (unsigned)channel, (unsigned)msg->sysid, (unsigned)msg->compid); #endif _mavlink_resend_uart(channel, msg); } } } }
//TODO: handle full txspace properly bool DataFlash_MAVLink::send_log_block(struct dm_block &block) { mavlink_channel_t chan = mavlink_channel_t(_chan - MAVLINK_COMM_0); if (!_initialised) { return false; } if (comm_get_txspace(chan) < MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN) { return false; } if (comm_get_txspace(chan) < 500) { return false; } #if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL if (rand() < 0.1) { return false; } #endif mavlink_message_t msg; mavlink_status_t *chan_status = mavlink_get_channel_status(chan); uint8_t saved_seq = chan_status->current_tx_seq; chan_status->current_tx_seq = mavlink_seq++; // Debug("Sending block (%d)", block.seqno); mavlink_msg_remote_log_data_block_pack(mavlink_system.sysid, MAV_COMP_ID_LOG, &msg, _target_system_id, _target_component_id, block.seqno, block.buf); block.last_sent = hal.scheduler->millis(); chan_status->current_tx_seq = saved_seq; // _last_send_time is set even if we fail to send the packet; if // the txspace is repeatedly chockas we should not add to the // problem and stop attempting to log _last_send_time = hal.scheduler->millis(); _mavlink_resend_uart(chan, &msg); return true; }
/* send a MAVLink message to all components with this vehicle's system id This is a no-op if no routes to components have been learned */ void MAVLink_routing::send_to_components(const mavlink_message_t* msg) { bool sent_to_chan[MAVLINK_COMM_NUM_BUFFERS]; memset(sent_to_chan, 0, sizeof(sent_to_chan)); // check learned routes for (uint8_t i=0; i<num_routes; i++) { if ((routes[i].sysid == mavlink_system.sysid) && !sent_to_chan[routes[i].channel]) { if (comm_get_txspace(routes[i].channel) >= ((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES) { #if ROUTING_DEBUG ::printf("send msg %u on chan %u sysid=%u compid=%u\n", msg->msgid, (unsigned)routes[i].channel, (unsigned)routes[i].sysid, (unsigned)routes[i].compid); #endif _mavlink_resend_uart(routes[i].channel, msg); sent_to_chan[routes[i].channel] = true; } } } }
/* forward a MAVLink message to the right port. This also automatically learns the route for the sender if it is not already known. This returns true if the message should be processed locally Theory of MAVLink routing: When a flight controller receives a message it should process it locally if any of these conditions hold: 1a) the message has no target_system field 1b) the message has a target_system of zero 1c) the message has the flight controllers target system and has no target_component field 1d) the message has the flight controllers target system and has the flight controllers target_component 1e) the message has the flight controllers target system and the flight controller has not seen any messages on any of its links from a system that has the messages target_system/target_component combination When a flight controller receives a message it should forward it onto another different link if any of these conditions hold for that link: 2a) the message has no target_system field 2b) the message has a target_system of zero 2c) the message does not have the flight controllers target_system and the flight controller has seen a message from the messages target_system on the link 2d) the message has the flight controllers target_system and has a target_component field and the flight controllers has seen a message from the target_system/target_component combination on the link Note: This proposal assumes that ground stations will not send command packets to a non-broadcast destination (sysid/compid combination) until they have received at least one package from that destination over the link. This is essential to prevent a flight controller from acting on a message that is not meant for it. For example, a PARAM_SET cannot be sent to a specific sysid/compid combination until the GCS has seen a packet from that sysid/compid combination on the link. The GCS must also reset what sysid/compid combinations it has seen on a link when it sees a SYSTEM_TIME message with a decrease in time_boot_ms from a particular sysid/compid. That is essential to detect a reset of the flight controller, which implies a reset of its routing table. */ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavlink_message_t* msg) { // handle the case of loopback of our own messages, due to // incorrect serial configuration. if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) { return true; } // learn new routes learn_route(in_channel, msg); if (msg->msgid == MAVLINK_MSG_ID_RADIO || msg->msgid == MAVLINK_MSG_ID_RADIO_STATUS) { // don't forward RADIO packets return true; } if (msg->msgid == MAVLINK_MSG_ID_HEARTBEAT) { // heartbeat needs special handling handle_heartbeat(in_channel, msg); return true; } // extract the targets for this packet int16_t target_system = -1; int16_t target_component = -1; get_targets(msg, target_system, target_component); bool broadcast_system = (target_system == 0 || target_system == -1); bool broadcast_component = (target_component == 0 || target_component == -1); bool match_system = broadcast_system || (target_system == mavlink_system.sysid); bool match_component = match_system && (broadcast_component || (target_component == mavlink_system.compid)); bool process_locally = match_system && match_component; if (process_locally && !broadcast_system && !broadcast_component) { // nothing more to do - it can only be for us return true; } // forward on any channels matching the targets bool forwarded = false; bool sent_to_chan[MAVLINK_COMM_NUM_BUFFERS]; memset(sent_to_chan, 0, sizeof(sent_to_chan)); for (uint8_t i=0; i<num_routes; i++) { if (broadcast_system || (target_system == routes[i].sysid && (broadcast_component || target_component == routes[i].compid || !match_system))) { if (in_channel != routes[i].channel && !sent_to_chan[routes[i].channel]) { if (comm_get_txspace(routes[i].channel) >= ((uint16_t)msg->len) + GCS_MAVLINK::packet_overhead_chan(routes[i].channel)) { #if ROUTING_DEBUG ::printf("fwd msg %u from chan %u on chan %u sysid=%d compid=%d\n", msg->msgid, (unsigned)in_channel, (unsigned)routes[i].channel, (int)target_system, (int)target_component); #endif _mavlink_resend_uart(routes[i].channel, msg); } sent_to_chan[routes[i].channel] = true; forwarded = true; } } } if (!forwarded && match_system) { process_locally = true; } return process_locally; }
int MavlinkParametersManager::send_param(param_t param, int component_id) { if (param == PARAM_INVALID) { return 1; } /* no free TX buf to send this param */ if (_mavlink->get_free_tx_buf() < MAVLINK_MSG_ID_PARAM_VALUE_LEN) { return 1; } mavlink_param_value_t msg; /* * get param value, since MAVLink encodes float and int params in the same * space during transmission, copy param onto float val_buf */ if (param_get(param, &msg.param_value) != OK) { return 2; } msg.param_count = param_count_used(); msg.param_index = param_get_used_index(param); #if defined(__GNUC__) && __GNUC__ >= 8 #pragma GCC diagnostic ignored "-Wstringop-truncation" #endif /* * coverity[buffer_size_warning : FALSE] * * The MAVLink spec does not require the string to be NUL-terminated if it * has length 16. In this case the receiving end needs to terminate it * when copying it. */ strncpy(msg.param_id, param_name(param), MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); #if defined(__GNUC__) && __GNUC__ >= 8 #pragma GCC diagnostic pop #endif /* query parameter type */ param_type_t type = param_type(param); /* * Map onboard parameter type to MAVLink type, * endianess matches (both little endian) */ if (type == PARAM_TYPE_INT32) { msg.param_type = MAVLINK_TYPE_INT32_T; } else if (type == PARAM_TYPE_FLOAT) { msg.param_type = MAVLINK_TYPE_FLOAT; } else { msg.param_type = MAVLINK_TYPE_FLOAT; } /* default component ID */ if (component_id < 0) { mavlink_msg_param_value_send_struct(_mavlink->get_channel(), &msg); } else { // Re-pack the message with a different component ID mavlink_message_t mavlink_packet; mavlink_msg_param_value_encode_chan(mavlink_system.sysid, component_id, _mavlink->get_channel(), &mavlink_packet, &msg); _mavlink_resend_uart(_mavlink->get_channel(), &mavlink_packet); } return 0; }
int Mavlink::task_main(int argc, char *argv[]) { int ch; _baudrate = 57600; _datarate = 0; _mode = MAVLINK_MODE_NORMAL; /* work around some stupidity in task_create's argv handling */ argc -= 2; argv += 2; /* don't exit from getopt loop to leave getopt global variables in consistent state, * set error flag instead */ bool err_flag = false; while ((ch = getopt(argc, argv, "b:r:d:m:fpvwx")) != EOF) { switch (ch) { case 'b': _baudrate = strtoul(optarg, NULL, 10); if (_baudrate < 9600 || _baudrate > 921600) { warnx("invalid baud rate '%s'", optarg); err_flag = true; } break; case 'r': _datarate = strtoul(optarg, NULL, 10); if (_datarate < 10 || _datarate > MAX_DATA_RATE) { warnx("invalid data rate '%s'", optarg); err_flag = true; } break; case 'd': _device_name = optarg; break; // case 'e': // mavlink_link_termination_allowed = true; // break; case 'm': if (strcmp(optarg, "custom") == 0) { _mode = MAVLINK_MODE_CUSTOM; } else if (strcmp(optarg, "camera") == 0) { _mode = MAVLINK_MODE_CAMERA; } break; case 'f': _forwarding_on = true; break; case 'p': _passing_on = true; break; case 'v': _verbose = true; break; case 'w': _wait_to_transmit = true; break; case 'x': _ftp_on = true; break; default: err_flag = true; break; } } if (err_flag) { usage(); return ERROR; } if (_datarate == 0) { /* convert bits to bytes and use 1/2 of bandwidth by default */ _datarate = _baudrate / 20; } if (_datarate > MAX_DATA_RATE) { _datarate = MAX_DATA_RATE; } if (Mavlink::instance_exists(_device_name, this)) { warnx("mavlink instance for %s already running", _device_name); return ERROR; } /* inform about mode */ switch (_mode) { case MAVLINK_MODE_NORMAL: warnx("mode: NORMAL"); break; case MAVLINK_MODE_CUSTOM: warnx("mode: CUSTOM"); break; case MAVLINK_MODE_CAMERA: warnx("mode: CAMERA"); break; default: warnx("ERROR: Unknown mode"); break; } warnx("data rate: %d Bytes/s, port: %s, baud: %d", _datarate, _device_name, _baudrate); /* flush stdout in case MAVLink is about to take it over */ fflush(stdout); struct termios uart_config_original; /* default values for arguments */ _uart_fd = mavlink_open_uart(_baudrate, _device_name, &uart_config_original, &_is_usb_uart); if (_uart_fd < 0) { warn("could not open %s", _device_name); return ERROR; } /* initialize mavlink text message buffering */ mavlink_logbuffer_init(&_logbuffer, 5); /* if we are passing on mavlink messages, we need to prepare a buffer for this instance */ if (_passing_on || _ftp_on) { /* initialize message buffer if multiplexing is on or its needed for FTP. * make space for two messages plus off-by-one space as we use the empty element * marker ring buffer approach. */ if (OK != message_buffer_init(2 * MAVLINK_MAX_PACKET_LEN + 2)) { errx(1, "can't allocate message buffer, exiting"); } /* initialize message buffer mutex */ pthread_mutex_init(&_message_buffer_mutex, NULL); } /* create the device node that's used for sending text log messages, etc. */ register_driver(MAVLINK_LOG_DEVICE, &fops, 0666, NULL); /* initialize logging device */ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); /* Initialize system properties */ mavlink_update_system(); /* start the MAVLink receiver */ _receive_thread = MavlinkReceiver::receive_start(this); _mission_result_sub = orb_subscribe(ORB_ID(mission_result)); /* create mission manager */ _mission_manager = new MavlinkMissionManager(this); _mission_manager->set_verbose(_verbose); _task_running = true; MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update)); uint64_t param_time = 0; MavlinkOrbSubscription *status_sub = add_orb_subscription(ORB_ID(vehicle_status)); uint64_t status_time = 0; struct vehicle_status_s status; status_sub->update(&status_time, &status); MavlinkCommandsStream commands_stream(this, _channel); /* add default streams depending on mode and intervals depending on datarate */ float rate_mult = get_rate_mult(); configure_stream("HEARTBEAT", 1.0f); switch (_mode) { case MAVLINK_MODE_NORMAL: configure_stream("SYS_STATUS", 1.0f); configure_stream("GPS_GLOBAL_ORIGIN", 0.5f); configure_stream("HIGHRES_IMU", 1.0f * rate_mult); configure_stream("ATTITUDE", 10.0f * rate_mult); configure_stream("VFR_HUD", 8.0f * rate_mult); configure_stream("GPS_RAW_INT", 1.0f * rate_mult); configure_stream("GLOBAL_POSITION_INT", 3.0f * rate_mult); configure_stream("LOCAL_POSITION_NED", 3.0f * rate_mult); configure_stream("RC_CHANNELS_RAW", 1.0f * rate_mult); configure_stream("NAMED_VALUE_FLOAT", 1.0f * rate_mult); configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f * rate_mult); configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f * rate_mult); configure_stream("DISTANCE_SENSOR", 0.5f); break; case MAVLINK_MODE_CAMERA: configure_stream("SYS_STATUS", 1.0f); configure_stream("ATTITUDE", 15.0f * rate_mult); configure_stream("GLOBAL_POSITION_INT", 15.0f * rate_mult); configure_stream("CAMERA_CAPTURE", 1.0f); break; default: break; } /* don't send parameters on startup without request */ _mavlink_param_queue_index = param_count(); MavlinkRateLimiter fast_rate_limiter(30000.0f / rate_mult); /* set main loop delay depending on data rate to minimize CPU overhead */ _main_loop_delay = MAIN_LOOP_DELAY / rate_mult; /* now the instance is fully initialized and we can bump the instance count */ LL_APPEND(_mavlink_instances, this); while (!_task_should_exit) { /* main loop */ usleep(_main_loop_delay); perf_begin(_loop_perf); hrt_abstime t = hrt_absolute_time(); if (param_sub->update(¶m_time, nullptr)) { /* parameters updated */ mavlink_update_system(); } if (status_sub->update(&status_time, &status)) { /* switch HIL mode if required */ set_hil_enabled(status.hil_state == HIL_STATE_ON); } /* update commands stream */ commands_stream.update(t); /* check for requested subscriptions */ if (_subscribe_to_stream != nullptr) { if (OK == configure_stream(_subscribe_to_stream, _subscribe_to_stream_rate)) { if (_subscribe_to_stream_rate > 0.0f) { warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, (double)_subscribe_to_stream_rate); } else { warnx("stream %s on device %s disabled", _subscribe_to_stream, _device_name); } } else { warnx("stream %s on device %s not found", _subscribe_to_stream, _device_name); } delete _subscribe_to_stream; _subscribe_to_stream = nullptr; } /* update streams */ MavlinkStream *stream; LL_FOREACH(_streams, stream) { stream->update(t); } if (fast_rate_limiter.check(t)) { mavlink_pm_queued_send(); _mission_manager->eventloop(); if (!mavlink_logbuffer_is_empty(&_logbuffer)) { struct mavlink_logmessage msg; int lb_ret = mavlink_logbuffer_read(&_logbuffer, &msg); if (lb_ret == OK) { send_statustext(msg.severity, msg.text); } } } /* pass messages from other UARTs or FTP worker */ if (_passing_on || _ftp_on) { bool is_part; uint8_t *read_ptr; uint8_t *write_ptr; pthread_mutex_lock(&_message_buffer_mutex); int available = message_buffer_get_ptr((void **)&read_ptr, &is_part); pthread_mutex_unlock(&_message_buffer_mutex); if (available > 0) { // Reconstruct message from buffer mavlink_message_t msg; write_ptr = (uint8_t *)&msg; // Pull a single message from the buffer size_t read_count = available; if (read_count > sizeof(mavlink_message_t)) { read_count = sizeof(mavlink_message_t); } memcpy(write_ptr, read_ptr, read_count); // We hold the mutex until after we complete the second part of the buffer. If we don't // we may end up breaking the empty slot overflow detection semantics when we mark the // possibly partial read below. pthread_mutex_lock(&_message_buffer_mutex); message_buffer_mark_read(read_count); /* write second part of buffer if there is some */ if (is_part && read_count < sizeof(mavlink_message_t)) { write_ptr += read_count; available = message_buffer_get_ptr((void **)&read_ptr, &is_part); read_count = sizeof(mavlink_message_t) - read_count; memcpy(write_ptr, read_ptr, read_count); message_buffer_mark_read(available); } pthread_mutex_unlock(&_message_buffer_mutex); _mavlink_resend_uart(_channel, &msg); } } /* update TX/RX rates*/ if (t > _bytes_timestamp + 1000000) { if (_bytes_timestamp != 0) { float dt = (t - _bytes_timestamp) / 1000.0f; _rate_tx = _bytes_tx / dt; _rate_txerr = _bytes_txerr / dt; _rate_rx = _bytes_rx / dt; _bytes_tx = 0; _bytes_txerr = 0; _bytes_rx = 0; } _bytes_timestamp = t; } perf_end(_loop_perf); }