Public Member Functions | Private Attributes
stereoDepthNode Class Reference

Manages the stereo procedure. More...

#include <depth.hpp>

List of all members.

Public Member Functions

void assignDepthCameraInfo ()
void handle_image_1 (const sensor_msgs::ImageConstPtr &msg_ptr, const sensor_msgs::CameraInfoConstPtr &info_msg)
void handle_image_2 (const sensor_msgs::ImageConstPtr &msg_ptr, const sensor_msgs::CameraInfoConstPtr &info_msg)
void publishMaps ()
void serverCallback (thermalvis::depthConfig &config, uint32_t level)
 stereoDepthNode (ros::NodeHandle &nh, stereoData startupData)
void timed_loop (const ros::TimerEvent &event)
void updateMaps ()
void updatePairs ()

Private Attributes

boost::shared_mutex _access
bool alphaChanged
Mat blurredImage
StereoBM bm
sensor_msgs::CameraInfo cam_info_1
sensor_msgs::CameraInfo cam_info_2
image_transport::CameraPublisher cam_pub_1
image_transport::CameraPublisher cam_pub_2
char cam_pub_name_1 [256]
char cam_pub_name_2 [256]
sensor_msgs::CameraInfo camera_info_1
sensor_msgs::CameraInfo camera_info_2
image_transport::CameraSubscriber camera_sub_1
image_transport::CameraSubscriber camera_sub_2
unsigned int checkIndex_1
unsigned int checkIndex_2
sensor_msgs::PointCloud2 colouredCloud
stereoData configData
cv_bridge::CvImagePtr cv_ptr_1
cv_bridge::CvImagePtr cv_ptr_2
struct timeval cycle_timer
sensor_msgs::CameraInfo debug_camera_info
image_transport::CameraPublisher depth_pub
char depth_pub_name [256]
Mat disp
Mat disp16
Mat disp8
stereo_msgs::DisparityImage disp_object
Mat disparityImage
ros::Publisher disparityPublisher
Mat dispFloat
Mat displayImage
Mat drawImage
double elapsedTime
Mat F
dynamic_reconfigure::Server
< thermalvis::depthConfig >
::CallbackType 
f
bool firstImProcessed_1
bool firstImProcessed_2
bool firstPair
bool firstPairProcessed
unsigned int frameCount
unsigned int frameCount_1
unsigned int frameCount_2
Mat grayImage
Mat grayImageBuffer_1 [MAXIMUM_FRAMES_TO_STORE]
Mat grayImageBuffer_2 [MAXIMUM_FRAMES_TO_STORE]
bool infoProcessed_1
bool infoProcessed_2
Mat lastImage_1
Mat lastImage_2
Mat map11
Mat map12
Mat map21
Mat map22
Mat mappedImage
sensor_msgs::Image msg_1
sensor_msgs::Image msg_2
Mat newImage
string nodeName
Mat normalizedMat
int numberOfDisparities
Mat olderImage_1
Mat olderImage_2
Mat P0
Mat P1
unsigned int pairsProcessed
ros::NodeHandle private_node_handle
Mat Q1
Mat Q2
Mat R0
Mat R1
Mat rawImageBuffer_1 [MAXIMUM_FRAMES_TO_STORE]
Mat rawImageBuffer_2 [MAXIMUM_FRAMES_TO_STORE]
Mat realImage
Rect roi1
Rect roi2
int SADWindowSize
dynamic_reconfigure::Server
< thermalvis::depthConfig > 
server
StereoSGBM sgbm
image_geometry::StereoCameraModel stereo_model
Mat t
ros::Time time_buffer_1 [MAXIMUM_FRAMES_TO_STORE]
ros::Time time_buffer_2 [MAXIMUM_FRAMES_TO_STORE]
ros::Timer timer
vector< unsigned int > validPairs [2]

Detailed Description

Manages the stereo procedure.

Definition at line 71 of file depth.hpp.


Constructor & Destructor Documentation

Definition at line 45 of file depth.cpp.


Member Function Documentation

void stereoDepthNode::handle_image_1 ( const sensor_msgs::ImageConstPtr &  msg_ptr,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
)

Definition at line 201 of file depth.cpp.

void stereoDepthNode::handle_image_2 ( const sensor_msgs::ImageConstPtr &  msg_ptr,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
)

Definition at line 383 of file depth.cpp.

Definition at line 861 of file depth.cpp.

void stereoDepthNode::serverCallback ( thermalvis::depthConfig &  config,
uint32_t  level 
)

Definition at line 986 of file depth.cpp.

Definition at line 651 of file depth.cpp.

Definition at line 963 of file depth.cpp.

Definition at line 559 of file depth.cpp.


Member Data Documentation

boost::shared_mutex stereoDepthNode::_access [private]

Definition at line 152 of file depth.hpp.

Definition at line 76 of file depth.hpp.

Definition at line 136 of file depth.hpp.

StereoBM stereoDepthNode::bm [private]

Definition at line 143 of file depth.hpp.

sensor_msgs::CameraInfo stereoDepthNode::cam_info_1 [private]

Definition at line 84 of file depth.hpp.

sensor_msgs::CameraInfo stereoDepthNode::cam_info_2 [private]

Definition at line 84 of file depth.hpp.

Definition at line 106 of file depth.hpp.

Definition at line 106 of file depth.hpp.

char stereoDepthNode::cam_pub_name_1[256] [private]

Definition at line 103 of file depth.hpp.

char stereoDepthNode::cam_pub_name_2[256] [private]

Definition at line 103 of file depth.hpp.

sensor_msgs::CameraInfo stereoDepthNode::camera_info_1 [private]

Definition at line 105 of file depth.hpp.

sensor_msgs::CameraInfo stereoDepthNode::camera_info_2 [private]

Definition at line 105 of file depth.hpp.

Definition at line 108 of file depth.hpp.

Definition at line 108 of file depth.hpp.

unsigned int stereoDepthNode::checkIndex_1 [private]

Definition at line 91 of file depth.hpp.

unsigned int stereoDepthNode::checkIndex_2 [private]

Definition at line 91 of file depth.hpp.

sensor_msgs::PointCloud2 stereoDepthNode::colouredCloud [private]

Definition at line 80 of file depth.hpp.

Definition at line 99 of file depth.hpp.

Definition at line 112 of file depth.hpp.

Definition at line 113 of file depth.hpp.

struct timeval stereoDepthNode::cycle_timer [private]

Definition at line 122 of file depth.hpp.

sensor_msgs::CameraInfo stereoDepthNode::debug_camera_info [private]

Definition at line 101 of file depth.hpp.

Definition at line 106 of file depth.hpp.

char stereoDepthNode::depth_pub_name[256] [private]

Definition at line 127 of file depth.hpp.

Mat stereoDepthNode::disp [private]

Definition at line 145 of file depth.hpp.

Mat stereoDepthNode::disp16 [private]

Definition at line 110 of file depth.hpp.

Mat stereoDepthNode::disp8 [private]

Definition at line 145 of file depth.hpp.

stereo_msgs::DisparityImage stereoDepthNode::disp_object [private]

Definition at line 79 of file depth.hpp.

Definition at line 145 of file depth.hpp.

Definition at line 97 of file depth.hpp.

Definition at line 145 of file depth.hpp.

Definition at line 132 of file depth.hpp.

Definition at line 132 of file depth.hpp.

double stereoDepthNode::elapsedTime [private]

Definition at line 123 of file depth.hpp.

Mat stereoDepthNode::F [private]

Definition at line 89 of file depth.hpp.

dynamic_reconfigure::Server<thermalvis::depthConfig>::CallbackType stereoDepthNode::f [private]

Definition at line 155 of file depth.hpp.

Definition at line 141 of file depth.hpp.

Definition at line 141 of file depth.hpp.

Definition at line 150 of file depth.hpp.

Definition at line 141 of file depth.hpp.

unsigned int stereoDepthNode::frameCount [private]

Definition at line 125 of file depth.hpp.

unsigned int stereoDepthNode::frameCount_1 [private]

Definition at line 125 of file depth.hpp.

unsigned int stereoDepthNode::frameCount_2 [private]

Definition at line 125 of file depth.hpp.

Definition at line 116 of file depth.hpp.

Definition at line 134 of file depth.hpp.

Definition at line 134 of file depth.hpp.

Definition at line 138 of file depth.hpp.

Definition at line 139 of file depth.hpp.

Definition at line 116 of file depth.hpp.

Definition at line 116 of file depth.hpp.

Mat stereoDepthNode::map11 [private]

Definition at line 118 of file depth.hpp.

Mat stereoDepthNode::map12 [private]

Definition at line 118 of file depth.hpp.

Mat stereoDepthNode::map21 [private]

Definition at line 118 of file depth.hpp.

Mat stereoDepthNode::map22 [private]

Definition at line 118 of file depth.hpp.

Definition at line 116 of file depth.hpp.

sensor_msgs::Image stereoDepthNode::msg_1 [private]

Definition at line 104 of file depth.hpp.

sensor_msgs::Image stereoDepthNode::msg_2 [private]

Definition at line 104 of file depth.hpp.

Definition at line 116 of file depth.hpp.

string stereoDepthNode::nodeName [private]

Definition at line 130 of file depth.hpp.

Definition at line 116 of file depth.hpp.

Definition at line 148 of file depth.hpp.

Definition at line 116 of file depth.hpp.

Definition at line 116 of file depth.hpp.

Mat stereoDepthNode::P0 [private]

Definition at line 88 of file depth.hpp.

Mat stereoDepthNode::P1 [private]

Definition at line 88 of file depth.hpp.

unsigned int stereoDepthNode::pairsProcessed [private]

Definition at line 95 of file depth.hpp.

Definition at line 128 of file depth.hpp.

Mat stereoDepthNode::Q1 [private]

Definition at line 89 of file depth.hpp.

Mat stereoDepthNode::Q2 [private]

Definition at line 89 of file depth.hpp.

Mat stereoDepthNode::R0 [private]

Definition at line 87 of file depth.hpp.

Mat stereoDepthNode::R1 [private]

Definition at line 87 of file depth.hpp.

Definition at line 115 of file depth.hpp.

Definition at line 115 of file depth.hpp.

Definition at line 116 of file depth.hpp.

Rect stereoDepthNode::roi1 [private]

Definition at line 120 of file depth.hpp.

Rect stereoDepthNode::roi2 [private]

Definition at line 120 of file depth.hpp.

Definition at line 147 of file depth.hpp.

dynamic_reconfigure::Server<thermalvis::depthConfig> stereoDepthNode::server [private]

Definition at line 154 of file depth.hpp.

StereoSGBM stereoDepthNode::sgbm [private]

Definition at line 144 of file depth.hpp.

Definition at line 82 of file depth.hpp.

Mat stereoDepthNode::t [private]

Definition at line 86 of file depth.hpp.

Definition at line 93 of file depth.hpp.

Definition at line 93 of file depth.hpp.

Definition at line 74 of file depth.hpp.

vector<unsigned int> stereoDepthNode::validPairs[2] [private]

Definition at line 94 of file depth.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