Skip to content

Commit

Permalink
migrate DepthCloudDisplay to tf2
Browse files Browse the repository at this point in the history
  • Loading branch information
wjwwood committed May 9, 2018
1 parent ffdfad0 commit 2dc400d
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 5 deletions.
11 changes: 8 additions & 3 deletions src/rviz/default_plugin/depth_cloud_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#include "rviz/properties/int_property.h"
#include "rviz/frame_manager.h"

#include <tf/transform_listener.h>
#include <tf2_ros/buffer.h>

#include <boost/bind.hpp>
#include <boost/algorithm/string/erase.hpp>
Expand Down Expand Up @@ -310,8 +310,13 @@ void DepthCloudDisplay::subscribe()
// subscribe to depth map topic
depthmap_sub_->subscribe(*depthmap_it_, depthmap_topic, queue_size_, image_transport::TransportHints(depthmap_transport));

depthmap_tf_filter_.reset(
new tf::MessageFilter<sensor_msgs::Image>(*depthmap_sub_, *context_->getTFClient(), fixed_frame_.toStdString(), queue_size_, threaded_nh_));
depthmap_tf_filter_.reset(new tf2_ros::MessageFilter<sensor_msgs::Image>(
*depthmap_sub_,
*context_->getTF2BufferPtr(),
fixed_frame_.toStdString(),
queue_size_,
threaded_nh_
));

// subscribe to CameraInfo topic
std::string info_topic = image_transport::getCameraInfoTopic(depthmap_topic);
Expand Down
4 changes: 2 additions & 2 deletions src/rviz/default_plugin/depth_cloud_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
# include <message_filters/subscriber.h>
# include <message_filters/synchronizer.h>
# include <message_filters/sync_policies/approximate_time.h>
# include <tf/message_filter.h>
# include <tf2_ros/message_filter.h>

# include "rviz/properties/enum_property.h"
# include "rviz/properties/float_property.h"
Expand Down Expand Up @@ -181,7 +181,7 @@ protected Q_SLOTS:
// ROS image subscription & synchronization
boost::scoped_ptr<image_transport::ImageTransport> depthmap_it_;
boost::shared_ptr<image_transport::SubscriberFilter > depthmap_sub_;
boost::shared_ptr<tf::MessageFilter<sensor_msgs::Image> > depthmap_tf_filter_;
boost::shared_ptr<tf2_ros::MessageFilter<sensor_msgs::Image> > depthmap_tf_filter_;
boost::scoped_ptr<image_transport::ImageTransport> rgb_it_;
boost::shared_ptr<image_transport::SubscriberFilter > rgb_sub_;
boost::shared_ptr<message_filters::Subscriber<sensor_msgs::CameraInfo> > cam_info_sub_;
Expand Down

0 comments on commit 2dc400d

Please sign in to comment.