Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009 #pragma once
00010
00011 #ifndef Q_MOC_RUN
00012 #include "grid_map_rviz_plugin/modified/frame_manager.h"
00013 #include <rviz/message_filter_display.h>
00014 #endif
00015
00016 namespace grid_map_rviz_plugin {
00017
00018 template<class MessageType>
00019 class MessageFilterDisplayMod : public rviz::MessageFilterDisplay<MessageType>
00020 {
00021 public:
00022 typedef MessageFilterDisplayMod<MessageType> MFDClass;
00023
00024 void onInitialize()
00025 {
00026 MFDClass::tf_filter_ = new tf::MessageFilter<MessageType>(*MFDClass::context_->getTFClient(),
00027 MFDClass::fixed_frame_.toStdString(),
00028 10, MFDClass::update_nh_);
00029
00030 MFDClass::tf_filter_->connectInput(MFDClass::sub_);
00031 MFDClass::tf_filter_->registerCallback(
00032 boost::bind(&MFDClass::incomingMessage, this, _1));
00033 MFDClass::context_->getFrameManager()->registerFilterForTransformStatusCheck(
00034 MFDClass::tf_filter_, this);
00035 }
00036
00037 };
00038
00039 }