createEventMessage.c 21.8 KB
Newer Older
pixhawk's avatar
pixhawk committed
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 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 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 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 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 289 290 291 292 293 294 295 296 297 298 299 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 332 333 334 335 336 337 338 339 340 341 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 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634
/*****************************************************************************
 *  Copyright (c) 2008, University of Florida
 *  All rights reserved.
 *  
 *  This file is part of OpenJAUS.  OpenJAUS is distributed under the BSD 
 *  license.  See the LICENSE file for details.
 * 
 *  Redistribution and use in source and binary forms, with or without 
 *  modification, are permitted provided that the following conditions 
 *  are met:
 *
 *     * Redistributions of source code must retain the above copyright
 *       notice, this list of conditions and the following disclaimer.
 *     * Redistributions in binary form must reproduce the above
 *       copyright notice, this list of conditions and the following
 *       disclaimer in the documentation and/or other materials provided
 *       with the distribution.
 *     * Neither the name of the University of Florida nor the names of its 
 *       contributors may be used to endorse or promote products derived from 
 *       this software without specific prior written permission.
 *
 *   THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 
 *   "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 
 *   LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR 
 *   A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 
 *   OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
 *   SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 
 *   LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 
 *   DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY 
 *   THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 *   (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 
 *   OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 ****************************************************************************/
// File Name: createEventMessage.c
//
// Written By: Danny Kent (jaus AT dannykent DOT com), Tom Galluzzo (galluzzo AT gmail DOT com)
//
// Version: 3.3.0a
//
// Date: 08/07/08
//
// Description: This file defines the functionality of a CreateEventMessage



#include <stdlib.h>
#include <string.h>
#include "jaus.h"

static const int commandCode = JAUS_CREATE_EVENT;
static const int maxDataSizeBytes = 512000; // Max Message size: 500K

static JausBoolean headerFromBuffer(CreateEventMessage message, unsigned char *buffer, unsigned int bufferSizeBytes);
static JausBoolean headerToBuffer(CreateEventMessage message, unsigned char *buffer, unsigned int bufferSizeBytes);

static JausBoolean dataFromBuffer(CreateEventMessage message, unsigned char *buffer, unsigned int bufferSizeBytes);
static int dataToBuffer(CreateEventMessage message, unsigned char *buffer, unsigned int bufferSizeBytes);
static void dataInitialize(CreateEventMessage message);
static void dataDestroy(CreateEventMessage message);
static unsigned int dataSize(CreateEventMessage message);

// ************************************************************************************************************** //
//                                    USER CONFIGURED FUNCTIONS
// ************************************************************************************************************** //

// Initializes the message-specific fields
static void dataInitialize(CreateEventMessage message)
{
	// Set initial values of message fields

	message->presenceVector = newJausByte(JAUS_BYTE_PRESENCE_VECTOR_ALL_ON);	// 1: Presence Vector
	message->requestId = newJausByte(0);					// Local request ID for use in confirm event
	message->reportMessageCode = newJausUnsignedShort(0);	// Command Code of the resulting report
	message->eventType = newJausByte(0);					// Enumeration of Event types
	message->eventBoundary = newJausByte(0);				// Enumeration of Event Boundary Conditions
	message->limitDataField = newJausByte(0);				// Field from Report for Limit Trigger
	message->lowerLimit = jausEventLimitCreate();			// Lower Event Limit
	message->lowerLimit->dataType = EVENT_LIMIT_BYTE_TYPE;
	message->upperLimit = jausEventLimitCreate();			// Upper Event Limit
	message->upperLimit->dataType = EVENT_LIMIT_BYTE_TYPE;
	message->stateLimit = jausEventLimitCreate();			// State Event Limit used for Equal Boundary
	message->stateLimit->dataType = EVENT_LIMIT_BYTE_TYPE;
	message->requestedMinimumRate = newJausDouble(0.0);		// For Periodic Events for unchanging value, Scaled UnsignedShort (0, 1092)
	message->requestedUpdateRate = newJausDouble(0.0);		// For Periodic Events, Scaled UnsignedShort (0, 1092)
	message->queryMessage = NULL;							// Query Message (not including header) to use for response	
}

// Destructs the message-specific fields
static void dataDestroy(CreateEventMessage message)
{
	// Free message fields
	if(message->queryMessage) jausMessageDestroy(message->queryMessage);
	if(message->lowerLimit) jausEventLimitDestroy(message->lowerLimit);
	if(message->upperLimit) jausEventLimitDestroy(message->upperLimit);
	if(message->stateLimit) jausEventLimitDestroy(message->stateLimit);
}

// Return boolean of success
static JausBoolean dataFromBuffer(CreateEventMessage message, unsigned char *buffer, unsigned int bufferSizeBytes)
{
	int index = 0;
	JausUnsignedShort tempUShort;
	JausUnsignedInteger queryMessageSize;

	if(bufferSizeBytes == message->dataSize)
	{
		// Unpack Message Fields from Buffer
		// Presence Vector
		if(!jausByteFromBuffer(&message->presenceVector, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
		index += JAUS_BYTE_SIZE_BYTES;

		// Request ID
		if(!jausByteFromBuffer(&message->requestId, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
		index += JAUS_BYTE_SIZE_BYTES;

		// Report Message Code
		if(!jausUnsignedShortFromBuffer(&message->reportMessageCode, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
		index += JAUS_UNSIGNED_SHORT_SIZE_BYTES;		

		// Event Type
		if(!jausByteFromBuffer(&message->eventType, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
		index += JAUS_BYTE_SIZE_BYTES;
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_BOUNDARY_BIT))
		{
			// Event Boundary
			if(!jausByteFromBuffer(&message->eventBoundary, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += JAUS_BYTE_SIZE_BYTES;
		}

		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_DATA_FIELD_BIT))
		{
			// Limit Data Field
			if(!jausByteFromBuffer(&message->limitDataField, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += JAUS_BYTE_SIZE_BYTES;
		}
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_LOWER_LIMIT_BIT))
		{		
			// Lower Limit
			if(!jausEventLimitFromBuffer(&message->lowerLimit, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += jausEventLimitSize(message->lowerLimit);
		}
		else
		{
			message->lowerLimit = NULL;
		}
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_UPPER_LIMIT_BIT))
		{		
			// Upper Limit
			if(!jausEventLimitFromBuffer(&message->upperLimit, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += jausEventLimitSize(message->upperLimit);
		}
		else
		{
			message->upperLimit = NULL;
		}

		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_STATE_LIMIT_BIT))
		{		
			// State Limit
			if(!jausEventLimitFromBuffer(&message->stateLimit, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += jausEventLimitSize(message->stateLimit);
		}
		else
		{
			message->stateLimit = NULL;
		}
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_MINIMUM_RATE_BIT))
		{		
			// Minimum Periodic Rate 
			if(!jausUnsignedShortFromBuffer(&tempUShort, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += JAUS_UNSIGNED_SHORT_SIZE_BYTES;
			
			// Scaled Int (0, 1092);
			message->requestedMinimumRate = jausUnsignedShortToDouble(tempUShort, 0, 1092);
		}
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_REQUESTED_RATE_BIT))
		{		
			// Periodic Rate 
			if(!jausUnsignedShortFromBuffer(&tempUShort, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += JAUS_UNSIGNED_SHORT_SIZE_BYTES;
			
			// Scaled Int (0, 1092);
			message->requestedUpdateRate = jausUnsignedShortToDouble(tempUShort, 0, 1092);
		}
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_QUERY_MESSAGE_BIT))
		{		
			// Query Message Size
			if(!jausUnsignedIntegerFromBuffer(&queryMessageSize, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += JAUS_UNSIGNED_INTEGER_SIZE_BYTES;
			
			// Query Message Body
			if(bufferSizeBytes-index < queryMessageSize) return JAUS_FALSE;

			// Setup our Query Message
			message->queryMessage = jausMessageCreate();
			if(!message->queryMessage) return JAUS_FALSE;

			message->queryMessage->dataSize = queryMessageSize;
			jausAddressCopy(message->queryMessage->source, message->source);
			jausAddressCopy(message->queryMessage->destination, message->destination);
			
			message->queryMessage->commandCode = jausMessageGetComplimentaryCommandCode(message->reportMessageCode);

			// Allocate Memory
			message->queryMessage->data = (unsigned char *) malloc(queryMessageSize);
			
			// Copy query message body to the data member
			memcpy(message->queryMessage->data, buffer+index, queryMessageSize);
			index += queryMessageSize;
		}
		return JAUS_TRUE;
	}
	else
	{
		return JAUS_FALSE;
	}
}

// Returns number of bytes put into the buffer
static int dataToBuffer(CreateEventMessage message, unsigned char *buffer, unsigned int bufferSizeBytes)
{
	int index = 0;
	JausUnsignedShort tempUShort;

	if(bufferSizeBytes >= dataSize(message))
	{
		// Unpack Message Fields from Buffer
		// Presence Vector
		if(!jausByteToBuffer(message->presenceVector, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
		index += JAUS_BYTE_SIZE_BYTES;
		
		// Request Id
		if(!jausByteToBuffer(message->requestId, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
		index += JAUS_BYTE_SIZE_BYTES;

		// Message Code
		if(!jausUnsignedShortToBuffer(message->reportMessageCode, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
		index += JAUS_UNSIGNED_SHORT_SIZE_BYTES;
		
		// Event Type
		if(!jausByteToBuffer(message->eventType, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
		index += JAUS_BYTE_SIZE_BYTES;
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_BOUNDARY_BIT))
		{
			// Event Boundary
			if(!jausByteToBuffer(message->eventBoundary, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += JAUS_BYTE_SIZE_BYTES;
		}

		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_DATA_FIELD_BIT))
		{
			// Data Field
			if(!jausByteToBuffer(message->limitDataField, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += JAUS_BYTE_SIZE_BYTES;
		}
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_LOWER_LIMIT_BIT))
		{		
			// Lower Limit
			if(!jausEventLimitToBuffer(message->lowerLimit, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += jausEventLimitSize(message->lowerLimit);
		}
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_UPPER_LIMIT_BIT))
		{		
			// Upper Limit
			if(!jausEventLimitToBuffer(message->upperLimit, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += jausEventLimitSize(message->upperLimit);
		}

		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_STATE_LIMIT_BIT))
		{		
			// State Limit
			if(!jausEventLimitToBuffer(message->stateLimit, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += jausEventLimitSize(message->stateLimit);
		}
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_MINIMUM_RATE_BIT))
		{		
			// Scaled Int (0, 1092);
			tempUShort = jausUnsignedShortFromDouble(message->requestedMinimumRate, 0, 1092);

			// Minimum Periodic Rate 
			if(!jausUnsignedShortToBuffer(tempUShort, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += JAUS_UNSIGNED_SHORT_SIZE_BYTES;
		}
		
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_REQUESTED_RATE_BIT))
		{		
			// Scaled Int (0, 1092);
			tempUShort = jausUnsignedShortFromDouble(message->requestedUpdateRate, 0, 1092);

			// Minimum Periodic Rate 
			if(!jausUnsignedShortToBuffer(tempUShort, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
			index += JAUS_UNSIGNED_SHORT_SIZE_BYTES;
		}
	
		if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_QUERY_MESSAGE_BIT))
		{		
			//Query Message Size 
			if(message->queryMessage)
			{
				if(!jausUnsignedIntegerToBuffer(message->queryMessage->dataSize, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
				index += JAUS_UNSIGNED_INTEGER_SIZE_BYTES;
			
				// Query Message Body
				if(bufferSizeBytes-index < message->queryMessage->dataSize) return JAUS_FALSE;
				memcpy(buffer+index, message->queryMessage->data, message->queryMessage->dataSize);
				index += message->queryMessage->dataSize;
			}
			else
			{
				if(!jausUnsignedIntegerToBuffer(0, buffer+index, bufferSizeBytes-index)) return JAUS_FALSE;
				index += JAUS_UNSIGNED_INTEGER_SIZE_BYTES;
			}
		}
	}

	return index;
}

// Returns number of bytes put into the buffer
static unsigned int dataSize(CreateEventMessage message)
{
	int index = 0;

	// Presence Vector
	index += JAUS_BYTE_SIZE_BYTES;

	// Request ID
	index += JAUS_BYTE_SIZE_BYTES;
	
	// Message Code
	index += JAUS_UNSIGNED_SHORT_SIZE_BYTES;
	
	// Event Type
	index += JAUS_BYTE_SIZE_BYTES;
	
	if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_BOUNDARY_BIT))
	{
		index += JAUS_BYTE_SIZE_BYTES;
	}

	if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_DATA_FIELD_BIT))
	{
		index += JAUS_BYTE_SIZE_BYTES;
	}
	
	if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_LOWER_LIMIT_BIT))
	{		
		index += jausEventLimitSize(message->lowerLimit);
	}
	
	if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_UPPER_LIMIT_BIT))
	{		
		index += jausEventLimitSize(message->upperLimit);
	}

	if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_STATE_LIMIT_BIT))
	{		
		index += jausEventLimitSize(message->stateLimit);
	}
	
	if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_MINIMUM_RATE_BIT))
	{		
		index += JAUS_UNSIGNED_SHORT_SIZE_BYTES;
	}
	
	if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_REQUESTED_RATE_BIT))
	{		
		index += JAUS_UNSIGNED_SHORT_SIZE_BYTES;
	}

	if(jausByteIsBitSet(message->presenceVector, CREATE_EVENT_PV_QUERY_MESSAGE_BIT))
	{		
		index += JAUS_UNSIGNED_INTEGER_SIZE_BYTES;

		// Jaus Message
		if(message->queryMessage) index += message->queryMessage->dataSize;
	}


	return index;
}


// ************************************************************************************************************** //
//                                    NON-USER CONFIGURED FUNCTIONS
// ************************************************************************************************************** //

CreateEventMessage createEventMessageCreate(void)
{
	CreateEventMessage message;

	message = (CreateEventMessage)malloc( sizeof(CreateEventMessageStruct) );
	if(message == NULL)
	{
		return NULL;
	}
	
	// Initialize Values
	message->properties.priority = JAUS_DEFAULT_PRIORITY;
	message->properties.ackNak = JAUS_ACK_NAK_NOT_REQUIRED;
	message->properties.scFlag = JAUS_NOT_SERVICE_CONNECTION_MESSAGE;
	message->properties.expFlag = JAUS_NOT_EXPERIMENTAL_MESSAGE;
	message->properties.version = JAUS_VERSION_3_3;
	message->properties.reserved = 0;
	message->commandCode = commandCode;
	message->destination = jausAddressCreate();
	message->source = jausAddressCreate();
	message->dataFlag = JAUS_SINGLE_DATA_PACKET;
	message->dataSize = maxDataSizeBytes;
	message->sequenceNumber = 0;
	
	dataInitialize(message);
	message->dataSize = dataSize(message);
	
	return message;	
}

void createEventMessageDestroy(CreateEventMessage message)
{
	dataDestroy(message);
	jausAddressDestroy(message->source);
	jausAddressDestroy(message->destination);
	free(message);
	message = NULL;
}

JausBoolean createEventMessageFromBuffer(CreateEventMessage message, unsigned char* buffer, unsigned int bufferSizeBytes)
{
	int index = 0;
	
	if(headerFromBuffer(message, buffer+index, bufferSizeBytes-index))
	{
		index += JAUS_HEADER_SIZE_BYTES;
		if(dataFromBuffer(message, buffer+index, bufferSizeBytes-index))
		{
			return JAUS_TRUE;
		}
		else
		{
			return JAUS_FALSE;
		}
	}
	else
	{
		return JAUS_FALSE;
	}
}

JausBoolean createEventMessageToBuffer(CreateEventMessage message, unsigned char *buffer, unsigned int bufferSizeBytes)
{
	if(bufferSizeBytes < createEventMessageSize(message))
	{
		return JAUS_FALSE; //improper size	
	}
	else
	{	
		message->dataSize = dataToBuffer(message, buffer+JAUS_HEADER_SIZE_BYTES, bufferSizeBytes - JAUS_HEADER_SIZE_BYTES);
		if(headerToBuffer(message, buffer, bufferSizeBytes))
		{
			return JAUS_TRUE;
		}
		else
		{
			return JAUS_FALSE; // headerToCreateEventBuffer failed
		}
	}
}

CreateEventMessage createEventMessageFromJausMessage(JausMessage jausMessage)
{
	CreateEventMessage message;

	if(jausMessage->commandCode != commandCode)
	{
		return NULL; // Wrong message type
	}
	else
	{
		message = (CreateEventMessage)malloc( sizeof(CreateEventMessageStruct) );
		if(message == NULL)
		{
			return NULL;
		}
		
		message->properties.priority = jausMessage->properties.priority;
		message->properties.ackNak = jausMessage->properties.ackNak;
		message->properties.scFlag = jausMessage->properties.scFlag;
		message->properties.expFlag = jausMessage->properties.expFlag;
		message->properties.version = jausMessage->properties.version;
		message->properties.reserved = jausMessage->properties.reserved;
		message->commandCode = jausMessage->commandCode;
		message->destination = jausAddressCreate();
		*message->destination = *jausMessage->destination;
		message->source = jausAddressCreate();
		*message->source = *jausMessage->source;
		message->dataSize = jausMessage->dataSize;
		message->dataFlag = jausMessage->dataFlag;
		message->sequenceNumber = jausMessage->sequenceNumber;
		
		// Unpack jausMessage->data
		if(dataFromBuffer(message, jausMessage->data, jausMessage->dataSize))
		{
			return message;
		}
		else
		{
			return NULL;
		}
	}
}

JausMessage createEventMessageToJausMessage(CreateEventMessage message)
{
	JausMessage jausMessage;

	jausMessage = (JausMessage)malloc( sizeof(struct JausMessageStruct) );
	if(jausMessage == NULL)
	{
		return NULL;
	}	
	
	jausMessage->properties.priority = message->properties.priority;
	jausMessage->properties.ackNak = message->properties.ackNak;
	jausMessage->properties.scFlag = message->properties.scFlag;
	jausMessage->properties.expFlag = message->properties.expFlag;
	jausMessage->properties.version = message->properties.version;
	jausMessage->properties.reserved = message->properties.reserved;
	jausMessage->commandCode = message->commandCode;
	jausMessage->destination = jausAddressCreate();
	*jausMessage->destination = *message->destination;
	jausMessage->source = jausAddressCreate();
	*jausMessage->source = *message->source;
	jausMessage->dataSize = dataSize(message);
	jausMessage->dataFlag = message->dataFlag;
	jausMessage->sequenceNumber = message->sequenceNumber;
	
	jausMessage->data = (unsigned char *)malloc(jausMessage->dataSize);
	jausMessage->dataSize = dataToBuffer(message, jausMessage->data, jausMessage->dataSize);
	
	return jausMessage;
}


unsigned int createEventMessageSize(CreateEventMessage message)
{
	return (unsigned int)(dataSize(message) + JAUS_HEADER_SIZE_BYTES);
}

//********************* PRIVATE HEADER FUNCTIONS **********************//

static JausBoolean headerFromBuffer(CreateEventMessage message, unsigned char *buffer, unsigned int bufferSizeBytes)
{
	if(bufferSizeBytes < JAUS_HEADER_SIZE_BYTES)
	{ 
		return JAUS_FALSE;
	}
	else
	{
		// unpack header
		message->properties.priority = (buffer[0] & 0x0F);
		message->properties.ackNak	 = ((buffer[0] >> 4) & 0x03);
		message->properties.scFlag	 = ((buffer[0] >> 6) & 0x01);
		message->properties.expFlag	 = ((buffer[0] >> 7) & 0x01);
		message->properties.version	 = (buffer[1] & 0x3F);
		message->properties.reserved = ((buffer[1] >> 6) & 0x03);
		
		message->commandCode = buffer[2] + (buffer[3] << 8);
	
		message->destination->instance = buffer[4];
		message->destination->component = buffer[5];
		message->destination->node = buffer[6];
		message->destination->subsystem = buffer[7];
	
		message->source->instance = buffer[8];
		message->source->component = buffer[9];
		message->source->node = buffer[10];
		message->source->subsystem = buffer[11];
		
		message->dataSize = buffer[12] + ((buffer[13] & 0x0F) << 8);

		message->dataFlag = ((buffer[13] >> 4) & 0x0F);

		message->sequenceNumber = buffer[14] + (buffer[15] << 8);
		
		return JAUS_TRUE;
	}
}

static JausBoolean headerToBuffer(CreateEventMessage message, unsigned char *buffer, unsigned int bufferSizeBytes)
{
	JausUnsignedShort *propertiesPtr = (JausUnsignedShort*)&message->properties;
	
	if(bufferSizeBytes < JAUS_HEADER_SIZE_BYTES)
	{
		return JAUS_FALSE;
	}
	else
	{	
		buffer[0] = (unsigned char)(*propertiesPtr & 0xFF);
		buffer[1] = (unsigned char)((*propertiesPtr & 0xFF00) >> 8);

		buffer[2] = (unsigned char)(message->commandCode & 0xFF);
		buffer[3] = (unsigned char)((message->commandCode & 0xFF00) >> 8);

		buffer[4] = (unsigned char)(message->destination->instance & 0xFF);
		buffer[5] = (unsigned char)(message->destination->component & 0xFF);
		buffer[6] = (unsigned char)(message->destination->node & 0xFF);
		buffer[7] = (unsigned char)(message->destination->subsystem & 0xFF);

		buffer[8] = (unsigned char)(message->source->instance & 0xFF);
		buffer[9] = (unsigned char)(message->source->component & 0xFF);
		buffer[10] = (unsigned char)(message->source->node & 0xFF);
		buffer[11] = (unsigned char)(message->source->subsystem & 0xFF);
		
		buffer[12] = (unsigned char)(message->dataSize & 0xFF);
		buffer[13] = (unsigned char)((message->dataFlag & 0xFF) << 4) | (unsigned char)((message->dataSize & 0x0F00) >> 8);

		buffer[14] = (unsigned char)(message->sequenceNumber & 0xFF);
		buffer[15] = (unsigned char)((message->sequenceNumber & 0xFF00) >> 8);
		
		return JAUS_TRUE;
	}
}