00001 00011 /* 00012 * libmavconn 00013 * Copyright 2015 Vladimir Ermakov, All rights reserved. 00014 * 00015 * This file is part of the mavros package and subject to the license terms 00016 * in the top-level LICENSE file of the mavros repository. 00017 * https://github.com/mavlink/mavros/tree/master/LICENSE.md 00018 */ 00019 00020 #include <cassert> 00021 #include <mavconn/mavlink_dialect.h> 00022 00023 /* I moved those arrays outside of functions because 00024 * module arrays easier to find with gdb 00025 */ 00026 static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; 00027 static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; 00028 00032 mavlink_status_t* mavlink_get_channel_status(uint8_t chan) 00033 { 00034 assert(chan < MAVLINK_COMM_NUM_BUFFERS); 00035 return &m_mavlink_status[chan]; 00036 } 00037 00041 mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) 00042 { 00043 assert(chan < MAVLINK_COMM_NUM_BUFFERS); 00044 return &m_mavlink_buffer[chan]; 00045 } 00046