Go to the documentation of this file.00001
00002
00005
00006 #ifndef GCS_MAVLink_h
00007 #define GCS_MAVLink_h
00008
00009 #include <Stream.h>
00010 #include "include/mavlink_types.h"
00011
00013 extern Stream *mavlink_comm_0_port;
00014
00016 extern Stream *mavlink_comm_1_port;
00017
00019 extern mavlink_system_t mavlink_system;
00020
00026 static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
00027 {
00028 switch(chan) {
00029 case MAVLINK_COMM_0:
00030 mavlink_comm_0_port->write(ch);
00031 break;
00032 case MAVLINK_COMM_1:
00033 mavlink_comm_1_port->write(ch);
00034 break;
00035 }
00036 }
00037
00043 static inline uint8_t comm_receive_ch(mavlink_channel_t chan)
00044 {
00045 uint8_t data = 0;
00046
00047 switch(chan) {
00048 case MAVLINK_COMM_0:
00049 data = mavlink_comm_0_port->read();
00050 break;
00051 case MAVLINK_COMM_1:
00052 data = mavlink_comm_1_port->read();
00053 break;
00054 }
00055 return data;
00056 }
00057
00062 static inline uint16_t comm_get_available(mavlink_channel_t chan)
00063 {
00064 uint16_t bytes = 0;
00065 switch(chan) {
00066 case MAVLINK_COMM_0:
00067 bytes = mavlink_comm_0_port->available();
00068 break;
00069 case MAVLINK_COMM_1:
00070 bytes = mavlink_comm_1_port->available();
00071 break;
00072 }
00073 return bytes;
00074 }
00075
00076 #define MAVLINK_USE_CONVENIENCE_FUNCTIONS
00077 #include "include/ardupilotmega/mavlink.h"
00078
00079 #endif // GCS_MAVLink_h