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.
|
#define | BUFFER_LENGTH 1000 |
| Mavlink message receive buffer size.
|
|
◆ portType_e
Enumerator |
---|
SOCKET | enum value SOCKET
|
SERIAL | enum value SERIAL
|
◆ InitializeSerialPort()
int InitializeSerialPort |
( |
port_t * |
prt, |
|
|
bool |
should_block |
|
) |
| |
Initialize a serial port
- Parameters
-
◆ InitializeSocketPort()
void InitializeSocketPort |
( |
port_t * |
prt | ) |
|
Initialize a socket port
- Parameters
-
◆ Port_LibInit()
int32 Port_LibInit |
( |
void |
| ) |
|
Initialize port library
- Returns
◆ readPort()
Read raw data from port
- Parameters
-
prt | pointer to port to read from |
◆ writeData()
void writeData |
( |
port_t * |
prt, |
|
|
char * |
sendbuffer, |
|
|
int |
datalength |
|
) |
| |
Write raw data to port
- Parameters
-
prt | pointer to port to read data from |
sendbuffer | pointer to char array contiaining data |
datalength | length of data to be used |
◆ writeMavlinkData()
void writeMavlinkData |
( |
port_t * |
prt, |
|
|
mavlink_message_t * |
message |
|
) |
| |
Write mavlink message to a given port
- Parameters
-
*prt | pointer to output port |
*message | pointer to mavlink message |