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

Manages the calibration procedures. More...

#include <calibrator.hpp>

List of all members.

Public Member Functions

void assignDebugCameraInfo ()
void assignIntrinsics ()
 calibratorNode (ros::NodeHandle &nh, calibratorData startupData)
void create_virtual_pairs ()
void determineValidPairs ()
void evaluateFrames ()
bool findPattern (const Mat &im, vector< Point2f > &dst, Mat &prev, const int cameraNumber)
void getAverageTime ()
void getFrameTrackingTime ()
void handle_image (const sensor_msgs::ImageConstPtr &msg_ptr, const sensor_msgs::CameraInfoConstPtr &info_msg, const unsigned int camera_index=0)
void imageCallback (const sensor_msgs::ImageConstPtr &msg)
bool isStillCollecting ()
bool isVerifying ()
void performExtrinsicCalibration ()
void performIntrinsicCalibration ()
void prepareExtrinsicPatternSubsets ()
void prepareForTermination ()
void preparePatternSubsets ()
void publishRectified (const ros::TimerEvent &event)
void publishUndistorted (const ros::TimerEvent &event)
void serverCallback (thermalvis::calibratorConfig &config, uint32_t level)
void set_ready_for_output ()
void startRectificationPublishing ()
void startUndistortionPublishing ()
void timerCallback (const ros::TimerEvent &e)
void updateIntrinsicMap (unsigned int idx)
void updateMap ()
void updatePairs ()
bool wantsExtrinsics ()
bool wantsIntrinsics ()
bool wantsToRectify ()
bool wantsToUndistort ()
void writeResults ()

Private Member Functions

void preprocessImage (Mat src, Mat &dst, double a, double b, bool normaliz, bool negative)

Private Attributes

boost::shared_mutex _access
double alpha
bool alphaChanged
double avgTime
int botValidHeight
image_transport::CameraSubscriber camera_sub [MAX_ALLOWABLE_CAMS]
Mat cameraMatrices [MAX_ALLOWABLE_CAMS]
vector< vector< Point2f > > candidateSets [MAX_ALLOWABLE_CAMS]
unsigned int checkIndex [MAX_ALLOWABLE_CAMS]
calibratorData configData
vector< Point2f > cornerSet [MAX_ALLOWABLE_CAMS]
vector< Point2f > cornerSets [MAX_ALLOWABLE_CAMS]
cv_bridge::CvImagePtr cv_ptr [MAX_ALLOWABLE_CAMS]
struct timeval cycle_timer
sensor_msgs::CameraInfo debug_camera_info [MAX_ALLOWABLE_CAMS]
image_transport::CameraPublisher debug_pub [MAX_ALLOWABLE_CAMS]
char debug_pub_name [MAX_ALLOWABLE_CAMS][256]
Mat default_R
vector< Mat > displayImages [MAX_ALLOWABLE_CAMS]
Mat distCoeffVecs [MAX_ALLOWABLE_CAMS]
bool doVerify
vector< unsigned char > duplicateFlags [MAX_ALLOWABLE_CAMS]
Mat E [MAX_ALLOWABLE_CAMS]
struct timeval vacant_timer elapsed_timer
double elapsedInputTime
double elapsedTime
double elapsedTrackingTime
double extendedExtrinsicReprojectionError
double extendedReprojectionError_intrinsics [MAX_ALLOWABLE_CAMS]
vector< vector< Point2f > > extrinsicCandidateSets [MAX_ALLOWABLE_CAMS]
vector< vector< Point2f > > extrinsicsPointSets [MAX_ALLOWABLE_CAMS]
vector< vector< Point2f > > extrinsicTestingSets [MAX_ALLOWABLE_CAMS]
Mat F [MAX_ALLOWABLE_CAMS]
dynamic_reconfigure::Server
< thermalvis::calibratorConfig >
::CallbackType 
f
unsigned int frameCount [MAX_ALLOWABLE_CAMS]
vector< unsigned int > frameCounts [MAX_ALLOWABLE_CAMS]
double frameTrackingTime
Mat grayMat [MAX_ALLOWABLE_CAMS]
Size imSize [MAX_ALLOWABLE_CAMS]
bool infoProcessed [MAX_ALLOWABLE_CAMS]
Mat lastImage
Mat lastMat [MAX_ALLOWABLE_CAMS]
vector< Point2f > leftLinePoints
int leftValid [MAX_ALLOWABLE_CAMS]
Mat map1 [MAX_ALLOWABLE_CAMS]
Mat map2 [MAX_ALLOWABLE_CAMS]
sensor_msgs::Image msg_debug [MAX_ALLOWABLE_CAMS]
Mat newCamMat [MAX_ALLOWABLE_CAMS]
Mat newImage
vector< Point2f > newRecBounds
char nodeName [256]
Mat P_ [MAX_ALLOWABLE_CAMS]
vector< unsigned int > patternIndices [MAX_ALLOWABLE_CAMS]
vector< ros::TimepatternTimestamps [MAX_ALLOWABLE_CAMS]
vector< vector< Point2f > > pointSets [MAX_ALLOWABLE_CAMS]
Mat prevMat [MAX_ALLOWABLE_CAMS]
ros::NodeHandle private_node_handle
unsigned int publishCount
Mat Q [MAX_ALLOWABLE_CAMS]
Mat R [MAX_ALLOWABLE_CAMS]
Mat R2 [MAX_ALLOWABLE_CAMS]
Mat R_ [MAX_ALLOWABLE_CAMS]
bool readyForOutput
vector< Point2f > rectangleBounds
Mat rectCamMat [MAX_ALLOWABLE_CAMS]
unsigned int rectificationCount
ros::NodeHandleref
double reprojectionError_intrinsics [MAX_ALLOWABLE_CAMS]
vector< Point2f > rightLinePoints
int rightValid [MAX_ALLOWABLE_CAMS]
Rect roi [MAX_ALLOWABLE_CAMS]
cv::vector< Point3f > row
Mat Rv [MAX_ALLOWABLE_CAMS]
dynamic_reconfigure::Server
< thermalvis::calibratorConfig > 
server
double stereoError
bool stillCollecting
vector< int > subselectedTags_intrinsics [MAX_ALLOWABLE_CAMS]
Mat T [MAX_ALLOWABLE_CAMS]
Mat T2 [MAX_ALLOWABLE_CAMS]
vector< vector< Point2f > > testingSets [MAX_ALLOWABLE_CAMS]
ros::Timer timer
vector< ros::Timetimes [MAX_ALLOWABLE_CAMS]
string topic [MAX_ALLOWABLE_CAMS]
int topValidHeight
unsigned int totalFrameCount [2]
struct timeval tracking_timer
unsigned int undistortionCount
double vacantInputTime
vector< unsigned int > validPairs [MAX_ALLOWABLE_CAMS]
unsigned int validSets

Detailed Description

Manages the calibration procedures.

Definition at line 136 of file calibrator.hpp.


Constructor & Destructor Documentation

Definition at line 2167 of file calibrator.cpp.


Member Function Documentation

Definition at line 1282 of file calibrator.cpp.

Definition at line 357 of file calibrator.cpp.

Definition at line 172 of file calibrator.cpp.

Definition at line 1403 of file calibrator.cpp.

Definition at line 1503 of file calibrator.cpp.

bool calibratorNode::findPattern ( const Mat &  im,
vector< Point2f > &  dst,
Mat &  prev,
const int  cameraNumber = -1 
)

Definition at line 1300 of file calibrator.cpp.

Definition at line 556 of file calibrator.cpp.

Definition at line 569 of file calibrator.cpp.

void calibratorNode::handle_image ( const sensor_msgs::ImageConstPtr &  msg_ptr,
const sensor_msgs::CameraInfoConstPtr &  info_msg,
const unsigned int  camera_index = 0 
)

Definition at line 1924 of file calibrator.cpp.

void calibratorNode::imageCallback ( const sensor_msgs::ImageConstPtr &  msg)

Definition at line 1289 of file calibrator.cpp.

Definition at line 1295 of file calibrator.cpp.

Definition at line 813 of file calibrator.cpp.

Definition at line 1014 of file calibrator.cpp.

Definition at line 110 of file calibrator.cpp.

Definition at line 346 of file calibrator.cpp.

Definition at line 282 of file calibrator.cpp.

void calibratorNode::preprocessImage ( Mat  src,
Mat &  dst,
double  a = 1.0,
double  b = 0.0,
bool  normaliz = false,
bool  negative = false 
) [private]

Definition at line 1649 of file calibrator.cpp.

Definition at line 774 of file calibrator.cpp.

Definition at line 706 of file calibrator.cpp.

void calibratorNode::serverCallback ( thermalvis::calibratorConfig &  config,
uint32_t  level 
)

Definition at line 2299 of file calibrator.cpp.

Definition at line 2368 of file calibrator.cpp.

Definition at line 603 of file calibrator.cpp.

Definition at line 584 of file calibrator.cpp.

Definition at line 2272 of file calibrator.cpp.

void calibratorNode::updateIntrinsicMap ( unsigned int  idx)

Definition at line 1259 of file calibrator.cpp.

Definition at line 1716 of file calibrator.cpp.

Definition at line 378 of file calibrator.cpp.

Definition at line 366 of file calibrator.cpp.

Definition at line 552 of file calibrator.cpp.

Definition at line 548 of file calibrator.cpp.

Definition at line 386 of file calibrator.cpp.


Member Data Documentation

boost::shared_mutex calibratorNode::_access [private]

Definition at line 250 of file calibrator.hpp.

double calibratorNode::alpha [private]

Definition at line 173 of file calibrator.hpp.

Definition at line 210 of file calibrator.hpp.

double calibratorNode::avgTime [private]

Definition at line 145 of file calibrator.hpp.

Definition at line 157 of file calibrator.hpp.

Definition at line 218 of file calibrator.hpp.

Definition at line 177 of file calibrator.hpp.

vector<vector<Point2f> > calibratorNode::candidateSets[MAX_ALLOWABLE_CAMS] [private]

Definition at line 240 of file calibrator.hpp.

Definition at line 235 of file calibrator.hpp.

Definition at line 212 of file calibrator.hpp.

vector<Point2f> calibratorNode::cornerSet[MAX_ALLOWABLE_CAMS] [private]

Definition at line 257 of file calibrator.hpp.

vector<Point2f> calibratorNode::cornerSets[MAX_ALLOWABLE_CAMS] [private]

Definition at line 245 of file calibrator.hpp.

Definition at line 223 of file calibrator.hpp.

struct timeval calibratorNode::cycle_timer [private]

Definition at line 143 of file calibrator.hpp.

sensor_msgs::CameraInfo calibratorNode::debug_camera_info[MAX_ALLOWABLE_CAMS] [private]

Definition at line 214 of file calibrator.hpp.

Definition at line 216 of file calibrator.hpp.

Definition at line 225 of file calibrator.hpp.

Definition at line 175 of file calibrator.hpp.

Definition at line 162 of file calibrator.hpp.

Definition at line 178 of file calibrator.hpp.

bool calibratorNode::doVerify [private]

Definition at line 247 of file calibrator.hpp.

vector<unsigned char> calibratorNode::duplicateFlags[MAX_ALLOWABLE_CAMS] [private]

Definition at line 191 of file calibrator.hpp.

Definition at line 203 of file calibrator.hpp.

struct timeval vacant_timer calibratorNode::elapsed_timer [private]

Definition at line 153 of file calibrator.hpp.

Definition at line 154 of file calibrator.hpp.

double calibratorNode::elapsedTime [private]

Definition at line 144 of file calibrator.hpp.

Definition at line 148 of file calibrator.hpp.

Definition at line 208 of file calibrator.hpp.

Definition at line 189 of file calibrator.hpp.

vector<vector<Point2f> > calibratorNode::extrinsicCandidateSets[MAX_ALLOWABLE_CAMS] [private]

Definition at line 241 of file calibrator.hpp.

vector<vector<Point2f> > calibratorNode::extrinsicsPointSets[MAX_ALLOWABLE_CAMS] [private]

Definition at line 241 of file calibrator.hpp.

vector<vector<Point2f> > calibratorNode::extrinsicTestingSets[MAX_ALLOWABLE_CAMS] [private]

Definition at line 241 of file calibrator.hpp.

Definition at line 203 of file calibrator.hpp.

dynamic_reconfigure::Server<thermalvis::calibratorConfig>::CallbackType calibratorNode::f [private]

Definition at line 255 of file calibrator.hpp.

Definition at line 236 of file calibrator.hpp.

vector<unsigned int> calibratorNode::frameCounts[MAX_ALLOWABLE_CAMS] [private]

Definition at line 246 of file calibrator.hpp.

Definition at line 149 of file calibrator.hpp.

Definition at line 141 of file calibrator.hpp.

Definition at line 185 of file calibrator.hpp.

Definition at line 170 of file calibrator.hpp.

Definition at line 233 of file calibrator.hpp.

Definition at line 244 of file calibrator.hpp.

vector<Point2f> calibratorNode::leftLinePoints [private]

Definition at line 183 of file calibrator.hpp.

Definition at line 157 of file calibrator.hpp.

Definition at line 156 of file calibrator.hpp.

Definition at line 156 of file calibrator.hpp.

sensor_msgs::Image calibratorNode::msg_debug[MAX_ALLOWABLE_CAMS] [private]

Definition at line 227 of file calibrator.hpp.

Definition at line 186 of file calibrator.hpp.

Mat calibratorNode::newImage [private]

Definition at line 233 of file calibrator.hpp.

vector<Point2f> calibratorNode::newRecBounds [private]

Definition at line 181 of file calibrator.hpp.

char calibratorNode::nodeName[256] [private]

Definition at line 231 of file calibrator.hpp.

Definition at line 202 of file calibrator.hpp.

vector<unsigned int> calibratorNode::patternIndices[MAX_ALLOWABLE_CAMS] [private]

Definition at line 161 of file calibrator.hpp.

Definition at line 193 of file calibrator.hpp.

vector<vector<Point2f> > calibratorNode::pointSets[MAX_ALLOWABLE_CAMS] [private]

Definition at line 240 of file calibrator.hpp.

Definition at line 141 of file calibrator.hpp.

Definition at line 229 of file calibrator.hpp.

unsigned int calibratorNode::publishCount [private]

Definition at line 199 of file calibrator.hpp.

Definition at line 203 of file calibrator.hpp.

Definition at line 204 of file calibrator.hpp.

Definition at line 205 of file calibrator.hpp.

Definition at line 202 of file calibrator.hpp.

Definition at line 252 of file calibrator.hpp.

vector<Point2f> calibratorNode::rectangleBounds [private]

Definition at line 181 of file calibrator.hpp.

Definition at line 182 of file calibrator.hpp.

unsigned int calibratorNode::rectificationCount [private]

Definition at line 236 of file calibrator.hpp.

Definition at line 139 of file calibrator.hpp.

Definition at line 188 of file calibrator.hpp.

vector<Point2f> calibratorNode::rightLinePoints [private]

Definition at line 183 of file calibrator.hpp.

Definition at line 157 of file calibrator.hpp.

Definition at line 180 of file calibrator.hpp.

cv::vector<Point3f> calibratorNode::row [private]

Definition at line 238 of file calibrator.hpp.

Definition at line 204 of file calibrator.hpp.

dynamic_reconfigure::Server<thermalvis::calibratorConfig> calibratorNode::server [private]

Definition at line 254 of file calibrator.hpp.

double calibratorNode::stereoError [private]

Definition at line 207 of file calibrator.hpp.

Definition at line 171 of file calibrator.hpp.

Definition at line 195 of file calibrator.hpp.

Definition at line 204 of file calibrator.hpp.

Definition at line 205 of file calibrator.hpp.

vector<vector<Point2f> > calibratorNode::testingSets[MAX_ALLOWABLE_CAMS] [private]

Definition at line 240 of file calibrator.hpp.

Definition at line 159 of file calibrator.hpp.

Definition at line 164 of file calibrator.hpp.

Definition at line 197 of file calibrator.hpp.

Definition at line 157 of file calibrator.hpp.

unsigned int calibratorNode::totalFrameCount[2] [private]

Definition at line 236 of file calibrator.hpp.

struct timeval calibratorNode::tracking_timer [private]

Definition at line 147 of file calibrator.hpp.

unsigned int calibratorNode::undistortionCount [private]

Definition at line 236 of file calibrator.hpp.

Definition at line 154 of file calibrator.hpp.

vector<unsigned int> calibratorNode::validPairs[MAX_ALLOWABLE_CAMS] [private]

Definition at line 166 of file calibrator.hpp.

unsigned int calibratorNode::validSets [private]

Definition at line 151 of file calibrator.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