Go to the documentation of this file.00001 #ifndef _MAVLINK_GET_INFO_H_
00002 #define _MAVLINK_GET_INFO_H_
00003
00004 #ifdef MAVLINK_USE_MESSAGE_INFO
00005 #define MAVLINK_HAVE_GET_MESSAGE_INFO
00006
00007
00008
00009 MAVLINK_HELPER const mavlink_message_info_t *mavlink_get_message_info(const mavlink_message_t *msg)
00010 {
00011 static const mavlink_message_info_t mavlink_message_info[] = MAVLINK_MESSAGE_INFO;
00012
00013
00014
00015
00016 uint32_t msgid = msg->msgid;
00017 uint32_t low=0, high=sizeof(mavlink_message_info)/sizeof(mavlink_message_info[0]);
00018 while (low < high) {
00019 uint32_t mid = (low+1+high)/2;
00020 if (msgid < mavlink_message_info[mid].msgid) {
00021 high = mid-1;
00022 continue;
00023 }
00024 if (msgid > mavlink_message_info[mid].msgid) {
00025 low = mid;
00026 continue;
00027 }
00028 low = mid;
00029 break;
00030 }
00031 return &mavlink_message_info[low];
00032 }
00033 #endif // MAVLINK_USE_MESSAGE_INFO
00034
00035 #endif // _MAVLINK_GET_INFO_H_
00036