Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
extractorNode Class Reference

Manages the extractor procedure. More...

#include <extractor.hpp>

List of all members.

Public Member Functions

void cameraCallback (const sensor_msgs::Image::ConstPtr &rgbImgMsg, const sensor_msgs::Image::ConstPtr &depthImgMsg, const sensor_msgs::Image::ConstPtr &thermalImgMsg, const sensor_msgs::CameraInfo::ConstPtr &rgbInfoMsg, const sensor_msgs::CameraInfo::ConstPtr &depthInfoMsg, const sensor_msgs::CameraInfo::ConstPtr &thermalInfoMsg)
void extractBagFile ()
 extractorNode (ros::NodeHandle &nh, extractorData startupData)
bool isStillListening ()
void makeDirectories ()
void serverCallback (thermalvis::extractorConfig &config, uint32_t level)
 ~extractorNode ()

Public Attributes

rosbag::Viewview

Private Member Functions

float ** ApplyBilateralFilter (float **data, const int width, const int height, float sigmaP, float sigmaR)

Private Attributes

rosbag::Bag bag [MAX_BAGS]
Mat cameraMatrix
Size cameraSize
extractorData configData
int count
int count_depth
int count_depthinfo
int count_rgb
int count_rgbinfo
int count_thermal
int count_thermalinfo
float d_cx
float d_cy
float d_fx
float d_fy
FILE * dataFile
sensor_msgs::Image::ConstPtr depthImg
sensor_msgs::CameraInfo::ConstPtr depthInfo
FILE * depthInternaltimeFile
stringstream depthInternaltimePath
FILE * depthtimeFile
stringstream depthtimePath
Mat distCoeffs
dynamic_reconfigure::Server
< thermalvis::extractorConfig >
::CallbackType 
f
int filenum
Mat imageSize
FILE * imgInternaltimeFile
stringstream imgInternaltimePath
stringstream imgPath
FILE * imgtimeFile
stringstream imgtimePath
Mat map1
Mat map2
int maxFrames
Mat newCamMat
char nodeName [256]
ofstream ofs_thermistor_log
Mat oldThermal
char * outputcloud
char * outputdepth
char * outputFilename
char * outputFilenameThermal
ros::NodeHandle private_node_handle
ros::NodeHandleref
sensor_msgs::Image::ConstPtr rgbImg
sensor_msgs::CameraInfo::ConstPtr rgbInfo
dynamic_reconfigure::Server
< thermalvis::extractorConfig > 
server
int skipFrames
vector< string > splitBagNames
double startTime
bool stillListening
FILE * thermalDuplicatesFile
stringstream thermalDuplicatesPath
sensor_msgs::Image::ConstPtr thermalImg
sensor_msgs::CameraInfo::ConstPtr thermalInfo
FILE * thermalInternaltimeFile
stringstream thermalInternaltimePath
FILE * thermaltimeFile
stringstream thermaltimePath
string thermistorLogFile
FILE * timeFile
stringstream timePath
std::vector< std::string > topics
float * writeData

Detailed Description

Manages the extractor procedure.

Definition at line 92 of file extractor.hpp.


Constructor & Destructor Documentation

Definition at line 124 of file extractor.cpp.

Definition at line 389 of file extractor.cpp.


Member Function Documentation

float ** extractorNode::ApplyBilateralFilter ( float **  data,
const int  width,
const int  height,
float  sigmaP,
float  sigmaR 
) [private]

Definition at line 881 of file extractor.cpp.

void extractorNode::cameraCallback ( const sensor_msgs::Image::ConstPtr &  rgbImgMsg,
const sensor_msgs::Image::ConstPtr &  depthImgMsg,
const sensor_msgs::Image::ConstPtr &  thermalImgMsg,
const sensor_msgs::CameraInfo::ConstPtr &  rgbInfoMsg,
const sensor_msgs::CameraInfo::ConstPtr &  depthInfoMsg,
const sensor_msgs::CameraInfo::ConstPtr &  thermalInfoMsg 
)

Definition at line 479 of file extractor.cpp.

Definition at line 119 of file extractor.cpp.

Definition at line 430 of file extractor.cpp.

void extractorNode::serverCallback ( thermalvis::extractorConfig &  config,
uint32_t  level 
)

Definition at line 422 of file extractor.cpp.


Member Data Documentation

Definition at line 105 of file extractor.hpp.

Definition at line 98 of file extractor.hpp.

Size extractorNode::cameraSize [private]

Definition at line 99 of file extractor.hpp.

Definition at line 111 of file extractor.hpp.

int extractorNode::count [private]

Definition at line 129 of file extractor.hpp.

Definition at line 154 of file extractor.hpp.

Definition at line 156 of file extractor.hpp.

int extractorNode::count_rgb [private]

Definition at line 153 of file extractor.hpp.

Definition at line 155 of file extractor.hpp.

Definition at line 157 of file extractor.hpp.

Definition at line 158 of file extractor.hpp.

float extractorNode::d_cx [private]

Definition at line 137 of file extractor.hpp.

float extractorNode::d_cy [private]

Definition at line 138 of file extractor.hpp.

float extractorNode::d_fx [private]

Definition at line 135 of file extractor.hpp.

float extractorNode::d_fy [private]

Definition at line 136 of file extractor.hpp.

FILE* extractorNode::dataFile [private]

Definition at line 127 of file extractor.hpp.

sensor_msgs::Image::ConstPtr extractorNode::depthImg [private]

Definition at line 162 of file extractor.hpp.

sensor_msgs::CameraInfo::ConstPtr extractorNode::depthInfo [private]

Definition at line 163 of file extractor.hpp.

Definition at line 127 of file extractor.hpp.

stringstream extractorNode::depthInternaltimePath [private]

Definition at line 146 of file extractor.hpp.

FILE * extractorNode::depthtimeFile [private]

Definition at line 127 of file extractor.hpp.

stringstream extractorNode::depthtimePath [private]

Definition at line 146 of file extractor.hpp.

Definition at line 98 of file extractor.hpp.

dynamic_reconfigure::Server<thermalvis::extractorConfig>::CallbackType extractorNode::f [private]

Definition at line 123 of file extractor.hpp.

int extractorNode::filenum [private]

Definition at line 130 of file extractor.hpp.

Mat extractorNode::imageSize [private]

Definition at line 98 of file extractor.hpp.

Definition at line 127 of file extractor.hpp.

stringstream extractorNode::imgInternaltimePath [private]

Definition at line 146 of file extractor.hpp.

stringstream extractorNode::imgPath [private]

Definition at line 144 of file extractor.hpp.

FILE * extractorNode::imgtimeFile [private]

Definition at line 127 of file extractor.hpp.

stringstream extractorNode::imgtimePath [private]

Definition at line 146 of file extractor.hpp.

Mat extractorNode::map1 [private]

Definition at line 100 of file extractor.hpp.

Mat extractorNode::map2 [private]

Definition at line 100 of file extractor.hpp.

int extractorNode::maxFrames [private]

Definition at line 133 of file extractor.hpp.

Mat extractorNode::newCamMat [private]

Definition at line 98 of file extractor.hpp.

char extractorNode::nodeName[256] [private]

Definition at line 120 of file extractor.hpp.

Definition at line 115 of file extractor.hpp.

Definition at line 103 of file extractor.hpp.

char * extractorNode::outputcloud [private]

Definition at line 142 of file extractor.hpp.

char* extractorNode::outputdepth [private]

Definition at line 142 of file extractor.hpp.

Definition at line 140 of file extractor.hpp.

Definition at line 141 of file extractor.hpp.

Definition at line 118 of file extractor.hpp.

Definition at line 95 of file extractor.hpp.

sensor_msgs::Image::ConstPtr extractorNode::rgbImg [private]

Definition at line 160 of file extractor.hpp.

sensor_msgs::CameraInfo::ConstPtr extractorNode::rgbInfo [private]

Definition at line 161 of file extractor.hpp.

dynamic_reconfigure::Server<thermalvis::extractorConfig> extractorNode::server [private]

Definition at line 122 of file extractor.hpp.

Definition at line 132 of file extractor.hpp.

vector<string> extractorNode::splitBagNames [private]

Definition at line 107 of file extractor.hpp.

double extractorNode::startTime [private]

Definition at line 131 of file extractor.hpp.

Definition at line 113 of file extractor.hpp.

Definition at line 127 of file extractor.hpp.

stringstream extractorNode::thermalDuplicatesPath [private]

Definition at line 146 of file extractor.hpp.

sensor_msgs::Image::ConstPtr extractorNode::thermalImg [private]

Definition at line 164 of file extractor.hpp.

sensor_msgs::CameraInfo::ConstPtr extractorNode::thermalInfo [private]

Definition at line 165 of file extractor.hpp.

Definition at line 127 of file extractor.hpp.

Definition at line 146 of file extractor.hpp.

Definition at line 127 of file extractor.hpp.

stringstream extractorNode::thermaltimePath [private]

Definition at line 146 of file extractor.hpp.

Definition at line 116 of file extractor.hpp.

FILE * extractorNode::timeFile [private]

Definition at line 127 of file extractor.hpp.

stringstream extractorNode::timePath [private]

Definition at line 145 of file extractor.hpp.

std::vector<std::string> extractorNode::topics [private]

Definition at line 149 of file extractor.hpp.

Definition at line 170 of file extractor.hpp.

float* extractorNode::writeData [private]

Definition at line 109 of file extractor.hpp.


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


thermalvis
Author(s): Stephen Vidas
autogenerated on Sun Jan 5 2014 11:38:45