#include <data_engine.h>
Definition at line 101 of file data_engine.h.
◆ DataEngine()
| DataEngine::DataEngine |
( |
int |
r_num | ) |
|
|
inline |
◆ coord_trans_7f_rt()
| pair< Eigen::MatrixXd, Eigen::Vector3d > DataEngine::coord_trans_7f_rt |
( |
std::vector< float > |
pose | ) |
|
◆ coord_trans_7f_se2()
| iro::SE2 DataEngine::coord_trans_7f_se2 |
( |
std::vector< float > |
pose | ) |
|
◆ coord_trans_oc2cell() [1/2]
| Eigen::Vector2i DataEngine::coord_trans_oc2cell |
( |
Eigen::Vector3d |
p_oc | ) |
|
◆ coord_trans_oc2cell() [2/2]
| Eigen::Vector2i DataEngine::coord_trans_oc2cell |
( |
Eigen::Vector3d |
p_oc, |
|
|
double |
node_size, |
|
|
int |
scale |
|
) |
| |
◆ coord_trans_se22gazebo()
| vector< double > DataEngine::coord_trans_se22gazebo |
( |
iro::SE2 |
pose | ) |
|
◆ create_connection()
| bool DataEngine::create_connection |
( |
| ) |
|
◆ fillTrivialHolesKnownRegion()
| void DataEngine::fillTrivialHolesKnownRegion |
( |
| ) |
|
◆ findExtraFreeSpace()
| void DataEngine::findExtraFreeSpace |
( |
int |
rid, |
|
|
cv::Mat |
depth, |
|
|
std::vector< float > |
pose |
|
) |
| |
◆ fuseScans2MapAndTree()
| void DataEngine::fuseScans2MapAndTree |
( |
| ) |
|
◆ getPoseFromServer()
| bool DataEngine::getPoseFromServer |
( |
| ) |
|
◆ getRGBDFromServer()
| bool DataEngine::getRGBDFromServer |
( |
| ) |
|
◆ initialize()
| int DataEngine::initialize |
( |
| ) |
|
|
inline |
◆ insertAFrame2Tree()
| void DataEngine::insertAFrame2Tree |
( |
cv::Mat & |
depth, |
|
|
std::vector< float > |
pose |
|
) |
| |
◆ loadIdealFrustum()
| vector< cv::Point > DataEngine::loadIdealFrustum |
( |
Eigen::MatrixXd |
r, |
|
|
Eigen::Vector3d |
t |
|
) |
| |
◆ projectOctree2Map()
| void DataEngine::projectOctree2Map |
( |
| ) |
|
◆ rcvPoseFromServer()
| bool DataEngine::rcvPoseFromServer |
( |
| ) |
|
◆ rcvRGBDFromServer()
| bool DataEngine::rcvRGBDFromServer |
( |
| ) |
|
◆ scanSurroundingsCmd()
| void DataEngine::scanSurroundingsCmd |
( |
| ) |
|
◆ SetUpSurroundings()
| void DataEngine::SetUpSurroundings |
( |
| ) |
|
◆ showCellMap()
| cv::Mat DataEngine::showCellMap |
( |
| ) |
|
◆ showStatement()
| cv::Mat DataEngine::showStatement |
( |
| ) |
|
◆ socket_move_to_views()
| bool DataEngine::socket_move_to_views |
( |
std::vector< std::vector< double >> |
poses | ) |
|
◆ test()
| void DataEngine::test |
( |
| ) |
|
|
inline |
◆ visCellMap()
| cv::Mat DataEngine::visCellMap |
( |
| ) |
|
◆ camera_cx
| const double DataEngine::camera_cx = 320.5 |
◆ camera_cy
| const double DataEngine::camera_cy = 240.5 |
◆ camera_factor
| const double DataEngine::camera_factor = 1000 |
◆ camera_fx
| const double DataEngine::camera_fx = 554.38 |
◆ camera_fy
| const double DataEngine::camera_fy = 554.38 |
◆ frame_cols
| const int DataEngine::frame_cols = 640 |
◆ frame_rows
| const int DataEngine::frame_rows = 480 |
◆ m_depth
| std::vector<cv::Mat> DataEngine::m_depth |
◆ m_free_space_contours2d
| std::vector<std::vector<cv::Point> > DataEngine::m_free_space_contours2d |
◆ m_frustum_contours
| std::vector<std::vector<cv::Point> > DataEngine::m_frustum_contours |
◆ m_pose
| std::vector<std::vector<float> > DataEngine::m_pose |
◆ m_pose2d
| std::vector<iro::SE2> DataEngine::m_pose2d |
◆ m_recon2D
◆ m_recon3D
◆ m_rgb
| std::vector<cv::Mat> DataEngine::m_rgb |
◆ m_set_pose
| std::vector<std::vector<float> > DataEngine::m_set_pose |
◆ MAXRECV
| const int DataEngine::MAXRECV = 10240 |
◆ rbt_num
| int DataEngine::rbt_num = 3 |
◆ scan_max_range
| const int DataEngine::scan_max_range = 3000 |
◆ server_ip
| char* DataEngine::server_ip = "192.168.180.128" |
◆ sockClient
| int DataEngine::sockClient |
The documentation for this class was generated from the following files: