123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155 |
- #include "GCS.h"
- #include "GCS_MAVLink.h"
- #include <AP_Common/AP_Common.h>
- #include <AP_GPS/AP_GPS.h>
- #include <AP_HAL/AP_HAL.h>
- extern const AP_HAL::HAL& hal;
- #ifdef MAVLINK_SEPARATE_HELPERS
- #pragma GCC diagnostic push
- #pragma GCC diagnostic ignored "-Wmissing-declarations"
- #include "include/mavlink/v2.0/mavlink_helpers.h"
- #pragma GCC diagnostic pop
- #endif
- AP_HAL::UARTDriver *mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS];
- bool gcs_alternative_active[MAVLINK_COMM_NUM_BUFFERS];
- static HAL_Semaphore chan_locks[MAVLINK_COMM_NUM_BUFFERS];
- mavlink_system_t mavlink_system = {7,1};
- static uint8_t mavlink_locked_mask;
- MAVLink_routing GCS_MAVLINK::routing;
- void GCS_MAVLINK::lock_channel(mavlink_channel_t _chan, bool lock)
- {
- if (!valid_channel(chan)) {
- return;
- }
- if (lock) {
- mavlink_locked_mask |= (1U<<(unsigned)_chan);
- } else {
- mavlink_locked_mask &= ~(1U<<(unsigned)_chan);
- }
- }
- bool GCS_MAVLINK::locked() const
- {
- return (1U<<chan) & mavlink_locked_mask;
- }
- void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan)
- {
- const uint8_t mask = (1U<<(unsigned)_chan);
- mavlink_private |= mask;
- mavlink_active &= ~mask;
- }
- MAV_PARAM_TYPE GCS_MAVLINK::mav_param_type(enum ap_var_type t)
- {
- if (t == AP_PARAM_INT8) {
- return MAV_PARAM_TYPE_INT8;
- }
- if (t == AP_PARAM_INT16) {
- return MAV_PARAM_TYPE_INT16;
- }
- if (t == AP_PARAM_INT32) {
- return MAV_PARAM_TYPE_INT32;
- }
-
- return MAV_PARAM_TYPE_REAL32;
- }
- uint16_t comm_get_txspace(mavlink_channel_t chan)
- {
- if (!valid_channel(chan)) {
- return 0;
- }
- if ((1U<<chan) & mavlink_locked_mask) {
- return 0;
- }
- int16_t ret = mavlink_comm_port[chan]->txspace();
- if (ret < 0) {
- ret = 0;
- }
- return (uint16_t)ret;
- }
- void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
- {
- if (!valid_channel(chan)) {
- return;
- }
- if (gcs_alternative_active[chan]) {
-
- return;
- }
- const size_t written = mavlink_comm_port[chan]->write(buf, len);
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- if (written < len) {
- AP_HAL::panic("Short write on UART: %lu < %u", written, len);
- }
- #else
- (void)written;
- #endif
- }
- void comm_send_lock(mavlink_channel_t chan)
- {
- chan_locks[(uint8_t)chan].take_blocking();
- }
- void comm_send_unlock(mavlink_channel_t chan)
- {
- chan_locks[(uint8_t)chan].give();
- }
|