Declarations for the VIDEOSLAM node. More...
#include "general_resources.hpp"#include "ros_resources.hpp"#include "opencv_resources.hpp"#include "pcl_resources.hpp"#include "improc.hpp"#include "video.hpp"#include "features.hpp"#include "reconstruction.hpp"#include "sba.hpp"#include "keyframes.hpp"#include "geometry.hpp"#include "feature_tracks.h"#include "pose_confidence.h"#include "videoslamConfig.h"#include <std_msgs/Float32.h>

Go to the source code of this file.
Classes | |
| struct | videoslamData |
| Stores configuration information for the ODOMETRY routine. More... | |
| class | videoslamNode |
| Manages the ODOMETRY procedure. More... | |
Defines | |
| #define | DEFAULT_DRAWGRAPH_BICOLOR 0 |
| #define | DEFAULT_DRAWGRAPH_DECIMATION 1 |
| #define | MAX_FRAMES 1000 |
| #define | MAX_HISTORY 10 |
| #define | MAX_POSES_TO_STORE 100 |
| #define | MAX_TIME_GAP_FOR_INTERP 0.5 |
| #define | MAX_TRACKS 10000 |
| #define | SBA_MEMORY 134217728 |
Typedefs | |
| typedef pcl::PointCloud < pcl::PointXYZ > | PointCloud |
| typedef Eigen::Quaternion< double > | QuaternionDbl |
| typedef dynamic_reconfigure::Server < thermalvis::videoslamConfig > | Server |
Functions | |
| void | connected (const ros::SingleSubscriberPublisher &) |
| void | disconnected (const ros::SingleSubscriberPublisher &) |
| bool | interpolatePose (const geometry_msgs::Pose &pose1, ros::Time time1, const geometry_msgs::Pose &pose2, ros::Time time2, geometry_msgs::Pose &finalPose, ros::Time time3) |
| void | mySigintHandler (int sig) |
| void | shiftPose (const geometry_msgs::Pose &pose_src, geometry_msgs::Pose &pose_dst, cv::Mat transformation) |
Variables | |
| const char | __PROGRAM__ [] = "THERMALVIS_ODOMETRY" |
| boost::shared_ptr < videoslamNode > * | globalNodePtr |
| bool | wantsToShutdown = false |
Declarations for the VIDEOSLAM node.
Definition in file videoslam.hpp.
| #define DEFAULT_DRAWGRAPH_BICOLOR 0 |
Definition at line 35 of file videoslam.hpp.
| #define DEFAULT_DRAWGRAPH_DECIMATION 1 |
Definition at line 34 of file videoslam.hpp.
| #define MAX_FRAMES 1000 |
Definition at line 40 of file videoslam.hpp.
| #define MAX_HISTORY 10 |
Definition at line 38 of file videoslam.hpp.
| #define MAX_POSES_TO_STORE 100 |
Definition at line 39 of file videoslam.hpp.
| #define MAX_TIME_GAP_FOR_INTERP 0.5 |
Definition at line 43 of file videoslam.hpp.
| #define MAX_TRACKS 10000 |
Definition at line 41 of file videoslam.hpp.
| #define SBA_MEMORY 134217728 |
Definition at line 42 of file videoslam.hpp.
| typedef pcl::PointCloud<pcl::PointXYZ> PointCloud |
Definition at line 45 of file videoslam.hpp.
| typedef Eigen::Quaternion<double> QuaternionDbl |
Definition at line 30 of file videoslam.hpp.
| typedef dynamic_reconfigure::Server< thermalvis::videoslamConfig > Server |
Definition at line 31 of file videoslam.hpp.
| void connected | ( | const ros::SingleSubscriberPublisher & | ) |
Definition at line 223 of file videoslam.hpp.
| void disconnected | ( | const ros::SingleSubscriberPublisher & | ) |
Definition at line 224 of file videoslam.hpp.
| bool interpolatePose | ( | const geometry_msgs::Pose & | pose1, |
| ros::Time | time1, | ||
| const geometry_msgs::Pose & | pose2, | ||
| ros::Time | time2, | ||
| geometry_msgs::Pose & | finalPose, | ||
| ros::Time | time3 | ||
| ) |
Definition at line 393 of file videoslam.cpp.
| void mySigintHandler | ( | int | sig | ) |
Definition at line 350 of file calibrator.cpp.
| void shiftPose | ( | const geometry_msgs::Pose & | pose_src, |
| geometry_msgs::Pose & | pose_dst, | ||
| cv::Mat | transformation | ||
| ) |
Definition at line 349 of file videoslam.cpp.
| const char __PROGRAM__[] = "THERMALVIS_ODOMETRY" |
Definition at line 47 of file videoslam.hpp.
| boost::shared_ptr< videoslamNode >* globalNodePtr |
Definition at line 226 of file videoslam.hpp.
| bool wantsToShutdown = false |
Definition at line 49 of file videoslam.hpp.