$search
Declarations for the LISTENER 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 "listenerConfig.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>
Go to the source code of this file.
Classes | |
class | BagSubscriber< M > |
Inherits from message_filters::SimpleFilter<M>Class to use protected signalMessage function. More... | |
struct | listenerData |
Stores configuration information for the rosbag listener routine. More... | |
class | listenerNode |
Manages the listener procedure. More... | |
Defines | |
#define | DEFAULT_MAX_TIMESTAMP_DIFF 0.01 |
#define | FILTER_DISTANCE 1 |
#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__ [] = "LISTENER" |
Declarations for the LISTENER node.
Definition in file listener.hpp.
#define DEFAULT_MAX_TIMESTAMP_DIFF 0.01 |
Definition at line 47 of file listener.hpp.
#define FILTER_DISTANCE 1 |
Definition at line 43 of file listener.hpp.
#define SAVEPLY false |
Definition at line 42 of file listener.hpp.
#define SIGMA_P 15 |
Definition at line 44 of file listener.hpp.
#define SIGMA_R .05 |
Definition at line 45 of file listener.hpp.
Definition at line 187 of file listener.hpp.
const char __PROGRAM__[] = "LISTENER" |
Definition at line 49 of file listener.hpp.