#include <mono_depth_processor.hpp>
Protected Member Functions | |
virtual void | imageCallback (const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &image_info_msg, const sensor_msgs::CameraInfoConstPtr &depth_info_msg)=0 |
MonoDepthProcessor (const std::string &transport) | |
Private Types | |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > | ApproximatePolicy |
typedef message_filters::Synchronizer < ApproximatePolicy > | ApproximateSync |
typedef message_filters::sync_policies::ExactTime < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > | ExactPolicy |
typedef message_filters::Synchronizer < ExactPolicy > | ExactSync |
Private Member Functions | |
void | checkInputsSynchronized () |
void | dataCb (const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::ImageConstPtr &depth_image_msg, const sensor_msgs::CameraInfoConstPtr &image_info_msg, const sensor_msgs::CameraInfoConstPtr &depth_info_msg) |
Static Private Member Functions | |
static void | increment (int *value) |
Private Attributes | |
int | all_received_ |
boost::shared_ptr < ApproximateSync > | approximate_sync_ |
ros::WallTimer | check_synced_timer_ |
int | depth_info_received_ |
message_filters::Subscriber < sensor_msgs::CameraInfo > | depth_info_sub_ |
int | depth_received_ |
image_transport::SubscriberFilter | depth_sub_ |
boost::shared_ptr< ExactSync > | exact_sync_ |
int | image_info_received_ |
message_filters::Subscriber < sensor_msgs::CameraInfo > | image_info_sub_ |
int | image_received_ |
image_transport::SubscriberFilter | image_sub_ |
int | queue_size_ |
This is an abstract base class for nodes that process RGBD data, such as Microsoft Kinect. It handles synchronization of input topics (approximate or exact) and checks for sync errors. To use this class, subclass it and implement the imageCallback() method.
Definition at line 24 of file mono_depth_processor.hpp.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> fovis_ros::MonoDepthProcessor::ApproximatePolicy [private] |
Definition at line 33 of file mono_depth_processor.hpp.
typedef message_filters::Synchronizer<ApproximatePolicy> fovis_ros::MonoDepthProcessor::ApproximateSync [private] |
Definition at line 35 of file mono_depth_processor.hpp.
typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> fovis_ros::MonoDepthProcessor::ExactPolicy [private] |
Definition at line 32 of file mono_depth_processor.hpp.
typedef message_filters::Synchronizer<ExactPolicy> fovis_ros::MonoDepthProcessor::ExactSync [private] |
Definition at line 34 of file mono_depth_processor.hpp.
fovis_ros::MonoDepthProcessor::MonoDepthProcessor | ( | const std::string & | transport | ) | [inline, protected] |
Constructor, subscribes to input topics using image transport and registers callbacks.
transport | The image transport to use |
Definition at line 90 of file mono_depth_processor.hpp.
void fovis_ros::MonoDepthProcessor::checkInputsSynchronized | ( | ) | [inline, private] |
Definition at line 63 of file mono_depth_processor.hpp.
void fovis_ros::MonoDepthProcessor::dataCb | ( | const sensor_msgs::ImageConstPtr & | image_msg, |
const sensor_msgs::ImageConstPtr & | depth_image_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | image_info_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | depth_info_msg | ||
) | [inline, private] |
Definition at line 50 of file mono_depth_processor.hpp.
virtual void fovis_ros::MonoDepthProcessor::imageCallback | ( | const sensor_msgs::ImageConstPtr & | image_msg, |
const sensor_msgs::ImageConstPtr & | depth_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | image_info_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | depth_info_msg | ||
) | [protected, pure virtual] |
Implement this method in sub-classes
Implemented in fovis_ros::MonoDepthOdometer.
static void fovis_ros::MonoDepthProcessor::increment | ( | int * | value | ) | [inline, static, private] |
Definition at line 45 of file mono_depth_processor.hpp.
int fovis_ros::MonoDepthProcessor::all_received_ [private] |
Definition at line 42 of file mono_depth_processor.hpp.
boost::shared_ptr<ApproximateSync> fovis_ros::MonoDepthProcessor::approximate_sync_ [private] |
Definition at line 37 of file mono_depth_processor.hpp.
Definition at line 41 of file mono_depth_processor.hpp.
int fovis_ros::MonoDepthProcessor::depth_info_received_ [private] |
Definition at line 42 of file mono_depth_processor.hpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> fovis_ros::MonoDepthProcessor::depth_info_sub_ [private] |
Definition at line 31 of file mono_depth_processor.hpp.
int fovis_ros::MonoDepthProcessor::depth_received_ [private] |
Definition at line 42 of file mono_depth_processor.hpp.
Definition at line 30 of file mono_depth_processor.hpp.
boost::shared_ptr<ExactSync> fovis_ros::MonoDepthProcessor::exact_sync_ [private] |
Definition at line 36 of file mono_depth_processor.hpp.
int fovis_ros::MonoDepthProcessor::image_info_received_ [private] |
Definition at line 42 of file mono_depth_processor.hpp.
message_filters::Subscriber<sensor_msgs::CameraInfo> fovis_ros::MonoDepthProcessor::image_info_sub_ [private] |
Definition at line 31 of file mono_depth_processor.hpp.
int fovis_ros::MonoDepthProcessor::image_received_ [private] |
Definition at line 42 of file mono_depth_processor.hpp.
Definition at line 30 of file mono_depth_processor.hpp.
int fovis_ros::MonoDepthProcessor::queue_size_ [private] |
Definition at line 38 of file mono_depth_processor.hpp.