ICAROUS
All Classes Namespaces Files Functions Variables Enumerations Enumerator Macros Modules Pages
Classes | Macros | Enumerations | Functions
port_lib.h File Reference

serial/socket port library More...

#include "cfe.h"
#include <string.h>
#include <errno.h>
#include <unistd.h>
#include <stdbool.h>
#include <fcntl.h>
#include <termios.h>
#include "network_includes.h"
#include "mavlink/ardupilotmega/mavlink.h"

Go to the source code of this file.

Classes

struct  port_t
 Structure to hold port attributes. More...
 

Macros

#define BUFFER_LENGTH   1000
 Mavlink message receive buffer size.
 

Enumerations

enum  portType_e { SOCKET , SERIAL }
 

Functions

int32 Port_LibInit (void)
 
void InitializeSocketPort (port_t *prt)
 
int InitializeSerialPort (port_t *prt, bool should_block)
 
void writeMavlinkData (port_t *prt, mavlink_message_t *message)
 
int readPort (port_t *prt)
 
void writeData (port_t *prt, char *sendbuffer, int datalength)
 

Enumeration Type Documentation

◆ portType_e

enum portType_e
Enumerator
SOCKET 

enum value SOCKET

SERIAL 

enum value SERIAL

Function Documentation

◆ InitializeSerialPort()

int InitializeSerialPort ( port_t prt,
bool  should_block 
)

Initialize a serial port

Parameters
*prtpointer to port

◆ InitializeSocketPort()

void InitializeSocketPort ( port_t prt)

Initialize a socket port

Parameters
*prtpointer to port

◆ Port_LibInit()

int32 Port_LibInit ( void  )

Initialize port library

Returns

◆ readPort()

int readPort ( port_t prt)

Read raw data from port

Parameters
prtpointer to port to read from

◆ writeData()

void writeData ( port_t prt,
char *  sendbuffer,
int  datalength 
)

Write raw data to port

Parameters
prtpointer to port to read data from
sendbufferpointer to char array contiaining data
datalengthlength of data to be used

◆ writeMavlinkData()

void writeMavlinkData ( port_t prt,
mavlink_message_t *  message 
)

Write mavlink message to a given port

Parameters
*prtpointer to output port
*messagepointer to mavlink message