Public Member Functions | Private Attributes
videoslamNode Class Reference

Manages the ODOMETRY procedure. More...

#include <videoslam.hpp>

List of all members.

Public Member Functions

bool checkConnectivity (unsigned int seq)
bool determinePose ()
bool findNearestPoses (int &index1, int &index2, const ros::Time &targetTime)
void handle_info (const sensor_msgs::CameraInfoConstPtr &info_msg)
void handle_pose (const geometry_msgs::PoseStamped &pose_msg)
void handle_tracks (const thermalvis::feature_tracksConstPtr &msg)
void integrateNewTrackMessage (const thermalvis::feature_tracksConstPtr &msg)
void main_loop (const ros::TimerEvent &event)
void prepareForTermination ()
void publishPoints (ros::Time stamp, unsigned int seq)
void publishPose ()
void serverCallback (thermalvis::videoslamConfig &config, uint32_t level)
void triangulatePoints ()
void trimFeatureTrackVector ()
bool updateKeyframePoses (const geometry_msgs::PoseStamped &pose_msg, bool fromICP=true)
bool updateLocalPoseEstimates ()
 videoslamNode (ros::NodeHandle &nh, videoslamData startupData)

Private Attributes

cv::Mat ACM [MAX_FRAMES]
double baAverage
int baSuccesses
int bicolor
cv::Mat blank
double bundleRotShift
double bundleTransShift
ros::Publisher camera_pub
pcl::PointCloud< pcl::PointXYZ >
::Ptr 
cloud_ptr_
ros::Publisher confidence_pub
videoslamData configData
geometry_msgs::PoseStamped currentPose
int currentPoseIndex
int decimation
double distanceTravelled
double dsAverage
cv::Mat extrinsicCalib_P
cv::Mat extrinsicCalib_R
cv::Mat extrinsicCalib_T
cv::Mat eye4
dynamic_reconfigure::Server
< thermalvis::videoslamConfig >
::CallbackType 
f
cv::Mat F_arr [MAX_FRAMES]
vector< featureTrackfeatureTrackVector
std_msgs::Header frameHeaderHistoryBuffer [MAX_HISTORY]
unsigned int frameHeaderHistoryCounter
unsigned int frameProcessedCounter
int framesArrived
int framesProcessed
vector< unsigned int > framesReceived
cv::Mat H_arr [MAX_FRAMES]
bool hasTerminatedFeed
ros::Subscriber info_sub
bool infoProcessed
keyframeStore keyframe_store
geometry_msgs::PoseStamped keyframePoses [MAX_POSES_TO_STORE]
bool keyframeTypes [MAX_POSES_TO_STORE]
int lastTestedFrame
bool latestReceivedPoseProcessed
double latestTracksTime
std::streambuf * lBufferOld
std::ofstream lStream
boost::mutex main_mutex
char nodeName [256]
ros::Publisher path_pub
double pnpError
double pnpInlierProp
geometry_msgs::PoseStamped pnpPose
int pnpSuccesses
sensor_msgs::PointCloud2 pointCloud_message
ros::Publisher points_pub
double pointShift
ros::Publisher pose_pub
char pose_pub_name [256]
ros::Subscriber pose_sub
geometry_msgs::PoseStamped poseHistoryBuffer [MAX_HISTORY]
unsigned int poseHistoryCounter
double predictiveError
geometry_msgs::PoseStamped savedPose
dynamic_reconfigure::Server
< thermalvis::videoslamConfig > 
server
unsigned int storedPosesCount
SysSBA sys
ros::Timer timer
ros::Subscriber tracks_sub
int usedTriangulations

Detailed Description

Manages the ODOMETRY procedure.

Definition at line 98 of file videoslam.hpp.


Constructor & Destructor Documentation

Definition at line 1267 of file videoslam.cpp.


Member Function Documentation

bool videoslamNode::checkConnectivity ( unsigned int  seq)

Definition at line 99 of file videoslam.cpp.

Definition at line 637 of file videoslam.cpp.

bool videoslamNode::findNearestPoses ( int &  index1,
int &  index2,
const ros::Time targetTime 
)

Definition at line 427 of file videoslam.cpp.

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

Definition at line 1175 of file videoslam.cpp.

void videoslamNode::handle_pose ( const geometry_msgs::PoseStamped &  pose_msg)

Definition at line 888 of file videoslam.cpp.

void videoslamNode::handle_tracks ( const thermalvis::feature_tracksConstPtr &  msg)

Definition at line 1017 of file videoslam.cpp.

void videoslamNode::integrateNewTrackMessage ( const thermalvis::feature_tracksConstPtr &  msg)

Definition at line 936 of file videoslam.cpp.

void videoslamNode::main_loop ( const ros::TimerEvent event)

Definition at line 1162 of file videoslam.cpp.

void videoslamNode::publishPoints ( ros::Time  stamp,
unsigned int  seq 
)

Definition at line 813 of file videoslam.cpp.

Definition at line 1116 of file videoslam.cpp.

void videoslamNode::serverCallback ( thermalvis::videoslamConfig &  config,
uint32_t  level 
)

Definition at line 1240 of file videoslam.cpp.

Definition at line 595 of file videoslam.cpp.

Definition at line 302 of file videoslam.cpp.

bool videoslamNode::updateKeyframePoses ( const geometry_msgs::PoseStamped &  pose_msg,
bool  fromICP = true 
)

Definition at line 137 of file videoslam.cpp.

Definition at line 526 of file videoslam.cpp.


Member Data Documentation

cv::Mat videoslamNode::ACM[MAX_FRAMES] [private]

Definition at line 156 of file videoslam.hpp.

double videoslamNode::baAverage [private]

Definition at line 120 of file videoslam.hpp.

Definition at line 119 of file videoslam.hpp.

int videoslamNode::bicolor [private]

Definition at line 103 of file videoslam.hpp.

cv::Mat videoslamNode::blank [private]

Definition at line 115 of file videoslam.hpp.

Definition at line 158 of file videoslam.hpp.

Definition at line 158 of file videoslam.hpp.

Definition at line 131 of file videoslam.hpp.

pcl::PointCloud<pcl::PointXYZ>::Ptr videoslamNode::cloud_ptr_ [private]

Definition at line 133 of file videoslam.hpp.

Definition at line 131 of file videoslam.hpp.

Definition at line 101 of file videoslam.hpp.

geometry_msgs::PoseStamped videoslamNode::currentPose [private]

Definition at line 172 of file videoslam.hpp.

Definition at line 174 of file videoslam.hpp.

Definition at line 103 of file videoslam.hpp.

Definition at line 117 of file videoslam.hpp.

double videoslamNode::dsAverage [private]

Definition at line 120 of file videoslam.hpp.

Definition at line 108 of file videoslam.hpp.

Definition at line 108 of file videoslam.hpp.

Definition at line 108 of file videoslam.hpp.

cv::Mat videoslamNode::eye4 [private]

Definition at line 115 of file videoslam.hpp.

dynamic_reconfigure::Server<thermalvis::videoslamConfig>::CallbackType videoslamNode::f [private]

Definition at line 184 of file videoslam.hpp.

cv::Mat videoslamNode::F_arr[MAX_FRAMES] [private]

Definition at line 154 of file videoslam.hpp.

Definition at line 151 of file videoslam.hpp.

Definition at line 136 of file videoslam.hpp.

Definition at line 135 of file videoslam.hpp.

unsigned int videoslamNode::frameProcessedCounter [private]

Definition at line 111 of file videoslam.hpp.

Definition at line 119 of file videoslam.hpp.

Definition at line 119 of file videoslam.hpp.

vector<unsigned int> videoslamNode::framesReceived [private]

Definition at line 178 of file videoslam.hpp.

cv::Mat videoslamNode::H_arr[MAX_FRAMES] [private]

Definition at line 154 of file videoslam.hpp.

Definition at line 113 of file videoslam.hpp.

Definition at line 123 of file videoslam.hpp.

Definition at line 149 of file videoslam.hpp.

Definition at line 153 of file videoslam.hpp.

geometry_msgs::PoseStamped videoslamNode::keyframePoses[MAX_POSES_TO_STORE] [private]

Definition at line 139 of file videoslam.hpp.

Definition at line 140 of file videoslam.hpp.

Definition at line 147 of file videoslam.hpp.

Definition at line 176 of file videoslam.hpp.

Definition at line 145 of file videoslam.hpp.

std::streambuf* videoslamNode::lBufferOld [private]

Definition at line 106 of file videoslam.hpp.

std::ofstream videoslamNode::lStream [private]

Definition at line 105 of file videoslam.hpp.

boost::mutex videoslamNode::main_mutex [private]

Definition at line 181 of file videoslam.hpp.

char videoslamNode::nodeName[256] [private]

Definition at line 160 of file videoslam.hpp.

Definition at line 131 of file videoslam.hpp.

double videoslamNode::pnpError [private]

Definition at line 145 of file videoslam.hpp.

double videoslamNode::pnpInlierProp [private]

Definition at line 145 of file videoslam.hpp.

geometry_msgs::PoseStamped videoslamNode::pnpPose [private]

Definition at line 172 of file videoslam.hpp.

Definition at line 119 of file videoslam.hpp.

sensor_msgs::PointCloud2 videoslamNode::pointCloud_message [private]

Definition at line 169 of file videoslam.hpp.

Definition at line 131 of file videoslam.hpp.

double videoslamNode::pointShift [private]

Definition at line 145 of file videoslam.hpp.

Definition at line 162 of file videoslam.hpp.

char videoslamNode::pose_pub_name[256] [private]

Definition at line 163 of file videoslam.hpp.

Definition at line 124 of file videoslam.hpp.

geometry_msgs::PoseStamped videoslamNode::poseHistoryBuffer[MAX_HISTORY] [private]

Definition at line 137 of file videoslam.hpp.

unsigned int videoslamNode::poseHistoryCounter [private]

Definition at line 135 of file videoslam.hpp.

Definition at line 158 of file videoslam.hpp.

geometry_msgs::PoseStamped videoslamNode::savedPose [private]

Definition at line 172 of file videoslam.hpp.

dynamic_reconfigure::Server<thermalvis::videoslamConfig> videoslamNode::server [private]

Definition at line 183 of file videoslam.hpp.

unsigned int videoslamNode::storedPosesCount [private]

Definition at line 141 of file videoslam.hpp.

SysSBA videoslamNode::sys [private]

Definition at line 126 of file videoslam.hpp.

Definition at line 143 of file videoslam.hpp.

Definition at line 122 of file videoslam.hpp.

Definition at line 147 of file videoslam.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