$search
Manages the driver / streamer. More...
#include <streamer.hpp>
Manages the driver / streamer.
Definition at line 268 of file streamer.hpp.
streamerNode::streamerNode | ( | ros::NodeHandle & | nh, | |
streamerData | startupData | |||
) |
Definition at line 1672 of file streamer.cpp.
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.
Mat streamerNode::_16bitMat [private] |
Definition at line 363 of file streamer.hpp.
Mat streamerNode::_16bitMat_pub [private] |
Definition at line 365 of file streamer.hpp.
Mat streamerNode::_8bitMat [private] |
Definition at line 363 of file streamer.hpp.
Mat streamerNode::_8bitMat_pub [private] |
Definition at line 365 of file streamer.hpp.
bool streamerNode::alphaChanged [private] |
Definition at line 349 of file streamer.hpp.
int streamerNode::alternateCounter [private] |
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.
CvCapture* streamerNode::capture |
Definition at line 402 of file streamer.hpp.
bool streamerNode::centerPrincipalPoint [private] |
Definition at line 321 of file streamer.hpp.
cScheme streamerNode::colourMap [private] |
Definition at line 335 of file streamer.hpp.
Mat streamerNode::colourMat [private] |
Definition at line 363 of file streamer.hpp.
Mat streamerNode::colourMat_pub [private] |
Definition at line 365 of file streamer.hpp.
streamerData streamerNode::configData [private] |
Definition at line 299 of file streamer.hpp.
cv_bridge::CvImagePtr streamerNode::cv_ptr [private] |
Definition at line 315 of file streamer.hpp.
int streamerNode::device_num [private] |
Definition at line 368 of file streamer.hpp.
ros::Time streamerNode::dodgeTime [private] |
Definition at line 304 of file streamer.hpp.
string streamerNode::duplicatesLogFile [private] |
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.
bool streamerNode::firstServerCallbackProcessed [private] |
Definition at line 318 of file streamer.hpp.
Mat streamerNode::frame [private] |
Definition at line 366 of file streamer.hpp.
int streamerNode::frameCounter [private] |
Definition at line 338 of file streamer.hpp.
double streamerNode::fusionFactor [private] |
Definition at line 320 of file streamer.hpp.
camData_ streamerNode::globalCameraInfo [private] |
Definition at line 370 of file streamer.hpp.
Definition at line 372 of file streamer.hpp.
Definition at line 300 of file streamer.hpp.
ros::Time streamerNode::image_time [private] |
Definition at line 304 of file streamer.hpp.
ros::Subscriber streamerNode::info_sub [private] |
Definition at line 301 of file streamer.hpp.
ros::Time streamerNode::info_time [private] |
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.
string streamerNode::internalLogFile [private] |
Definition at line 289 of file streamer.hpp.
bool streamerNode::isActuallyGray [private] |
Definition at line 379 of file streamer.hpp.
image_transport::ImageTransport* streamerNode::it [private] |
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.
float streamerNode::lastThermistorReading [private] |
Definition at line 296 of file streamer.hpp.
double streamerNode::lastUpperLimit [private] |
Definition at line 323 of file streamer.hpp.
int streamerNode::lastWritten [private] |
Definition at line 339 of file streamer.hpp.
int streamerNode::mainfd [private] |
Definition at line 396 of file streamer.hpp.
streamerSource* streamerNode::mainVideoSource [private] |
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.
double streamerNode::medianPercentile [private] |
Definition at line 294 of file streamer.hpp.
double streamerNode::minVal [private] |
Definition at line 325 of file streamer.hpp.
sensor_msgs::Image streamerNode::msg_16bit [private] |
Definition at line 316 of file streamer.hpp.
sensor_msgs::Image streamerNode::msg_8bit [private] |
Definition at line 316 of file streamer.hpp.
sensor_msgs::Image streamerNode::msg_color [private] |
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.
float streamerNode::newThermistorReading [private] |
Definition at line 296 of file streamer.hpp.
char streamerNode::nodeName[256] [private] |
Definition at line 271 of file streamer.hpp.
Mat streamerNode::normalizedMat [private] |
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.
ofstream streamerNode::ofs_duplicates_log [private] |
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.
ofstream streamerNode::ofs_thermistor_log [private] |
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.
ros::Time streamerNode::original_time [private] |
Definition at line 304 of file streamer.hpp.
int streamerNode::pastMeanIndex [private] |
Definition at line 287 of file streamer.hpp.
double streamerNode::pastMeans[256] [private] |
Definition at line 286 of file streamer.hpp.
bool streamerNode::performingNuc [private] |
Definition at line 280 of file streamer.hpp.
Mat streamerNode::preFilteredMat [private] |
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.
bool streamerNode::readyToPublish [private] |
Definition at line 345 of file streamer.hpp.
string streamerNode::retrieveLogFile [private] |
Definition at line 289 of file streamer.hpp.
Mat streamerNode::rzMat [private] |
Definition at line 333 of file streamer.hpp.
ros::Timer streamerNode::serial_timer [private] |
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.
Mat streamerNode::smoothedMat [private] |
Definition at line 364 of file streamer.hpp.
Mat streamerNode::testMat [private] |
Definition at line 292 of file streamer.hpp.
string streamerNode::thermistorLogFile [private] |
Definition at line 289 of file streamer.hpp.
ros::Timer streamerNode::timer [private] |
Definition at line 347 of file streamer.hpp.
Mat streamerNode::undistorted [private] |
Definition at line 366 of file streamer.hpp.
bool streamerNode::updateDetectorMode [private] |
Definition at line 276 of file streamer.hpp.
bool streamerNode::updateNucInterval [private] |
Definition at line 275 of file streamer.hpp.
VideoWriter streamerNode::vid_writer [private] |
Definition at line 341 of file streamer.hpp.
bool streamerNode::videoInitialized [private] |
Definition at line 343 of file streamer.hpp.
bool streamerNode::videoValid [private] |
Definition at line 388 of file streamer.hpp.
Mat streamerNode::workingFrame [private] |
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.