$search

streamerNode Class Reference

Manages the driver / streamer. More...

#include <streamer.hpp>

List of all members.

Public Member Functions

void acceptImage (void *ptr)
void act_on_image ()
void assignCameraInfo ()
void assignDefaultCameraInfo ()
bool configureSerialComms ()
streamerSourcegetMainVideoSource ()
void getRectification ()
float getThermistorReading ()
VideoCapture * getVideoCapture ()
void handle_camera (const sensor_msgs::ImageConstPtr &msg_ptr, const sensor_msgs::CameraInfoConstPtr &info_msg)
void handle_image (const sensor_msgs::ImageConstPtr &msg_ptr)
void handle_info (const sensor_msgs::CameraInfoConstPtr &info_msg)
void initializeMessages ()
bool isVideoValid ()
void markCurrentFrameAsDuplicate ()
int mygetch ()
int open_port ()
void overwriteCameraDims ()
void prepareForTermination ()
bool processFolder ()
bool processImage ()
void publishTopics ()
void refreshCameraAdvertisements ()
void releaseDevice ()
bool runBag ()
bool runDevice ()
bool runLoad ()
bool runRead ()
void serialCallback (const ros::TimerEvent &e)
void serverCallback (thermalvis::streamerConfig &config, uint32_t level)
bool setCameraInfo (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
bool setupDevice ()
void setValidity (bool val)
bool streamCallback (bool capture=true)
 streamerNode (ros::NodeHandle &nh, streamerData startupData)
void timerCallback (const ros::TimerEvent &e)
void updateCameraInfo ()
void updateCameraInfoExtrinsics ()
void updateMap ()
void writeData ()

Public Attributes

CvCapture * capture

Private Attributes

Mat _16bitMat
Mat _16bitMat_pub
Mat _8bitMat
Mat _8bitMat_pub
bool alphaChanged
int alternateCounter
bool altStatus
string callLogFile
sensor_msgs::CameraInfo camera_info
image_transport::CameraSubscriber camera_sub
VideoCapture cap
bool centerPrincipalPoint
cScheme colourMap
Mat colourMat
Mat colourMat_pub
streamerData configData
cv_bridge::CvImagePtr cv_ptr
int device_num
ros::Time dodgeTime
string duplicatesLogFile
dynamic_reconfigure::Server
< thermalvis::streamerConfig >
::CallbackType 
f
int fileCount
int64_t firmwareTime
bool firstCall
bool firstFrame
bool firstServerCallbackProcessed
Mat frame
int frameCounter
double fusionFactor
camData_ globalCameraInfo
camExtrinsicsData_ globalExtrinsicsData
image_transport::Subscriber image_sub
ros::Time image_time
ros::Subscriber info_sub
ros::Time info_time
vector< string > inputList
unsigned long internal_time
string internalLogFile
bool isActuallyGray
image_transport::ImageTransportit
Mat lastFrame
double lastLowerLimit
double lastMedian
float lastThermistorReading
double lastUpperLimit
int lastWritten
int mainfd
streamerSourcemainVideoSource
Mat map1
Mat map2
double maxVal
double medianPercentile
double minVal
sensor_msgs::Image msg_16bit
sensor_msgs::Image msg_8bit
sensor_msgs::Image msg_color
Mat newImage
double newMedian
float newThermistorReading
char nodeName [256]
Mat normalizedMat
ofstream ofs
ofstream ofs_call_log
ofstream ofs_duplicates_log
ofstream ofs_internal_log
ofstream ofs_retrieve_log
ofstream ofs_thermistor_log
ofstream ofs_write_log
double oldMaxDiff
unsigned long original_bx
unsigned long original_by
ros::Time original_time
int pastMeanIndex
double pastMeans [256]
bool performingNuc
Mat preFilteredMat
image_transport::CameraPublisher pub_16bit
image_transport::Publisher pub_16bit_im
image_transport::CameraPublisher pub_8bit
image_transport::Publisher pub_8bit_im
image_transport::CameraPublisher pub_color
image_transport::Publisher pub_color_im
image_transport::CameraPublisher pub_republish
image_transport::Publisher pub_republish_im
bool readyToPublish
string retrieveLogFile
Mat rzMat
ros::Timer serial_timer
char serialCommand [256]
dynamic_reconfigure::Server
< thermalvis::streamerConfig > 
server
ros::ServiceServer set_camera_info
double shiftDiff
Mat smoothedMat
Mat testMat
string thermistorLogFile
ros::Timer timer
Mat undistorted
bool updateDetectorMode
bool updateNucInterval
VideoWriter vid_writer
bool videoInitialized
bool videoValid
Mat workingFrame
int writeIndex
string writeLogFile

Detailed Description

Manages the driver / streamer.

Definition at line 268 of file streamer.hpp.


Constructor & Destructor Documentation

streamerNode::streamerNode ( ros::NodeHandle nh,
streamerData  startupData 
)

Definition at line 1672 of file streamer.cpp.


Member Function Documentation

void streamerNode::acceptImage ( void *  ptr  ) 

Definition at line 724 of file streamer.cpp.

void streamerNode::act_on_image (  ) 

Definition at line 2115 of file streamer.cpp.

void streamerNode::assignCameraInfo (  ) 

* use data from intrinsics file

Definition at line 428 of file streamer.cpp.

void streamerNode::assignDefaultCameraInfo (  ) 

Definition at line 1652 of file streamer.cpp.

bool streamerNode::configureSerialComms (  ) 

Definition at line 3117 of file streamer.cpp.

streamerSource * streamerNode::getMainVideoSource (  ) 

Definition at line 2607 of file streamer.cpp.

void streamerNode::getRectification (  ) 

Definition at line 1947 of file streamer.cpp.

float streamerNode::getThermistorReading (  ) 

Definition at line 3260 of file streamer.cpp.

VideoCapture * streamerNode::getVideoCapture (  ) 

Definition at line 2611 of file streamer.cpp.

void streamerNode::handle_camera ( const sensor_msgs::ImageConstPtr msg_ptr,
const sensor_msgs::CameraInfoConstPtr info_msg 
)

Definition at line 2085 of file streamer.cpp.

void streamerNode::handle_image ( const sensor_msgs::ImageConstPtr msg_ptr  ) 

Definition at line 2155 of file streamer.cpp.

void streamerNode::handle_info ( const sensor_msgs::CameraInfoConstPtr info_msg  ) 

Definition at line 1970 of file streamer.cpp.

void streamerNode::initializeMessages (  ) 

Definition at line 1001 of file streamer.cpp.

bool streamerNode::isVideoValid (  ) 

Definition at line 2591 of file streamer.cpp.

void streamerNode::markCurrentFrameAsDuplicate (  ) 

Definition at line 363 of file streamer.cpp.

int streamerNode::mygetch (  ) 

Definition at line 3092 of file streamer.cpp.

int streamerNode::open_port (  ) 

Definition at line 3104 of file streamer.cpp.

void streamerNode::overwriteCameraDims (  ) 

Definition at line 1665 of file streamer.cpp.

void streamerNode::prepareForTermination (  ) 

Definition at line 67 of file streamer.cpp.

bool streamerNode::processFolder (  ) 

Definition at line 325 of file streamer.cpp.

bool streamerNode::processImage (  ) 

Definition at line 764 of file streamer.cpp.

void streamerNode::publishTopics (  ) 

Definition at line 1046 of file streamer.cpp.

void streamerNode::refreshCameraAdvertisements (  ) 

Definition at line 2000 of file streamer.cpp.

void streamerNode::releaseDevice (  ) 

Definition at line 162 of file streamer.cpp.

bool streamerNode::runBag (  ) 

Definition at line 301 of file streamer.cpp.

bool streamerNode::runDevice (  ) 

Definition at line 177 of file streamer.cpp.

bool streamerNode::runLoad (  ) 

Definition at line 234 of file streamer.cpp.

bool streamerNode::runRead (  ) 

Definition at line 257 of file streamer.cpp.

void streamerNode::serialCallback ( const ros::TimerEvent e  ) 

Definition at line 1315 of file streamer.cpp.

void streamerNode::serverCallback ( thermalvis::streamerConfig &  config,
uint32_t  level 
)

Definition at line 2656 of file streamer.cpp.

bool streamerNode::setCameraInfo ( sensor_msgs::SetCameraInfo::Request req,
sensor_msgs::SetCameraInfo::Response rsp 
)

Definition at line 588 of file streamer.cpp.

bool streamerNode::setupDevice (  ) 

Definition at line 117 of file streamer.cpp.

void streamerNode::setValidity ( bool  val  ) 

Definition at line 2602 of file streamer.cpp.

bool streamerNode::streamCallback ( bool  capture = true  ) 

Definition at line 605 of file streamer.cpp.

void streamerNode::timerCallback ( const ros::TimerEvent e  ) 

Definition at line 1490 of file streamer.cpp.

void streamerNode::updateCameraInfo (  ) 

Definition at line 369 of file streamer.cpp.

void streamerNode::updateCameraInfoExtrinsics (  ) 

Definition at line 570 of file streamer.cpp.

void streamerNode::updateMap (  ) 

Definition at line 2615 of file streamer.cpp.

void streamerNode::writeData (  ) 

Definition at line 1229 of file streamer.cpp.


Member Data Documentation

Mat streamerNode::_16bitMat [private]

Definition at line 363 of file streamer.hpp.

Definition at line 365 of file streamer.hpp.

Mat streamerNode::_8bitMat [private]

Definition at line 363 of file streamer.hpp.

Definition at line 365 of file streamer.hpp.

Definition at line 349 of file streamer.hpp.

Definition at line 284 of file streamer.hpp.

bool streamerNode::altStatus [private]

Definition at line 279 of file streamer.hpp.

string streamerNode::callLogFile [private]

Definition at line 289 of file streamer.hpp.

Definition at line 375 of file streamer.hpp.

Definition at line 302 of file streamer.hpp.

VideoCapture streamerNode::cap [private]

Definition at line 390 of file streamer.hpp.

Definition at line 402 of file streamer.hpp.

Definition at line 321 of file streamer.hpp.

Definition at line 335 of file streamer.hpp.

Mat streamerNode::colourMat [private]

Definition at line 363 of file streamer.hpp.

Definition at line 365 of file streamer.hpp.

Definition at line 299 of file streamer.hpp.

Definition at line 315 of file streamer.hpp.

int streamerNode::device_num [private]

Definition at line 368 of file streamer.hpp.

Definition at line 304 of file streamer.hpp.

Definition at line 289 of file streamer.hpp.

dynamic_reconfigure::Server<thermalvis::streamerConfig>::CallbackType streamerNode::f [private]

Definition at line 393 of file streamer.hpp.

int streamerNode::fileCount [private]

Definition at line 384 of file streamer.hpp.

int64_t streamerNode::firmwareTime [private]

Definition at line 313 of file streamer.hpp.

bool streamerNode::firstCall [private]

Definition at line 273 of file streamer.hpp.

bool streamerNode::firstFrame [private]

Definition at line 329 of file streamer.hpp.

Definition at line 318 of file streamer.hpp.

Mat streamerNode::frame [private]

Definition at line 366 of file streamer.hpp.

Definition at line 338 of file streamer.hpp.

double streamerNode::fusionFactor [private]

Definition at line 320 of file streamer.hpp.

Definition at line 370 of file streamer.hpp.

Definition at line 372 of file streamer.hpp.

Definition at line 300 of file streamer.hpp.

Definition at line 304 of file streamer.hpp.

Definition at line 301 of file streamer.hpp.

Definition at line 304 of file streamer.hpp.

vector<string> streamerNode::inputList [private]

Definition at line 383 of file streamer.hpp.

unsigned long streamerNode::internal_time [private]

Definition at line 311 of file streamer.hpp.

Definition at line 289 of file streamer.hpp.

Definition at line 379 of file streamer.hpp.

Definition at line 298 of file streamer.hpp.

Mat streamerNode::lastFrame [private]

Definition at line 327 of file streamer.hpp.

double streamerNode::lastLowerLimit [private]

Definition at line 323 of file streamer.hpp.

double streamerNode::lastMedian [private]

Definition at line 323 of file streamer.hpp.

Definition at line 296 of file streamer.hpp.

double streamerNode::lastUpperLimit [private]

Definition at line 323 of file streamer.hpp.

Definition at line 339 of file streamer.hpp.

int streamerNode::mainfd [private]

Definition at line 396 of file streamer.hpp.

Definition at line 389 of file streamer.hpp.

Mat streamerNode::map1 [private]

Definition at line 331 of file streamer.hpp.

Mat streamerNode::map2 [private]

Definition at line 331 of file streamer.hpp.

double streamerNode::maxVal [private]

Definition at line 325 of file streamer.hpp.

Definition at line 294 of file streamer.hpp.

double streamerNode::minVal [private]

Definition at line 325 of file streamer.hpp.

Definition at line 316 of file streamer.hpp.

Definition at line 316 of file streamer.hpp.

Definition at line 316 of file streamer.hpp.

Mat streamerNode::newImage [private]

Definition at line 366 of file streamer.hpp.

double streamerNode::newMedian [private]

Definition at line 323 of file streamer.hpp.

Definition at line 296 of file streamer.hpp.

char streamerNode::nodeName[256] [private]

Definition at line 271 of file streamer.hpp.

Definition at line 366 of file streamer.hpp.

ofstream streamerNode::ofs [private]

Definition at line 282 of file streamer.hpp.

ofstream streamerNode::ofs_call_log [private]

Definition at line 290 of file streamer.hpp.

Definition at line 290 of file streamer.hpp.

ofstream streamerNode::ofs_internal_log [private]

Definition at line 290 of file streamer.hpp.

ofstream streamerNode::ofs_retrieve_log [private]

Definition at line 290 of file streamer.hpp.

Definition at line 290 of file streamer.hpp.

ofstream streamerNode::ofs_write_log [private]

Definition at line 290 of file streamer.hpp.

double streamerNode::oldMaxDiff [private]

Definition at line 323 of file streamer.hpp.

unsigned long streamerNode::original_bx [private]

Definition at line 308 of file streamer.hpp.

unsigned long streamerNode::original_by [private]

Definition at line 308 of file streamer.hpp.

Definition at line 304 of file streamer.hpp.

Definition at line 287 of file streamer.hpp.

double streamerNode::pastMeans[256] [private]

Definition at line 286 of file streamer.hpp.

Definition at line 280 of file streamer.hpp.

Definition at line 364 of file streamer.hpp.

Definition at line 358 of file streamer.hpp.

Definition at line 352 of file streamer.hpp.

Definition at line 359 of file streamer.hpp.

Definition at line 353 of file streamer.hpp.

Definition at line 357 of file streamer.hpp.

Definition at line 351 of file streamer.hpp.

Definition at line 361 of file streamer.hpp.

Definition at line 355 of file streamer.hpp.

Definition at line 345 of file streamer.hpp.

Definition at line 289 of file streamer.hpp.

Mat streamerNode::rzMat [private]

Definition at line 333 of file streamer.hpp.

Definition at line 347 of file streamer.hpp.

char streamerNode::serialCommand[256] [private]

Definition at line 277 of file streamer.hpp.

dynamic_reconfigure::Server<thermalvis::streamerConfig> streamerNode::server [private]

Definition at line 392 of file streamer.hpp.

Definition at line 377 of file streamer.hpp.

double streamerNode::shiftDiff [private]

Definition at line 306 of file streamer.hpp.

Definition at line 364 of file streamer.hpp.

Mat streamerNode::testMat [private]

Definition at line 292 of file streamer.hpp.

Definition at line 289 of file streamer.hpp.

Definition at line 347 of file streamer.hpp.

Definition at line 366 of file streamer.hpp.

Definition at line 276 of file streamer.hpp.

Definition at line 275 of file streamer.hpp.

VideoWriter streamerNode::vid_writer [private]

Definition at line 341 of file streamer.hpp.

Definition at line 343 of file streamer.hpp.

bool streamerNode::videoValid [private]

Definition at line 388 of file streamer.hpp.

Definition at line 366 of file streamer.hpp.

int streamerNode::writeIndex [private]

Definition at line 337 of file streamer.hpp.

string streamerNode::writeLogFile [private]

Definition at line 289 of file streamer.hpp.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


thermalvis
Author(s): Stephen Vidas
autogenerated on Tue Mar 5 12:25:48 2013