main.c 8.8 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54
/*******************************************************************************
 
 Copyright (C) 2011 Lorenz Meier lm ( a t ) inf.ethz.ch
 and Bryan Godbolt godbolt ( a t ) ualberta.ca
 
 adapted from example written by Bryan Godbolt godbolt ( a t ) ualberta.ca
 
 This program is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
 
 This program is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
 
 You should have received a copy of the GNU General Public License
 along with this program.  If not, see <http://www.gnu.org/licenses/>.
 
 ****************************************************************************/
/*
 This program sends some data to qgroundcontrol using the mavlink protocol.  The sent packets
 cause qgroundcontrol to respond with heartbeats.  Any settings or custom commands sent from
 qgroundcontrol are printed by this program along with the heartbeats.
 
 
 I compiled this program sucessfully on Ubuntu 10.04 with the following command
 
 gcc -I ../../pixhawk/mavlink/include -o udp-server udp.c
 
 the rt library is needed for the clock_gettime on linux
 */
/* These headers are for QNX, but should all be standard on unix/linux */
#include <stdio.h>
#include <errno.h>
#include <string.h>
#include <sys/socket.h>
#include <sys/types.h>
#include <netinet/in.h>
#include <unistd.h>
#include <stdlib.h>
#include <fcntl.h>
#include <time.h>
#if (defined __QNX__) | (defined __QNXNTO__)
/* QNX specific headers */
#include <unix.h>
#else
/* Linux / MacOS POSIX timer headers */
#include <sys/time.h>
#include <time.h>
#include <arpa/inet.h>
#endif

lm's avatar
lm committed
55 56 57 58
/* FIRST: MAVLink setup */
//#define MAVLINK_CONFIGURED
//#define MAVLINK_NO_DATA
#define MAVLINK_WPM_VERBOSE
59

lm's avatar
lm committed
60 61
/* 0: Include MAVLink types */
#include "mavlink_types.h"
62

lm's avatar
lm committed
63
/* 1: Define mavlink system storage */
64 65
mavlink_system_t mavlink_system;

lm's avatar
lm committed
66 67
/* 2: Include actual protocol, REQUIRES mavlink_system */
#include "mavlink.h"
68

lm's avatar
lm committed
69 70
/* 3: Include MAVLink data structures */
#include "mavlink_data.h"
71

lm's avatar
lm committed
72 73 74 75 76 77 78
/* 3: Define waypoint helper functions */
void mavlink_wpm_send_message(mavlink_message_t* msg);
void mavlink_wpm_send_gcs_string(const char* string);
uint64_t mavlink_wpm_get_system_timestamp();
void mavlink_missionlib_send_message(mavlink_message_t* msg);
void mavlink_missionlib_send_gcs_string(const char* string);
uint64_t mavlink_missionlib_get_system_timestamp();
79

lm's avatar
lm committed
80 81 82 83 84 85 86 87 88 89 90 91 92
/* 4: Include waypoint protocol */
#include "waypoints.h"
mavlink_wpm_storage wpm;


#include "mavlink_missionlib_data.h"
#include "mavlink_parameters.h"

mavlink_pm_storage pm;

/**
 * @brief reset all parameters to default
 * @warning DO NOT USE THIS IN FLIGHT!
93
 */
lm's avatar
lm committed
94
void mavlink_pm_reset_params(mavlink_pm_storage* pm)
95
{
lm's avatar
lm committed
96 97 98 99 100 101 102
	pm->size = MAVLINK_PM_MAX_PARAM_COUNT;
	// 1) MAVLINK_PM_PARAM_SYSTEM_ID
	pm->param_values[MAVLINK_PM_PARAM_SYSTEM_ID] = 12;
	strcpy(pm->param_names[MAVLINK_PM_PARAM_SYSTEM_ID], "SYS_ID");
	// 2) MAVLINK_PM_PARAM_ATT_K_D
	pm->param_values[MAVLINK_PM_PARAM_ATT_K_D] = 0.3f;
	strcpy(pm->param_names[MAVLINK_PM_PARAM_ATT_K_D], "ATT_K_D");
103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130
}


#define BUFFER_LENGTH 2041 // minimum buffer size that can be used with qnx (I don't know why)

char help[] = "--help";


char target_ip[100];

float position[6] = {};
int sock;
struct sockaddr_in gcAddr; 
struct sockaddr_in locAddr;
uint8_t buf[BUFFER_LENGTH];
ssize_t recsize;
socklen_t fromlen;
int bytes_sent;
mavlink_message_t msg;
uint16_t len;
int i = 0;
unsigned int temp = 0;

uint64_t microsSinceEpoch();




lm's avatar
lm committed
131
/* Provide the interface functions for the waypoint manager */
132 133 134 135

/*
 *  @brief Sends a MAVLink message over UDP
 */
lm's avatar
lm committed
136 137

void mavlink_missionlib_send_message(mavlink_message_t* msg)
138
{
lm's avatar
lm committed
139
	uint8_t buf[MAVLINK_MAX_PACKET_LEN];
140 141
	uint16_t len = mavlink_msg_to_send_buffer(buf, msg);
	uint16_t bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in));
lm's avatar
lm committed
142 143
	
	printf("SENT %d bytes\n", bytes_sent);
144 145
}

lm's avatar
lm committed
146
void mavlink_missionlib_send_gcs_string(const char* string)
147
{
lm's avatar
lm committed
148
	printf("%s\n",string);
149 150
}

lm's avatar
lm committed
151
uint64_t mavlink_missionlib_get_system_timestamp()
152 153 154 155 156 157 158
{
	struct timeval tv;
	gettimeofday(&tv, NULL);
	return ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec;
}


lm's avatar
lm committed
159
void mavlink_wpm_send_message(mavlink_message_t* msg)
160
{
lm's avatar
lm committed
161
	mavlink_missionlib_send_message(msg);
162 163
}

lm's avatar
lm committed
164
void mavlink_wpm_send_gcs_string(const char* string)
165
{
lm's avatar
lm committed
166
	mavlink_missionlib_send_gcs_string(string);
167 168
}

lm's avatar
lm committed
169
uint64_t mavlink_wpm_get_system_timestamp()
170
{
lm's avatar
lm committed
171
	return mavlink_missionlib_get_system_timestamp();
172 173 174 175 176 177 178 179 180
}



int main(int argc, char* argv[])
{	
	// Initialize MAVLink
	mavlink_wpm_init(&wpm);
	mavlink_system.sysid = 1;
lm's avatar
lm committed
181 182
	mavlink_system.compid = 20;
	mavlink_pm_reset_params(&pm);
183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288
	
	
	
	// Create socket
	sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP);
	
	// Check if --help flag was used
	if ((argc == 2) && (strcmp(argv[1], help) == 0))
    {
		printf("\n");
		printf("\tUsage:\n\n");
		printf("\t");
		printf("%s", argv[0]);
		printf(" <ip address of QGroundControl>\n");
		printf("\tDefault for localhost: udp-server 127.0.0.1\n\n");
		exit(EXIT_FAILURE);
    }
	
	
	// Change the target ip if parameter was given
	strcpy(target_ip, "127.0.0.1");
	if (argc == 2)
    {
		strcpy(target_ip, argv[1]);
    }
	
	
	memset(&locAddr, 0, sizeof(locAddr));
	locAddr.sin_family = AF_INET;
	locAddr.sin_addr.s_addr = INADDR_ANY;
	locAddr.sin_port = htons(14551);
	
	/* Bind the socket to port 14551 - necessary to receive packets from qgroundcontrol */ 
	if (-1 == bind(sock,(struct sockaddr *)&locAddr, sizeof(struct sockaddr)))
    {
		perror("error bind failed");
		close(sock);
		exit(EXIT_FAILURE);
    } 
	
	/* Attempt to make it non blocking */
	if (fcntl(sock, F_SETFL, O_NONBLOCK | FASYNC) < 0)
    {
		fprintf(stderr, "error setting nonblocking: %s\n", strerror(errno));
		close(sock);
		exit(EXIT_FAILURE);
    }
	
	
	memset(&gcAddr, 0, sizeof(gcAddr));
	gcAddr.sin_family = AF_INET;
	gcAddr.sin_addr.s_addr = inet_addr(target_ip);
	gcAddr.sin_port = htons(14550);
	
	
	printf("MAVLINK MISSION LIBRARY EXAMPLE PROCESS INITIALIZATION DONE, RUNNING..\n");
	
	
	for (;;) 
    {
		
		/*Send Heartbeat */
		mavlink_msg_heartbeat_pack(mavlink_system.sysid, 200, &msg, MAV_TYPE_HELICOPTER, MAV_CLASS_GENERIC);
		len = mavlink_msg_to_send_buffer(buf, &msg);
		bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
		
		/* Send Status */
		mavlink_msg_sys_status_pack(1, 200, &msg, MAV_MODE_GUIDED, MAV_NAV_HOLD, MAV_STATE_ACTIVE, 500, 7500, 0, 0);
		len = mavlink_msg_to_send_buffer(buf, &msg);
		bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in));
		
		/* Send Local Position */
		mavlink_msg_local_position_pack(mavlink_system.sysid, 200, &msg, microsSinceEpoch(), 
										position[0], position[1], position[2],
										position[3], position[4], position[5]);
		len = mavlink_msg_to_send_buffer(buf, &msg);
		bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
		
		/* Send attitude */
		mavlink_msg_attitude_pack(mavlink_system.sysid, 200, &msg, microsSinceEpoch(), 1.2, 1.7, 3.14, 0.01, 0.02, 0.03);
		len = mavlink_msg_to_send_buffer(buf, &msg);
		bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
		
		
		memset(buf, 0, BUFFER_LENGTH);
		recsize = recvfrom(sock, (void *)buf, BUFFER_LENGTH, 0, (struct sockaddr *)&gcAddr, &fromlen);
		if (recsize > 0)
      	{
			// Something received - print out all bytes and parse packet
			mavlink_message_t msg;
			mavlink_status_t status;
			
			printf("Bytes Received: %d\nDatagram: ", (int)recsize);
			for (i = 0; i < recsize; ++i)
			{
				temp = buf[i];
				printf("%02x ", (unsigned char)temp);
				if (mavlink_parse_char(MAVLINK_COMM_0, buf[i], &msg, &status))
				{
					// Packet received
					printf("\nReceived packet: SYS: %d, COMP: %d, LEN: %d, MSG ID: %d\n", msg.sysid, msg.compid, msg.len, msg.msgid);
					
					// Handle packet with waypoint component
					mavlink_wpm_message_handler(&msg);
					
					// Handle packet with parameter component
lm's avatar
lm committed
289
					mavlink_pm_message_handler(MAVLINK_COMM_0, &msg);
290 291 292 293 294
				}
			}
			printf("\n");
		}
		memset(buf, 0, BUFFER_LENGTH);
lm's avatar
lm committed
295 296 297 298 299
		usleep(50000); // Sleep one second
		
		
		// Send one parameter
		mavlink_pm_queued_send();
300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331
    }
}


/* QNX timer version */
#if (defined __QNX__) | (defined __QNXNTO__)
uint64_t microsSinceEpoch()
{
	
	struct timespec time;
	
	uint64_t micros = 0;
	
	clock_gettime(CLOCK_REALTIME, &time);  
	micros = (uint64_t)time.tv_sec * 100000 + time.tv_nsec/1000;
	
	return micros;
}
#else
uint64_t microsSinceEpoch()
{
	
	struct timeval tv;
	
	uint64_t micros = 0;
	
	gettimeofday(&tv, NULL);  
	micros =  ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec;
	
	return micros;
}
#endif