mavlink_udp.c 6.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219
  1. /*******************************************************************************
  2. Copyright (C) 2010 Bryan Godbolt godbolt ( a t ) ualberta.ca
  3. This program is free software: you can redistribute it and/or modify
  4. it under the terms of the GNU General Public License as published by
  5. the Free Software Foundation, either version 3 of the License, or
  6. (at your option) any later version.
  7. This program is distributed in the hope that it will be useful,
  8. but WITHOUT ANY WARRANTY; without even the implied warranty of
  9. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  10. GNU General Public License for more details.
  11. You should have received a copy of the GNU General Public License
  12. along with this program. If not, see <http://www.gnu.org/licenses/>.
  13. ****************************************************************************/
  14. /*
  15. This program sends some data to qgroundcontrol using the mavlink protocol. The sent packets
  16. cause qgroundcontrol to respond with heartbeats. Any settings or custom commands sent from
  17. qgroundcontrol are printed by this program along with the heartbeats.
  18. I compiled this program sucessfully on Ubuntu 10.04 with the following command
  19. gcc -I ../../pixhawk/mavlink/include -o udp-server udp-server-test.c
  20. the rt library is needed for the clock_gettime on linux
  21. */
  22. /* These headers are for QNX, but should all be standard on unix/linux */
  23. #include <stdio.h>
  24. #include <errno.h>
  25. #include <string.h>
  26. #include <sys/socket.h>
  27. #include <sys/types.h>
  28. #include <netinet/in.h>
  29. #include <unistd.h>
  30. #include <stdlib.h>
  31. #include <fcntl.h>
  32. #include <time.h>
  33. #if (defined __QNX__) | (defined __QNXNTO__)
  34. /* QNX specific headers */
  35. #include <unix.h>
  36. #else
  37. /* Linux / MacOS POSIX timer headers */
  38. #include <sys/time.h>
  39. #include <time.h>
  40. #include <arpa/inet.h>
  41. #include <stdbool.h> /* required for the definition of bool in C99 */
  42. #endif
  43. /* This assumes you have the mavlink headers on your include path
  44. or in the same folder as this source file */
  45. #include <mavlink.h>
  46. #define BUFFER_LENGTH 2041 // minimum buffer size that can be used with qnx (I don't know why)
  47. uint64_t microsSinceEpoch();
  48. int main(int argc, char* argv[])
  49. {
  50. char help[] = "--help";
  51. char target_ip[100];
  52. float position[6] = {};
  53. int sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP);
  54. struct sockaddr_in gcAddr;
  55. struct sockaddr_in locAddr;
  56. //struct sockaddr_in fromAddr;
  57. uint8_t buf[BUFFER_LENGTH];
  58. ssize_t recsize;
  59. socklen_t fromlen = sizeof(gcAddr);
  60. int bytes_sent;
  61. mavlink_message_t msg;
  62. uint16_t len;
  63. int i = 0;
  64. //int success = 0;
  65. unsigned int temp = 0;
  66. // Check if --help flag was used
  67. if ((argc == 2) && (strcmp(argv[1], help) == 0))
  68. {
  69. printf("\n");
  70. printf("\tUsage:\n\n");
  71. printf("\t");
  72. printf("%s", argv[0]);
  73. printf(" <ip address of QGroundControl>\n");
  74. printf("\tDefault for localhost: udp-server 127.0.0.1\n\n");
  75. exit(EXIT_FAILURE);
  76. }
  77. // Change the target ip if parameter was given
  78. strcpy(target_ip, "127.0.0.1");
  79. if (argc == 2)
  80. {
  81. strcpy(target_ip, argv[1]);
  82. }
  83. memset(&locAddr, 0, sizeof(locAddr));
  84. locAddr.sin_family = AF_INET;
  85. locAddr.sin_addr.s_addr = INADDR_ANY;
  86. locAddr.sin_port = htons(14551);
  87. /* Bind the socket to port 14551 - necessary to receive packets from qgroundcontrol */
  88. if (-1 == bind(sock,(struct sockaddr *)&locAddr, sizeof(struct sockaddr)))
  89. {
  90. perror("error bind failed");
  91. close(sock);
  92. exit(EXIT_FAILURE);
  93. }
  94. /* Attempt to make it non blocking */
  95. #if (defined __QNX__) | (defined __QNXNTO__)
  96. if (fcntl(sock, F_SETFL, O_NONBLOCK | FASYNC) < 0)
  97. #else
  98. if (fcntl(sock, F_SETFL, O_NONBLOCK | O_ASYNC) < 0)
  99. #endif
  100. {
  101. fprintf(stderr, "error setting nonblocking: %s\n", strerror(errno));
  102. close(sock);
  103. exit(EXIT_FAILURE);
  104. }
  105. memset(&gcAddr, 0, sizeof(gcAddr));
  106. gcAddr.sin_family = AF_INET;
  107. gcAddr.sin_addr.s_addr = inet_addr(target_ip);
  108. gcAddr.sin_port = htons(14550);
  109. for (;;)
  110. {
  111. /*Send Heartbeat */
  112. mavlink_msg_heartbeat_pack(1, 200, &msg, MAV_TYPE_HELICOPTER, MAV_AUTOPILOT_GENERIC, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE);
  113. len = mavlink_msg_to_send_buffer(buf, &msg);
  114. bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
  115. /* Send Status */
  116. mavlink_msg_sys_status_pack(1, 200, &msg, 0, 0, 0, 500, 11000, -1, -1, 0, 0, 0, 0, 0, 0);
  117. len = mavlink_msg_to_send_buffer(buf, &msg);
  118. bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in));
  119. /* Send Local Position */
  120. mavlink_msg_local_position_ned_pack(1, 200, &msg, microsSinceEpoch(),
  121. position[0], position[1], position[2],
  122. position[3], position[4], position[5]);
  123. len = mavlink_msg_to_send_buffer(buf, &msg);
  124. bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
  125. /* Send attitude */
  126. mavlink_msg_attitude_pack(1, 200, &msg, microsSinceEpoch(), 1.2, 1.7, 3.14, 0.01, 0.02, 0.03);
  127. len = mavlink_msg_to_send_buffer(buf, &msg);
  128. bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
  129. memset(buf, 0, BUFFER_LENGTH);
  130. recsize = recvfrom(sock, (void *)buf, BUFFER_LENGTH, 0, (struct sockaddr *)&gcAddr, &fromlen);
  131. if (recsize > 0)
  132. {
  133. // Something received - print out all bytes and parse packet
  134. mavlink_message_t msg;
  135. mavlink_status_t status;
  136. printf("Bytes Received: %d\nDatagram: ", (int)recsize);
  137. for (i = 0; i < recsize; ++i)
  138. {
  139. temp = buf[i];
  140. printf("%02x ", (unsigned char)temp);
  141. if (mavlink_parse_char(MAVLINK_COMM_0, buf[i], &msg, &status))
  142. {
  143. // Packet received
  144. printf("\nReceived packet: SYS: %d, COMP: %d, LEN: %d, MSG ID: %d\n", msg.sysid, msg.compid, msg.len, msg.msgid);
  145. }
  146. }
  147. printf("\n");
  148. }
  149. memset(buf, 0, BUFFER_LENGTH);
  150. sleep(1); // Sleep one second
  151. }
  152. }
  153. /* QNX timer version */
  154. #if (defined __QNX__) | (defined __QNXNTO__)
  155. uint64_t microsSinceEpoch()
  156. {
  157. struct timespec time;
  158. uint64_t micros = 0;
  159. clock_gettime(CLOCK_REALTIME, &time);
  160. micros = (uint64_t)time.tv_sec * 1000000 + time.tv_nsec/1000;
  161. return micros;
  162. }
  163. #else
  164. uint64_t microsSinceEpoch()
  165. {
  166. struct timeval tv;
  167. uint64_t micros = 0;
  168. gettimeofday(&tv, NULL);
  169. micros = ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec;
  170. return micros;
  171. }
  172. #endif