Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Deprecate tf for tf2 #1236

Merged
merged 16 commits into from
May 10, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 11 additions & 0 deletions src/rviz/default_plugin/axes_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,20 @@

#include <boost/bind.hpp>

#ifndef _WIN32
# pragma GCC diagnostic push
# ifdef __clang__
# pragma clang diagnostic ignored "-W#warnings"
# endif
#endif

#include <OgreSceneNode.h>
#include <OgreSceneManager.h>

#ifndef _WIN32
# pragma GCC diagnostic pop
#endif

#include "rviz/display_context.h"
#include "rviz/frame_manager.h"
#include "rviz/ogre_helpers/axes.h"
Expand Down
25 changes: 19 additions & 6 deletions src/rviz/default_plugin/camera_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,13 @@

#include <boost/bind.hpp>

#ifndef _WIN32
# pragma GCC diagnostic push
# ifdef __clang__
# pragma clang diagnostic ignored "-W#warnings"
# endif
#endif

#include <OgreManualObject.h>
#include <OgreMaterialManager.h>
#include <OgreRectangle2D.h>
Expand All @@ -41,7 +48,11 @@
#include <OgreTechnique.h>
#include <OgreCamera.h>

#include <tf/transform_listener.h>
#ifndef _WIN32
# pragma GCC diagnostic pop
#endif

#include <tf2_ros/message_filter.h>

#include "rviz/bit_allocator.h"
#include "rviz/frame_manager.h"
Expand Down Expand Up @@ -82,7 +93,7 @@ CameraDisplay::CameraDisplay()
: ImageDisplayBase()
, texture_()
, render_panel_( 0 )
, caminfo_tf_filter_( 0 )
, caminfo_tf_filter_( nullptr )
, new_caminfo_( false )
, force_render_( false )
, caminfo_ok_(false)
Expand Down Expand Up @@ -127,8 +138,6 @@ CameraDisplay::~CameraDisplay()
bg_scene_node_->getParentSceneNode()->removeAndDestroyChild( bg_scene_node_->getName() );
fg_scene_node_->getParentSceneNode()->removeAndDestroyChild( fg_scene_node_->getName() );

delete caminfo_tf_filter_;

context_->visibilityBits()->freeBits(vis_bit_);
}
}
Expand All @@ -137,8 +146,12 @@ void CameraDisplay::onInitialize()
{
ImageDisplayBase::onInitialize();

caminfo_tf_filter_ = new tf::MessageFilter<sensor_msgs::CameraInfo>( *context_->getTFClient(), fixed_frame_.toStdString(),
queue_size_property_->getInt(), update_nh_ );
caminfo_tf_filter_.reset(new tf2_ros::MessageFilter<sensor_msgs::CameraInfo>(
*context_->getTF2BufferPtr(),
fixed_frame_.toStdString(),
queue_size_property_->getInt(),
update_nh_
));

bg_scene_node_ = scene_node_->createChildSceneNode();
fg_scene_node_ = scene_node_->createChildSceneNode();
Expand Down
6 changes: 4 additions & 2 deletions src/rviz/default_plugin/camera_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
#ifndef RVIZ_CAMERA_DISPLAY_H
#define RVIZ_CAMERA_DISPLAY_H

#include <memory>

#include <QObject>

#ifndef Q_MOC_RUN
Expand All @@ -40,7 +42,7 @@
# include <sensor_msgs/CameraInfo.h>

# include <message_filters/subscriber.h>
# include <tf/message_filter.h>
# include <tf2_ros/message_filter.h>

# include "rviz/image/image_display_base.h"
# include "rviz/image/ros_image_texture.h"
Expand Down Expand Up @@ -126,7 +128,7 @@ private Q_SLOTS:
Ogre::MaterialPtr fg_material_;

message_filters::Subscriber<sensor_msgs::CameraInfo> caminfo_sub_;
tf::MessageFilter<sensor_msgs::CameraInfo>* caminfo_tf_filter_;
std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::CameraInfo>> caminfo_tf_filter_;

FloatProperty* alpha_property_;
EnumProperty* image_position_property_;
Expand Down
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
2 changes: 0 additions & 2 deletions src/rviz/default_plugin/effort_display.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
#include <OgreSceneNode.h>
#include <OgreSceneManager.h>

#include <tf/transform_listener.h>

#include <rviz/visualization_manager.h>
#include <rviz/properties/color_property.h>
#include <rviz/properties/float_property.h>
Expand Down
23 changes: 22 additions & 1 deletion src/rviz/default_plugin/effort_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -544,12 +544,33 @@ class MessageFilterJointStateDisplay: public _RosTopicDisplay

virtual void onInitialize()
{
tf_filter_ = new tf::MessageFilterJointState( *context_->getTFClient(),
// TODO(wjwwood): remove this and use tf2 interface instead
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif

auto tf_client = context_->getTFClient();

#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
tf_filter_ = new tf::MessageFilterJointState( *tf_client,
fixed_frame_.toStdString(), 10, update_nh_ );

tf_filter_->connectInput( sub_ );
tf_filter_->registerCallback( boost::bind( &MessageFilterJointStateDisplay::incomingMessage, this, _1 ));
// TODO(wjwwood): remove this and use tf2 interface instead
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif

context_->getFrameManager()->registerFilterForTransformStatusCheck( tf_filter_, this );

#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
}

virtual ~MessageFilterJointStateDisplay()
Expand Down
43 changes: 40 additions & 3 deletions src/rviz/default_plugin/grid_cells_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,12 +29,24 @@

#include <boost/bind.hpp>

#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wpedantic"
# ifdef __clang__
# pragma clang diagnostic ignored "-Wdeprecated-register"
# endif
# pragma GCC diagnostic ignored "-Woverloaded-virtual"
# pragma GCC diagnostic ignored "-Wunused-parameter"
#endif

#include <OgreSceneNode.h>
#include <OgreSceneManager.h>
#include <OgreManualObject.h>
#include <OgreBillboardSet.h>

#include <tf/transform_listener.h>
#ifndef _WIN32
# pragma GCC diagnostic pop
#endif

#include "rviz/frame_manager.h"
#include "rviz/ogre_helpers/arrow.h"
Expand Down Expand Up @@ -73,8 +85,23 @@ GridCellsDisplay::GridCellsDisplay()

void GridCellsDisplay::onInitialize()
{
tf_filter_ = new tf::MessageFilter<nav_msgs::GridCells>( *context_->getTFClient(), fixed_frame_.toStdString(),
10, update_nh_ );
// TODO(wjwwood): remove this and use tf2 interface instead
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif

auto tf_client = context_->getTFClient();

#ifndef _WIN32
# pragma GCC diagnostic pop
#endif

tf_filter_ = new tf::MessageFilter<nav_msgs::GridCells>(
*tf_client,
fixed_frame_.toStdString(),
10,
update_nh_);
static int count = 0;
std::stringstream ss;
ss << "PolyLine" << count++;
Expand All @@ -88,7 +115,17 @@ void GridCellsDisplay::onInitialize()

tf_filter_->connectInput( sub_ );
tf_filter_->registerCallback( boost::bind( &GridCellsDisplay::incomingMessage, this, _1 ));
// TODO(wjwwood): remove this and use tf2 interface instead
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif

context_->getFrameManager()->registerFilterForTransformStatusCheck( tf_filter_, this );

#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
}

GridCellsDisplay::~GridCellsDisplay()
Expand Down
16 changes: 15 additions & 1 deletion src/rviz/default_plugin/image_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,16 @@

#include <boost/bind.hpp>

#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wpedantic"
# ifdef __clang__
# pragma clang diagnostic ignored "-Wdeprecated-register"
# endif
# pragma GCC diagnostic ignored "-Woverloaded-virtual"
# pragma GCC diagnostic ignored "-Wunused-parameter"
#endif

#include <OgreManualObject.h>
#include <OgreMaterialManager.h>
#include <OgreRectangle2D.h>
Expand All @@ -42,7 +52,9 @@
#include <OgreTechnique.h>
#include <OgreCamera.h>

#include <tf/transform_listener.h>
#ifndef _WIN32
# pragma GCC diagnostic pop
#endif

#include "rviz/display_context.h"
#include "rviz/frame_manager.h"
Expand Down Expand Up @@ -189,6 +201,8 @@ void ImageDisplay::clear()

void ImageDisplay::update( float wall_dt, float ros_dt )
{
Q_UNUSED(wall_dt)
Q_UNUSED(ros_dt)
try
{
texture_.update();
Expand Down
10 changes: 10 additions & 0 deletions src/rviz/default_plugin/interactive_marker_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,17 @@ InteractiveMarkerDisplay::InteractiveMarkerDisplay()

void InteractiveMarkerDisplay::onInitialize()
{
// TODO(wjwwood): remove this and use tf2 interface instead
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif

tf::Transformer* tf = context_->getFrameManager()->getTFClient();

#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
im_client_.reset( new interactive_markers::InteractiveMarkerClient( *tf, fixed_frame_.toStdString() ) );

im_client_->setInitCb( boost::bind( &InteractiveMarkerDisplay::initCb, this, _1 ) );
Expand Down
10 changes: 10 additions & 0 deletions src/rviz/default_plugin/interactive_markers/interactive_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -315,8 +315,18 @@ void InteractiveMarker::updateReferencePose()
else
{
std::string error;
// TODO(wjwwood): remove this and use tf2 interface instead
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif

int retval = context_->getFrameManager()->getTFClient()->getLatestCommonTime(
reference_frame_, fixed_frame, reference_time_, &error );

#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
if ( retval != tf::NO_ERROR )
{
std::ostringstream s;
Expand Down
13 changes: 12 additions & 1 deletion src/rviz/default_plugin/laser_scan_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,18 @@ void LaserScanDisplay::processMessage( const sensor_msgs::LaserScanConstPtr& sca

try
{
projector_->transformLaserScanToPointCloud( fixed_frame_.toStdString(), *scan, *cloud, *context_->getTFClient(),
// TODO(wjwwood): remove this and use tf2 interface instead
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
#endif

auto tf_client = context_->getTFClient();

#ifndef _WIN32
# pragma GCC diagnostic pop
#endif
projector_->transformLaserScanToPointCloud( fixed_frame_.toStdString(), *scan, *cloud, *tf_client,
laser_geometry::channel_option::Intensity );
}
catch (tf::TransformException& e)
Expand Down
2 changes: 0 additions & 2 deletions src/rviz/default_plugin/map_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,6 @@

#include <ros/ros.h>

#include <tf/transform_listener.h>

#include "rviz/frame_manager.h"
#include "rviz/ogre_helpers/custom_parameter_indices.h"
#include "rviz/ogre_helpers/grid.h"
Expand Down
Loading