Classes | Defines | Typedefs | Variables
extractor.hpp File Reference

Declarations for the EXTRACTOR node. Thanks to Hans Moorkens for contributions to this node. More...

#include "ros_resources.hpp"
#include "general_resources.hpp"
#include "opencv_resources.hpp"
#include "tools.hpp"
#include "improc.hpp"
#include <dynamic_reconfigure/server.h>
#include "extractorConfig.h"
#include <rosbag/bag.h>
#include <rosbag/view.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <opencv/cv.h>
#include <opencv/highgui.h>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <boost/foreach.hpp>
#include "boost/filesystem.hpp"
#include <time.h>
#include <math.h>
#include "ros/ros.h"
#include "sensor_msgs/Image.h"
#include "sensor_msgs/CameraInfo.h"
#include <iostream>
#include <fstream>
Include dependency graph for extractor.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  BagSubscriber< M >
struct  extractorData
 Stores configuration information for the rosbag extractor routine. More...
class  extractorNode
 Manages the extractor procedure. More...

Defines

#define DEFAULT_MAX_TIMESTAMP_DIFF   0.01
#define FILTER_DISTANCE   1
#define MAX_BAGS   200
#define SAVEPLY   false
#define SIGMA_P   15
#define SIGMA_R   .05

Typedefs

typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
SyncPolicy

Variables

const char __PROGRAM__ [] = "EXTRACTOR"

Detailed Description

Declarations for the EXTRACTOR node. Thanks to Hans Moorkens for contributions to this node.

Definition in file extractor.hpp.


Define Documentation

#define DEFAULT_MAX_TIMESTAMP_DIFF   0.01

Definition at line 50 of file extractor.hpp.

#define FILTER_DISTANCE   1

Definition at line 44 of file extractor.hpp.

#define MAX_BAGS   200

Definition at line 48 of file extractor.hpp.

#define SAVEPLY   false

Definition at line 43 of file extractor.hpp.

#define SIGMA_P   15

Definition at line 45 of file extractor.hpp.

#define SIGMA_R   .05

Definition at line 46 of file extractor.hpp.


Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > SyncPolicy

Definition at line 193 of file extractor.hpp.


Variable Documentation

const char __PROGRAM__[] = "EXTRACTOR"

Definition at line 52 of file extractor.hpp.



thermalvis
Author(s): Stephen Vidas
autogenerated on Sun Jan 5 2014 11:38:45