Classes | Macros | Functions | Variables
test_com_manager.cpp File Reference
#include "gtest/gtest.h"
#include <deque>
#include "../com_manager.h"
#include "../ring_buffer.h"
#include "../protocol_nmea.h"
Include dependency graph for test_com_manager.cpp:

Go to the source code of this file.

Classes

struct  data_holder_t
 
struct  test_data_t
 

Macros

#define DEBUG_PRINTF
 
#define NUM_HANDLES   1
 
#define PORT_BUFFER_SIZE   8192
 
#define TASK_PERIOD_MS   1
 
#define TEST_PROTO_ASCII   1
 
#define TEST_PROTO_IS   1
 
#define TEST_PROTO_RTCM3   1
 
#define TEST_PROTO_UBLOX   1
 
#define TIMES_TO_DIVIDE_DATA   10
 

Functions

void addDequeToRingBuf (std::deque< data_holder_t > &testDeque, ring_buf_t *rbuf)
 
void disableBroadcasts (CMHANDLE cmHandle, int pHandle)
 
void generateData (std::deque< data_holder_t > &testDeque)
 
bool init (test_data_t &t)
 
bool initComManager (test_data_t &t)
 
int msgHandlerAscii (CMHANDLE cmHandle, int pHandle, const uint8_t *msg, int msgSize)
 
int msgHandlerRtcm3 (CMHANDLE cmHandle, int pHandle, const uint8_t *msg, int msgSize)
 
int msgHandlerUblox (CMHANDLE cmHandle, int pHandle, const uint8_t *msg, int msgSize)
 
void parseDataPortTxBuf (std::deque< data_holder_t > &testDeque, test_data_t &t)
 
int portRead (CMHANDLE cmHandle, int pHandle, unsigned char *buf, int len)
 
int portWrite (CMHANDLE cmHandle, int pHandle, unsigned char *buf, int len)
 
void postRxRead (CMHANDLE cmHandle, int pHandle, p_data_t *dataRead)
 
void prepDevInfo (CMHANDLE cmHandle, int pHandle)
 
void ringBuftoRingBufWrite (ring_buf_t *dst, ring_buf_t *src, int len)
 
 TEST (ComManager, BasicTxTest)
 
 TEST (ComManager, BasicRxTest)
 
 TEST (ComManager, SegmentedRxTest)
 
 TEST (ComManager, RxWithGarbageTest)
 
 TEST (ComManager, Evb2AltDecodeBufferTest)
 
 TEST (ComManager, Evb2DataForwardTest)
 
void writeNvrUserpageFlashCfg (CMHANDLE cmHandle, int pHandle, p_data_t *data)
 

Variables

std::deque< data_holder_tg_testRxDeque
 
std::deque< data_holder_tg_testTxDeque
 
static com_manager_port_t s_cmPort = {}
 
static is_comm_instance_t s_comm [NUM_HANDLES] = { 0 }
 
static uint8_t s_comm_buffer [NUM_HANDLES *PKT_BUF_SIZE] = { 0 }
 
test_data_t tcm = {}
 

Macro Definition Documentation

◆ DEBUG_PRINTF

#define DEBUG_PRINTF

Definition at line 27 of file test_com_manager.cpp.

◆ NUM_HANDLES

#define NUM_HANDLES   1

Definition at line 249 of file test_com_manager.cpp.

◆ PORT_BUFFER_SIZE

#define PORT_BUFFER_SIZE   8192

Definition at line 30 of file test_com_manager.cpp.

◆ TASK_PERIOD_MS

#define TASK_PERIOD_MS   1

Definition at line 23 of file test_com_manager.cpp.

◆ TEST_PROTO_ASCII

#define TEST_PROTO_ASCII   1

Definition at line 19 of file test_com_manager.cpp.

◆ TEST_PROTO_IS

#define TEST_PROTO_IS   1

Definition at line 18 of file test_com_manager.cpp.

◆ TEST_PROTO_RTCM3

#define TEST_PROTO_RTCM3   1

Definition at line 21 of file test_com_manager.cpp.

◆ TEST_PROTO_UBLOX

#define TEST_PROTO_UBLOX   1

Definition at line 20 of file test_com_manager.cpp.

◆ TIMES_TO_DIVIDE_DATA

#define TIMES_TO_DIVIDE_DATA   10

Function Documentation

◆ addDequeToRingBuf()

void addDequeToRingBuf ( std::deque< data_holder_t > &  testDeque,
ring_buf_t rbuf 
)

Definition at line 516 of file test_com_manager.cpp.

◆ disableBroadcasts()

void disableBroadcasts ( CMHANDLE  cmHandle,
int  pHandle 
)

Definition at line 96 of file test_com_manager.cpp.

◆ generateData()

void generateData ( std::deque< data_holder_t > &  testDeque)

Definition at line 289 of file test_com_manager.cpp.

◆ init()

bool init ( test_data_t t)

Definition at line 279 of file test_com_manager.cpp.

◆ initComManager()

bool initComManager ( test_data_t t)

Definition at line 254 of file test_com_manager.cpp.

◆ msgHandlerAscii()

int msgHandlerAscii ( CMHANDLE  cmHandle,
int  pHandle,
const uint8_t *  msg,
int  msgSize 
)

Definition at line 109 of file test_com_manager.cpp.

◆ msgHandlerRtcm3()

int msgHandlerRtcm3 ( CMHANDLE  cmHandle,
int  pHandle,
const uint8_t *  msg,
int  msgSize 
)

Definition at line 210 of file test_com_manager.cpp.

◆ msgHandlerUblox()

int msgHandlerUblox ( CMHANDLE  cmHandle,
int  pHandle,
const uint8_t *  msg,
int  msgSize 
)

Definition at line 171 of file test_com_manager.cpp.

◆ parseDataPortTxBuf()

void parseDataPortTxBuf ( std::deque< data_holder_t > &  testDeque,
test_data_t t 
)

Definition at line 553 of file test_com_manager.cpp.

◆ portRead()

int portRead ( CMHANDLE  cmHandle,
int  pHandle,
unsigned char *  buf,
int  len 
)

Definition at line 69 of file test_com_manager.cpp.

◆ portWrite()

int portWrite ( CMHANDLE  cmHandle,
int  pHandle,
unsigned char *  buf,
int  len 
)

Definition at line 74 of file test_com_manager.cpp.

◆ postRxRead()

void postRxRead ( CMHANDLE  cmHandle,
int  pHandle,
p_data_t dataRead 
)

Definition at line 84 of file test_com_manager.cpp.

◆ prepDevInfo()

void prepDevInfo ( CMHANDLE  cmHandle,
int  pHandle 
)

Definition at line 100 of file test_com_manager.cpp.

◆ ringBuftoRingBufWrite()

void ringBuftoRingBufWrite ( ring_buf_t dst,
ring_buf_t src,
int  len 
)

Definition at line 598 of file test_com_manager.cpp.

◆ TEST() [1/6]

TEST ( ComManager  ,
BasicTxTest   
)

Definition at line 608 of file test_com_manager.cpp.

◆ TEST() [2/6]

TEST ( ComManager  ,
BasicRxTest   
)

Definition at line 648 of file test_com_manager.cpp.

◆ TEST() [3/6]

TEST ( ComManager  ,
SegmentedRxTest   
)

Definition at line 676 of file test_com_manager.cpp.

◆ TEST() [4/6]

TEST ( ComManager  ,
RxWithGarbageTest   
)

Definition at line 719 of file test_com_manager.cpp.

◆ TEST() [5/6]

TEST ( ComManager  ,
Evb2AltDecodeBufferTest   
)

Definition at line 766 of file test_com_manager.cpp.

◆ TEST() [6/6]

TEST ( ComManager  ,
Evb2DataForwardTest   
)

Definition at line 854 of file test_com_manager.cpp.

◆ writeNvrUserpageFlashCfg()

void writeNvrUserpageFlashCfg ( CMHANDLE  cmHandle,
int  pHandle,
p_data_t data 
)

Definition at line 104 of file test_com_manager.cpp.

Variable Documentation

◆ g_testRxDeque

std::deque<data_holder_t> g_testRxDeque

Definition at line 65 of file test_com_manager.cpp.

◆ g_testTxDeque

std::deque<data_holder_t> g_testTxDeque

Definition at line 66 of file test_com_manager.cpp.

◆ s_cmPort

com_manager_port_t s_cmPort = {}
static

Definition at line 252 of file test_com_manager.cpp.

◆ s_comm

is_comm_instance_t s_comm[NUM_HANDLES] = { 0 }
static

Definition at line 250 of file test_com_manager.cpp.

◆ s_comm_buffer

uint8_t s_comm_buffer[NUM_HANDLES *PKT_BUF_SIZE] = { 0 }
static

Definition at line 251 of file test_com_manager.cpp.

◆ tcm

test_data_t tcm = {}

Definition at line 64 of file test_com_manager.cpp.



inertial_sense_ros
Author(s):
autogenerated on Sat Sep 19 2020 03:19:07