Public Member Functions | Public Attributes | Private Attributes
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 ()
bool getNucSettingsReading (int &delay, double &diff)
void getRectification ()
float getThermistorReading ()
cv::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 handle_nuc_instruction (const std_msgs::Float32::ConstPtr &nuc_msg)
void initializeMessages ()
bool isVideoValid ()
void markCurrentFrameAsDuplicate ()
int open_port ()
void overwriteCameraDims ()
bool performNuc ()
void prepareForTermination ()
bool processFolder ()
bool processImage ()
void publishTopics ()
void refreshCameraAdvertisements ()
void releaseDevice ()
bool runBag ()
bool runDevice ()
bool runLoad ()
bool runRead ()
bool sendSerialCommand (char *command, int max_attempts=1)
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)
double smoothThermistorReading ()
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

cv::Mat _16bitMat
cv::Mat _16bitMat_pub
cv::Mat _8bitMat
cv::Mat _8bitMat_pub
bool alphaChanged
int alternateCounter
bool altStatus
string callLogFile
sensor_msgs::CameraInfo camera_info
image_transport::CameraSubscriber camera_sub
bool canRadiometricallyCorrect
cv::VideoCapture cap
bool centerPrincipalPoint
cScheme colourMap
cv::Mat colourMat
cv::Mat colourMat_pub
streamerData configData
bool currentDesiredNucProtectionMode
bool currentNucProtectionMode
cv_bridge::CvImagePtr cv_ptr
bool deviceCreated
ros::Time dodgeTime
string duplicatesLogFile
dynamic_reconfigure::Server
< thermalvis::streamerConfig >
::CallbackType 
f
int fileCount
int64_t firmwareTime
bool firstCall
bool firstFrame
bool firstServerCallbackProcessed
cv::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
double lastDisplayed
ros::Time lastFlagReceived
cv::Mat lastFrame
bool lastIsDuplicate
double lastLowerLimit
double lastMaxDisplayTemp
double lastMedian
double lastMinDisplayTemp
ros::Time lastNucPerformed_at_the_earliest
float lastThermistorReading
double lastUpperLimit
int lastWritten
int mainfd
streamerSourcemainVideoSource
cv::Mat map1
cv::Mat map2
double maxVal
double medianPercentile
double minVal
sensor_msgs::Image msg_16bit
sensor_msgs::Image msg_8bit
sensor_msgs::Image msg_color
cv::Mat newImage
double newMedian
float newThermistorReading
char nodeName [256]
cv::Mat normalizedMat
ros::Subscriber nuc_management_sub
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
sensor_msgs::CameraInfo original_camera_info
ros::Time original_time
float originalInternalTime
int pastMeanIndex
double pastMeans [256]
bool performingNuc
cv::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
rScheme radMapper
bool readyToPublish
unsigned int recordedThermistorReadings
string retrieveLogFile
cv::Mat rzMat
cv::Mat scaled16Mat
ros::Timer serial_timer
dynamic_reconfigure::Server
< thermalvis::streamerConfig > 
server
ros::ServiceServer set_camera_info
bool settingsDisabled
double shiftDiff
cv::Mat smoothedMat
cv::Mat temperatureMat
cv::Mat testMat
double thermistorBuffer [MAX_THERMISTOR_READINGS_TO_STORE][2]
string thermistorLogFile
ros::Timer timer
cv::Mat undistorted
bool updateDetectorMode
bool updateNucInterval
bool updateUSBMode
cv::VideoWriter vid_writer
bool videoInitialized
bool videoValid
bool wantsToDisableNuc
cv::Mat workingFrame
int writeIndex
string writeLogFile

Detailed Description

Manages the driver / streamer.

Definition at line 301 of file streamer.hpp.


Constructor & Destructor Documentation

Definition at line 2146 of file streamer.cpp.


Member Function Documentation

void streamerNode::acceptImage ( void *  ptr)

Definition at line 791 of file streamer.cpp.

Definition at line 2714 of file streamer.cpp.

Definition at line 476 of file streamer.cpp.

Definition at line 2126 of file streamer.cpp.

Definition at line 3922 of file streamer.cpp.

Definition at line 3325 of file streamer.cpp.

bool streamerNode::getNucSettingsReading ( int &  delay,
double &  diff 
)

Definition at line 4360 of file streamer.cpp.

Definition at line 2504 of file streamer.cpp.

Definition at line 4394 of file streamer.cpp.

cv::VideoCapture * streamerNode::getVideoCapture ( )

Definition at line 3329 of file streamer.cpp.

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

Definition at line 2667 of file streamer.cpp.

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

Definition at line 2763 of file streamer.cpp.

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

Definition at line 2543 of file streamer.cpp.

void streamerNode::handle_nuc_instruction ( const std_msgs::Float32::ConstPtr &  nuc_msg)

Definition at line 2527 of file streamer.cpp.

Definition at line 1298 of file streamer.cpp.

Definition at line 3309 of file streamer.cpp.

Definition at line 386 of file streamer.cpp.

Definition at line 3861 of file streamer.cpp.

Definition at line 2139 of file streamer.cpp.

Definition at line 1616 of file streamer.cpp.

Definition at line 67 of file streamer.cpp.

Definition at line 348 of file streamer.cpp.

Definition at line 839 of file streamer.cpp.

Definition at line 1343 of file streamer.cpp.

Definition at line 2582 of file streamer.cpp.

Definition at line 168 of file streamer.cpp.

Definition at line 324 of file streamer.cpp.

Definition at line 187 of file streamer.cpp.

Definition at line 255 of file streamer.cpp.

Definition at line 278 of file streamer.cpp.

bool streamerNode::sendSerialCommand ( char *  command,
int  max_attempts = 1 
)

Definition at line 1916 of file streamer.cpp.

Definition at line 1627 of file streamer.cpp.

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

Definition at line 3374 of file streamer.cpp.

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

Definition at line 642 of file streamer.cpp.

Definition at line 119 of file streamer.cpp.

void streamerNode::setValidity ( bool  val)

Definition at line 3320 of file streamer.cpp.

Definition at line 4313 of file streamer.cpp.

bool streamerNode::streamCallback ( bool  capture = true)

Definition at line 659 of file streamer.cpp.

Definition at line 1963 of file streamer.cpp.

Definition at line 392 of file streamer.cpp.

Definition at line 624 of file streamer.cpp.

Definition at line 3333 of file streamer.cpp.

Definition at line 1530 of file streamer.cpp.


Member Data Documentation

cv::Mat streamerNode::_16bitMat [private]

Definition at line 418 of file streamer.hpp.

cv::Mat streamerNode::_16bitMat_pub [private]

Definition at line 420 of file streamer.hpp.

cv::Mat streamerNode::_8bitMat [private]

Definition at line 418 of file streamer.hpp.

cv::Mat streamerNode::_8bitMat_pub [private]

Definition at line 420 of file streamer.hpp.

Definition at line 404 of file streamer.hpp.

Definition at line 334 of file streamer.hpp.

bool streamerNode::altStatus [private]

Definition at line 329 of file streamer.hpp.

string streamerNode::callLogFile [private]

Definition at line 339 of file streamer.hpp.

sensor_msgs::CameraInfo streamerNode::camera_info [private]

Definition at line 430 of file streamer.hpp.

Definition at line 352 of file streamer.hpp.

Definition at line 318 of file streamer.hpp.

cv::VideoCapture streamerNode::cap [private]

Definition at line 445 of file streamer.hpp.

Definition at line 457 of file streamer.hpp.

Definition at line 376 of file streamer.hpp.

Definition at line 390 of file streamer.hpp.

cv::Mat streamerNode::colourMat [private]

Definition at line 418 of file streamer.hpp.

cv::Mat streamerNode::colourMat_pub [private]

Definition at line 420 of file streamer.hpp.

Definition at line 349 of file streamer.hpp.

Definition at line 308 of file streamer.hpp.

Definition at line 308 of file streamer.hpp.

Definition at line 370 of file streamer.hpp.

Definition at line 307 of file streamer.hpp.

Definition at line 356 of file streamer.hpp.

Definition at line 339 of file streamer.hpp.

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

Definition at line 448 of file streamer.hpp.

int streamerNode::fileCount [private]

Definition at line 439 of file streamer.hpp.

int64_t streamerNode::firmwareTime [private]

Definition at line 368 of file streamer.hpp.

bool streamerNode::firstCall [private]

Definition at line 311 of file streamer.hpp.

bool streamerNode::firstFrame [private]

Definition at line 384 of file streamer.hpp.

Definition at line 373 of file streamer.hpp.

cv::Mat streamerNode::frame [private]

Definition at line 421 of file streamer.hpp.

Definition at line 393 of file streamer.hpp.

double streamerNode::fusionFactor [private]

Definition at line 375 of file streamer.hpp.

Definition at line 425 of file streamer.hpp.

Definition at line 427 of file streamer.hpp.

Definition at line 350 of file streamer.hpp.

Definition at line 356 of file streamer.hpp.

Definition at line 351 of file streamer.hpp.

Definition at line 356 of file streamer.hpp.

vector<string> streamerNode::inputList [private]

Definition at line 438 of file streamer.hpp.

unsigned long streamerNode::internal_time [private]

Definition at line 366 of file streamer.hpp.

Definition at line 339 of file streamer.hpp.

Definition at line 434 of file streamer.hpp.

Definition at line 348 of file streamer.hpp.

double streamerNode::lastDisplayed [private]

Definition at line 320 of file streamer.hpp.

Definition at line 356 of file streamer.hpp.

cv::Mat streamerNode::lastFrame [private]

Definition at line 382 of file streamer.hpp.

Definition at line 324 of file streamer.hpp.

double streamerNode::lastLowerLimit [private]

Definition at line 378 of file streamer.hpp.

Definition at line 306 of file streamer.hpp.

double streamerNode::lastMedian [private]

Definition at line 378 of file streamer.hpp.

Definition at line 306 of file streamer.hpp.

Definition at line 356 of file streamer.hpp.

Definition at line 346 of file streamer.hpp.

double streamerNode::lastUpperLimit [private]

Definition at line 378 of file streamer.hpp.

Definition at line 394 of file streamer.hpp.

int streamerNode::mainfd [private]

Definition at line 451 of file streamer.hpp.

Definition at line 444 of file streamer.hpp.

cv::Mat streamerNode::map1 [private]

Definition at line 386 of file streamer.hpp.

cv::Mat streamerNode::map2 [private]

Definition at line 386 of file streamer.hpp.

double streamerNode::maxVal [private]

Definition at line 380 of file streamer.hpp.

Definition at line 344 of file streamer.hpp.

double streamerNode::minVal [private]

Definition at line 380 of file streamer.hpp.

sensor_msgs::Image streamerNode::msg_16bit [private]

Definition at line 371 of file streamer.hpp.

sensor_msgs::Image streamerNode::msg_8bit [private]

Definition at line 371 of file streamer.hpp.

sensor_msgs::Image streamerNode::msg_color [private]

Definition at line 371 of file streamer.hpp.

cv::Mat streamerNode::newImage [private]

Definition at line 421 of file streamer.hpp.

double streamerNode::newMedian [private]

Definition at line 378 of file streamer.hpp.

Definition at line 346 of file streamer.hpp.

char streamerNode::nodeName[256] [private]

Definition at line 304 of file streamer.hpp.

cv::Mat streamerNode::normalizedMat [private]

Definition at line 421 of file streamer.hpp.

Definition at line 354 of file streamer.hpp.

ofstream streamerNode::ofs [private]

Definition at line 332 of file streamer.hpp.

ofstream streamerNode::ofs_call_log [private]

Definition at line 340 of file streamer.hpp.

Definition at line 340 of file streamer.hpp.

ofstream streamerNode::ofs_internal_log [private]

Definition at line 340 of file streamer.hpp.

ofstream streamerNode::ofs_retrieve_log [private]

Definition at line 340 of file streamer.hpp.

Definition at line 340 of file streamer.hpp.

ofstream streamerNode::ofs_write_log [private]

Definition at line 340 of file streamer.hpp.

double streamerNode::oldMaxDiff [private]

Definition at line 378 of file streamer.hpp.

unsigned long streamerNode::original_bx [private]

Definition at line 363 of file streamer.hpp.

unsigned long streamerNode::original_by [private]

Definition at line 363 of file streamer.hpp.

sensor_msgs::CameraInfo streamerNode::original_camera_info [private]

Definition at line 430 of file streamer.hpp.

Definition at line 356 of file streamer.hpp.

Definition at line 357 of file streamer.hpp.

Definition at line 337 of file streamer.hpp.

double streamerNode::pastMeans[256] [private]

Definition at line 336 of file streamer.hpp.

Definition at line 330 of file streamer.hpp.

cv::Mat streamerNode::preFilteredMat [private]

Definition at line 419 of file streamer.hpp.

Definition at line 413 of file streamer.hpp.

Definition at line 407 of file streamer.hpp.

Definition at line 414 of file streamer.hpp.

Definition at line 408 of file streamer.hpp.

Definition at line 412 of file streamer.hpp.

Definition at line 406 of file streamer.hpp.

Definition at line 416 of file streamer.hpp.

Definition at line 410 of file streamer.hpp.

Definition at line 322 of file streamer.hpp.

Definition at line 400 of file streamer.hpp.

Definition at line 315 of file streamer.hpp.

Definition at line 339 of file streamer.hpp.

cv::Mat streamerNode::rzMat [private]

Definition at line 388 of file streamer.hpp.

cv::Mat streamerNode::scaled16Mat [private]

Definition at line 419 of file streamer.hpp.

Definition at line 402 of file streamer.hpp.

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

Definition at line 447 of file streamer.hpp.

Definition at line 432 of file streamer.hpp.

Definition at line 313 of file streamer.hpp.

double streamerNode::shiftDiff [private]

Definition at line 361 of file streamer.hpp.

cv::Mat streamerNode::smoothedMat [private]

Definition at line 419 of file streamer.hpp.

cv::Mat streamerNode::temperatureMat [private]

Definition at line 342 of file streamer.hpp.

cv::Mat streamerNode::testMat [private]

Definition at line 342 of file streamer.hpp.

Definition at line 316 of file streamer.hpp.

Definition at line 339 of file streamer.hpp.

Definition at line 402 of file streamer.hpp.

cv::Mat streamerNode::undistorted [private]

Definition at line 421 of file streamer.hpp.

Definition at line 327 of file streamer.hpp.

Definition at line 326 of file streamer.hpp.

Definition at line 327 of file streamer.hpp.

cv::VideoWriter streamerNode::vid_writer [private]

Definition at line 396 of file streamer.hpp.

Definition at line 398 of file streamer.hpp.

bool streamerNode::videoValid [private]

Definition at line 443 of file streamer.hpp.

Definition at line 309 of file streamer.hpp.

cv::Mat streamerNode::workingFrame [private]

Definition at line 421 of file streamer.hpp.

int streamerNode::writeIndex [private]

Definition at line 392 of file streamer.hpp.

string streamerNode::writeLogFile [private]

Definition at line 339 of file streamer.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