main.c 10.6 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
/*******************************************************************************
 
 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>
lm's avatar
lm committed
45
#include <math.h>
46 47 48 49 50 51 52 53 54 55
#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
56 57 58
/* FIRST: MAVLink setup */
//#define MAVLINK_CONFIGURED
//#define MAVLINK_NO_DATA
59
//#define MAVLINK_WPM_VERBOSE
60

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

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

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

lm's avatar
lm committed
70 71 72 73 74 75 76
/* 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();
77

lm's avatar
lm committed
78 79 80 81 82 83 84 85 86 87 88 89 90
/* 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!
91
 */
lm's avatar
lm committed
92
void mavlink_pm_reset_params(mavlink_pm_storage* pm)
93
{
lm's avatar
lm committed
94 95 96 97 98 99 100
	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");
101 102 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
}


#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
129
/* Provide the interface functions for the waypoint manager */
130 131 132 133

/*
 *  @brief Sends a MAVLink message over UDP
 */
lm's avatar
lm committed
134 135

void mavlink_missionlib_send_message(mavlink_message_t* msg)
136
{
lm's avatar
lm committed
137
	uint8_t buf[MAVLINK_MAX_PACKET_LEN];
138 139
	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
140 141
	
	printf("SENT %d bytes\n", bytes_sent);
142 143
}

lm's avatar
lm committed
144
void mavlink_missionlib_send_gcs_string(const char* string)
145
{
146 147 148 149 150 151 152 153 154 155 156 157 158 159 160
	const int len = 50;
	mavlink_statustext_t status;
	int i = 0;
	while (i < len - 1)
	{
		status.text[i] = string[i];
		if (string[i] == '\0')
			break;
		i++;
	}
	status.text[i] = '\0'; // Enforce null termination
	mavlink_message_t msg;
	
	mavlink_msg_statustext_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &status);
	mavlink_missionlib_send_message(&msg);
161 162
}

lm's avatar
lm committed
163
uint64_t mavlink_missionlib_get_system_timestamp()
164 165 166 167 168 169
{
	struct timeval tv;
	gettimeofday(&tv, NULL);
	return ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec;
}

lm's avatar
lm committed
170 171 172 173 174 175
float roll, pitch, yaw;
uint32_t latitude, longitude, altitude;
uint16_t speedx, speedy, speedz;
float rollspeed, pitchspeed, yawspeed;
bool hilEnabled = false;

176 177 178 179
int main(int argc, char* argv[])
{	
	// Initialize MAVLink
	mavlink_wpm_init(&wpm);
180
	mavlink_system.sysid = 5;
lm's avatar
lm committed
181 182
	mavlink_system.compid = 20;
	mavlink_pm_reset_params(&pm);
183
	
184 185 186
	int32_t ground_distance;
	uint32_t time_ms;
	
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
	
	
	// 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 (;;) 
    {
246
		bytes_sent = 0;
247
		
lm's avatar
lm committed
248
		/* Send Heartbeat */
249
		mavlink_msg_heartbeat_pack(mavlink_system.sysid, 200, &msg, MAV_TYPE_HELICOPTER, MAV_AUTOPILOT_GENERIC, 0, 0, 0);
250
		len = mavlink_msg_to_send_buffer(buf, &msg);
251
		bytes_sent += sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
252 253
		
		/* Send Status */
254
		mavlink_msg_sys_status_pack(1, 200, &msg, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE, 500, 7500, 0, 0, 0, 0, 0, 0, 0, 0);
255
		len = mavlink_msg_to_send_buffer(buf, &msg);
256
		bytes_sent += sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in));
257 258
		
		/* Send Local Position */
259
		mavlink_msg_local_position_ned_pack(mavlink_system.sysid, 200, &msg, microsSinceEpoch(), 
260 261 262
										position[0], position[1], position[2],
										position[3], position[4], position[5]);
		len = mavlink_msg_to_send_buffer(buf, &msg);
263
		bytes_sent += sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
264
		
lm's avatar
lm committed
265 266 267
		/* Send global position */
		if (hilEnabled)
		{
268
			mavlink_msg_global_position_int_pack(mavlink_system.sysid, 200, &msg, time_ms, latitude, longitude, altitude, ground_distance, speedx, speedy, speedz, (yaw/M_PI)*180*100);
lm's avatar
lm committed
269 270 271 272
			len = mavlink_msg_to_send_buffer(buf, &msg);
			bytes_sent += sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
		}
		
273
		/* Send attitude */
lm's avatar
lm committed
274
		mavlink_msg_attitude_pack(mavlink_system.sysid, 200, &msg, microsSinceEpoch(), roll, pitch, yaw, rollspeed, pitchspeed, yawspeed);
275
		len = mavlink_msg_to_send_buffer(buf, &msg);
276
		bytes_sent += sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
277
		
278 279
		/* Send HIL outputs */
		float roll_ailerons = 0;   // -1 .. 1
lm's avatar
lm committed
280
		float pitch_elevator = 0.2;  // -1 .. 1
281 282
		float yaw_rudder = 0.1;      // -1 .. 1
		float throttle = 0.9;      //  0 .. 1
lm's avatar
lm committed
283
		mavlink_msg_hil_controls_pack_chan(mavlink_system.sysid, mavlink_system.compid, MAVLINK_COMM_0, &msg, microsSinceEpoch(), roll_ailerons, pitch_elevator, yaw_rudder, throttle, mavlink_system.mode, mavlink_system.nav_mode, 0, 0, 0, 0);
284 285
		len = mavlink_msg_to_send_buffer(buf, &msg);
		bytes_sent += sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308
		
		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
309
					mavlink_pm_message_handler(MAVLINK_COMM_0, &msg);
310 311 312 313 314 315 316 317
					
					// Print HIL values sent to system
					if (msg.msgid == MAVLINK_MSG_ID_HIL_STATE)
					{
						mavlink_hil_state_t hil;
						mavlink_msg_hil_state_decode(&msg, &hil);
						printf("Received HIL state:\n");
						printf("R: %f P: %f Y: %f\n", hil.roll, hil.pitch, hil.yaw);
lm's avatar
lm committed
318 319 320 321 322 323 324 325 326 327 328 329 330
						roll = hil.roll;
						pitch = hil.pitch;
						yaw = hil.yaw;
						rollspeed = hil.rollspeed;
						pitchspeed = hil.pitchspeed;
						yawspeed = hil.yawspeed;
						speedx = hil.vx;
						speedy = hil.vy;
						speedz = hil.vz;
						latitude = hil.lat;
						longitude = hil.lon;
						altitude = hil.alt;
						hilEnabled = true;
331
					}
332 333 334 335 336
				}
			}
			printf("\n");
		}
		memset(buf, 0, BUFFER_LENGTH);
337
		usleep(10000); // Sleep 10 ms
lm's avatar
lm committed
338 339 340 341
		
		
		// Send one parameter
		mavlink_pm_queued_send();
342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373
    }
}


/* 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