Public Member Functions | Public Attributes | List of all members
DataEngine Class Reference

#include <data_engine.h>

Public Member Functions

std::pair< Eigen::MatrixXd, Eigen::Vector3d > coord_trans_7f_rt (std::vector< float > pose)
 
iro::SE2 coord_trans_7f_se2 (std::vector< float > pose)
 
Eigen::Vector2i coord_trans_oc2cell (Eigen::Vector3d p_oc)
 
Eigen::Vector2i coord_trans_oc2cell (Eigen::Vector3d p_oc, double node_size, int scale)
 
std::vector< double > coord_trans_se22gazebo (iro::SE2 pose)
 
bool create_connection ()
 
 DataEngine (int r_num)
 
void fillTrivialHolesKnownRegion ()
 
void findExtraFreeSpace (int rid, cv::Mat depth, std::vector< float > pose)
 
void fuseScans2MapAndTree ()
 
bool getPoseFromServer ()
 
bool getRGBDFromServer ()
 
int initialize ()
 
void insertAFrame2Tree (cv::Mat &depth, std::vector< float > pose)
 
std::vector< cv::Point > loadIdealFrustum (Eigen::MatrixXd r, Eigen::Vector3d t)
 
void projectOctree2Map ()
 
bool rcvPoseFromServer ()
 
bool rcvRGBDFromServer ()
 
void scanSurroundingsCmd ()
 
void SetUpSurroundings ()
 
cv::Mat showCellMap ()
 
cv::Mat showStatement ()
 
bool socket_move_to_views (std::vector< std::vector< double >> poses)
 
void test ()
 
cv::Mat visCellMap ()
 

Public Attributes

const double camera_cx = 320.5
 
const double camera_cy = 240.5
 
const double camera_factor = 1000
 
const double camera_fx = 554.38
 
const double camera_fy = 554.38
 
const int frame_cols = 640
 
const int frame_rows = 480
 
std::vector< cv::Mat > m_depth
 
std::vector< std::vector< cv::Point > > m_free_space_contours2d
 
std::vector< std::vector< cv::Point > > m_frustum_contours
 
std::vector< std::vector< float > > m_pose
 
std::vector< iro::SE2m_pose2d
 
Recon2D m_recon2D
 
Recon3D m_recon3D
 
std::vector< cv::Mat > m_rgb
 
std::vector< std::vector< float > > m_set_pose
 
const int MAXRECV = 10240
 
int rbt_num = 3
 
const int scan_max_range = 3000
 
char * server_ip = "192.168.180.128"
 
int sockClient
 

Detailed Description

Definition at line 101 of file data_engine.h.

Constructor & Destructor Documentation

◆ DataEngine()

DataEngine::DataEngine ( int  r_num)
inline

Definition at line 136 of file data_engine.h.

Member Function Documentation

◆ coord_trans_7f_rt()

pair< Eigen::MatrixXd, Eigen::Vector3d > DataEngine::coord_trans_7f_rt ( std::vector< float >  pose)

Definition at line 598 of file data_engine.cpp.

◆ coord_trans_7f_se2()

iro::SE2 DataEngine::coord_trans_7f_se2 ( std::vector< float >  pose)

Definition at line 607 of file data_engine.cpp.

◆ coord_trans_oc2cell() [1/2]

Eigen::Vector2i DataEngine::coord_trans_oc2cell ( Eigen::Vector3d  p_oc)

Definition at line 637 of file data_engine.cpp.

◆ coord_trans_oc2cell() [2/2]

Eigen::Vector2i DataEngine::coord_trans_oc2cell ( Eigen::Vector3d  p_oc,
double  node_size,
int  scale 
)

Definition at line 650 of file data_engine.cpp.

◆ coord_trans_se22gazebo()

vector< double > DataEngine::coord_trans_se22gazebo ( iro::SE2  pose)

Definition at line 659 of file data_engine.cpp.

◆ create_connection()

bool DataEngine::create_connection ( )

Definition at line 12 of file data_engine.cpp.

◆ fillTrivialHolesKnownRegion()

void DataEngine::fillTrivialHolesKnownRegion ( )

Definition at line 1063 of file data_engine.cpp.

◆ findExtraFreeSpace()

void DataEngine::findExtraFreeSpace ( int  rid,
cv::Mat  depth,
std::vector< float >  pose 
)

Definition at line 846 of file data_engine.cpp.

◆ fuseScans2MapAndTree()

void DataEngine::fuseScans2MapAndTree ( )

Definition at line 1194 of file data_engine.cpp.

◆ getPoseFromServer()

bool DataEngine::getPoseFromServer ( )

Definition at line 244 of file data_engine.cpp.

◆ getRGBDFromServer()

bool DataEngine::getRGBDFromServer ( )

Definition at line 63 of file data_engine.cpp.

◆ initialize()

int DataEngine::initialize ( )
inline

Definition at line 168 of file data_engine.h.

◆ insertAFrame2Tree()

void DataEngine::insertAFrame2Tree ( cv::Mat &  depth,
std::vector< float >  pose 
)

Definition at line 1222 of file data_engine.cpp.

◆ loadIdealFrustum()

vector< cv::Point > DataEngine::loadIdealFrustum ( Eigen::MatrixXd  r,
Eigen::Vector3d  t 
)

Definition at line 988 of file data_engine.cpp.

◆ projectOctree2Map()

void DataEngine::projectOctree2Map ( )

Definition at line 689 of file data_engine.cpp.

◆ rcvPoseFromServer()

bool DataEngine::rcvPoseFromServer ( )

Definition at line 483 of file data_engine.cpp.

◆ rcvRGBDFromServer()

bool DataEngine::rcvRGBDFromServer ( )

Definition at line 350 of file data_engine.cpp.

◆ scanSurroundingsCmd()

void DataEngine::scanSurroundingsCmd ( )

Definition at line 545 of file data_engine.cpp.

◆ SetUpSurroundings()

void DataEngine::SetUpSurroundings ( )

Definition at line 585 of file data_engine.cpp.

◆ showCellMap()

cv::Mat DataEngine::showCellMap ( )

Definition at line 1381 of file data_engine.cpp.

◆ showStatement()

cv::Mat DataEngine::showStatement ( )

Definition at line 1390 of file data_engine.cpp.

◆ socket_move_to_views()

bool DataEngine::socket_move_to_views ( std::vector< std::vector< double >>  poses)

Definition at line 554 of file data_engine.cpp.

◆ test()

void DataEngine::test ( )
inline

Definition at line 241 of file data_engine.h.

◆ visCellMap()

cv::Mat DataEngine::visCellMap ( )

Definition at line 1361 of file data_engine.cpp.

Member Data Documentation

◆ camera_cx

const double DataEngine::camera_cx = 320.5

Definition at line 106 of file data_engine.h.

◆ camera_cy

const double DataEngine::camera_cy = 240.5

Definition at line 107 of file data_engine.h.

◆ camera_factor

const double DataEngine::camera_factor = 1000

Definition at line 105 of file data_engine.h.

◆ camera_fx

const double DataEngine::camera_fx = 554.38

Definition at line 108 of file data_engine.h.

◆ camera_fy

const double DataEngine::camera_fy = 554.38

Definition at line 109 of file data_engine.h.

◆ frame_cols

const int DataEngine::frame_cols = 640

Definition at line 115 of file data_engine.h.

◆ frame_rows

const int DataEngine::frame_rows = 480

Definition at line 114 of file data_engine.h.

◆ m_depth

std::vector<cv::Mat> DataEngine::m_depth

Definition at line 122 of file data_engine.h.

◆ m_free_space_contours2d

std::vector<std::vector<cv::Point> > DataEngine::m_free_space_contours2d

Definition at line 131 of file data_engine.h.

◆ m_frustum_contours

std::vector<std::vector<cv::Point> > DataEngine::m_frustum_contours

Definition at line 129 of file data_engine.h.

◆ m_pose

std::vector<std::vector<float> > DataEngine::m_pose

Definition at line 123 of file data_engine.h.

◆ m_pose2d

std::vector<iro::SE2> DataEngine::m_pose2d

Definition at line 133 of file data_engine.h.

◆ m_recon2D

Recon2D DataEngine::m_recon2D

Definition at line 127 of file data_engine.h.

◆ m_recon3D

Recon3D DataEngine::m_recon3D

Definition at line 126 of file data_engine.h.

◆ m_rgb

std::vector<cv::Mat> DataEngine::m_rgb

Definition at line 121 of file data_engine.h.

◆ m_set_pose

std::vector<std::vector<float> > DataEngine::m_set_pose

Definition at line 124 of file data_engine.h.

◆ MAXRECV

const int DataEngine::MAXRECV = 10240

Definition at line 113 of file data_engine.h.

◆ rbt_num

int DataEngine::rbt_num = 3

Definition at line 120 of file data_engine.h.

◆ scan_max_range

const int DataEngine::scan_max_range = 3000

Definition at line 110 of file data_engine.h.

◆ server_ip

char* DataEngine::server_ip = "192.168.180.128"

Definition at line 116 of file data_engine.h.

◆ sockClient

int DataEngine::sockClient

Definition at line 117 of file data_engine.h.


The documentation for this class was generated from the following files:


co_scan
Author(s):
autogenerated on Mon Feb 28 2022 23:00:58