From b1bb6a2567056044f2d5514d1135a2ffa1cb9be6 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:02:41 -0700 Subject: [PATCH 01/16] deprecate tf in favor of tf2 in VisualizationManager --- src/rviz/display_context.h | 12 +++++++++++- src/rviz/visualization_manager.cpp | 21 ++++++++++++++++++++- src/rviz/visualization_manager.h | 26 +++++++++++++++++++++++++- 3 files changed, 56 insertions(+), 3 deletions(-) diff --git a/src/rviz/display_context.h b/src/rviz/display_context.h index 84ee284057..d4c34ce4b4 100644 --- a/src/rviz/display_context.h +++ b/src/rviz/display_context.h @@ -29,7 +29,8 @@ #ifndef DISPLAY_CONTEXT_H #define DISPLAY_CONTEXT_H -#include // for uint64_t +#include // for uint64_t +#include #include #include @@ -51,6 +52,11 @@ namespace tf class TransformListener; } +namespace tf2_ros +{ +class Buffer; +} + namespace rviz { @@ -90,8 +96,12 @@ Q_OBJECT virtual FrameManager* getFrameManager() const = 0; /** @brief Convenience function: returns getFrameManager()->getTFClient(). */ + [[deprecated("use getTF2BufferPtr() instead")]] virtual tf::TransformListener* getTFClient() const = 0; + /** @brief Convenience function: returns getFrameManager()->getTF2BufferPtr(). */ + virtual std::shared_ptr getTF2BufferPtr() const = 0; + /** @brief Return the fixed frame name. */ virtual QString getFixedFrame() const = 0; diff --git a/src/rviz/visualization_manager.cpp b/src/rviz/visualization_manager.cpp index 996d59098f..5db0e8a13e 100644 --- a/src/rviz/visualization_manager.cpp +++ b/src/rviz/visualization_manager.cpp @@ -117,7 +117,21 @@ class VisualizationManagerPrivate boost::mutex render_mutex_; }; -VisualizationManager::VisualizationManager( RenderPanel* render_panel, WindowManagerInterface* wm, boost::shared_ptr tf ) +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif +VisualizationManager::VisualizationManager(RenderPanel* render_panel, WindowManagerInterface * wm) +: VisualizationManager(render_panel, wm, boost::shared_ptr()) +{} +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + +VisualizationManager::VisualizationManager( + RenderPanel* render_panel, + WindowManagerInterface* wm, + boost::shared_ptr tf) : ogre_root_( Ogre::Root::getSingletonPtr() ) , update_timer_(0) , shutting_down_(false) @@ -424,6 +438,11 @@ tf::TransformListener* VisualizationManager::getTFClient() const return frame_manager_->getTFClient(); } +std::shared_ptr VisualizationManager::getTF2BufferPtr() const +{ + return frame_manager_->getTF2BufferPtr(); +} + void VisualizationManager::resetTime() { root_display_group_->reset(); diff --git a/src/rviz/visualization_manager.h b/src/rviz/visualization_manager.h index aa615a451c..4b983d490c 100644 --- a/src/rviz/visualization_manager.h +++ b/src/rviz/visualization_manager.h @@ -109,7 +109,25 @@ Q_OBJECT * VisualizationFrame, the top-level container widget of rviz). * @param tf a pointer to tf::TransformListener which will be internally used by FrameManager. */ - VisualizationManager( RenderPanel* render_panel, WindowManagerInterface* wm = 0, boost::shared_ptr tf = boost::shared_ptr() ); + explicit VisualizationManager( + RenderPanel* render_panel, + WindowManagerInterface* wm = 0); + + [[deprecated( + "This constructor signature will be removed in the next version. " + "If you still need to pass a boost::shared_ptr, " + "disable the warning explicitly. " + "When this constructor is removed, a new optional argument will added to " + "the other constructor and it will take a std::pair<> containing a " + "std::shared_ptr and a " + "std::shared_ptr. " + "However, that cannot occur until the use of tf::TransformListener is " + "removed internally." + )]] + VisualizationManager( + RenderPanel* render_panel, + WindowManagerInterface* wm, + boost::shared_ptr tf); /** * \brief Destructor @@ -187,8 +205,14 @@ Q_OBJECT /** * @brief Convenience function: returns getFrameManager()->getTFClient(). */ + [[deprecated("use getTF2BufferPtr() instead")]] tf::TransformListener* getTFClient() const; + /** + * @brief Convenience function: returns getFrameManager()->getTF2BufferPtr(). + */ + std::shared_ptr getTF2BufferPtr() const; + /** * @brief Returns the Ogre::SceneManager used for the main RenderPanel. */ From 7ee47f3617cef5dd3cd69f4d238ee72b9cbb2c80 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:17:26 -0700 Subject: [PATCH 02/16] deprecate tf in favor of tf2 in FrameManager --- src/rviz/frame_manager.cpp | 53 ++++++++++++++++++-- src/rviz/frame_manager.h | 100 +++++++++++++++++++++++++++++++++++-- 2 files changed, 144 insertions(+), 9 deletions(-) diff --git a/src/rviz/frame_manager.cpp b/src/rviz/frame_manager.cpp index 6d9136d06f..9645e41a7e 100644 --- a/src/rviz/frame_manager.cpp +++ b/src/rviz/frame_manager.cpp @@ -39,6 +39,20 @@ namespace rviz { +// TODO(wjwwood): remove this when deprecated interface is removed +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + +FrameManager::FrameManager() +: FrameManager(boost::shared_ptr()) +{} + +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + FrameManager::FrameManager(boost::shared_ptr tf) { if (!tf) tf_.reset(new tf::TransformListener(ros::NodeHandle(), ros::Duration(10*60), true)); @@ -323,7 +337,12 @@ std::string getTransformStatusName(const std::string& caller_id) return ss.str(); } -std::string FrameManager::discoverFailureReason(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, tf::FilterFailureReason reason) +std::string +FrameManager::discoverFailureReason( + const std::string& frame_id, + const ros::Time& stamp, + const std::string& caller_id, + tf::FilterFailureReason reason) { if (reason == tf::filter_failure_reasons::OutTheBack) { @@ -343,17 +362,43 @@ std::string FrameManager::discoverFailureReason(const std::string& frame_id, con return "Unknown reason for transform failure"; } +std::string +FrameManager::discoverFailureReason( + const std::string& frame_id, + const ros::Time& stamp, + const std::string& caller_id, + tf2_ros::FilterFailureReason reason) +{ + if (reason == tf2_ros::filter_failure_reasons::OutTheBack) + { + std::stringstream ss; + ss << "Message removed because it is too old (frame=[" << frame_id << "], stamp=[" << stamp << "])"; + return ss.str(); + } + else + { + std::string error; + if (transformHasProblems(frame_id, stamp, error)) + { + return error; + } + } + + return "Unknown reason for transform failure"; +} + void FrameManager::messageArrived( const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, Display* display ) { display->setStatusStd( StatusProperty::Ok, getTransformStatusName( caller_id ), "Transform OK" ); } -void FrameManager::messageFailed( const std::string& frame_id, const ros::Time& stamp, - const std::string& caller_id, tf::FilterFailureReason reason, Display* display ) +void FrameManager::messageFailedImpl( + const std::string& caller_id, + const std::string& status_text, + Display* display) { std::string status_name = getTransformStatusName( caller_id ); - std::string status_text = discoverFailureReason( frame_id, stamp, caller_id, reason ); display->setStatusStd(StatusProperty::Error, status_name, status_text ); } diff --git a/src/rviz/frame_manager.h b/src/rviz/frame_manager.h index e75b5b61c2..c4c4114428 100644 --- a/src/rviz/frame_manager.h +++ b/src/rviz/frame_manager.h @@ -45,6 +45,7 @@ #ifndef Q_MOC_RUN #include +#include #endif namespace tf @@ -52,6 +53,11 @@ namespace tf class TransformListener; } +namespace tf2_ros +{ +class Buffer; +} + namespace rviz { class Display; @@ -71,10 +77,24 @@ Q_OBJECT SyncApprox }; + /// Default constructor, which will create a tf::TransformListener automatically. + FrameManager(); + /** @brief Constructor * @param tf a pointer to tf::TransformListener (should not be used anywhere else because of thread safety) */ - FrameManager(boost::shared_ptr tf = boost::shared_ptr()); + [[deprecated( + "This constructor signature will be removed in the next version. " + "If you still need to pass a boost::shared_ptr, " + "disable the warning explicitly. " + "When this constructor is removed, a new constructor with a single, " + "optional argument will take a std::pair<> containing a " + "std::shared_ptr and a " + "std::shared_ptr. " + "However, that cannot occur until the use of tf::TransformListener is " + "removed internally." + )]] + explicit FrameManager(boost::shared_ptr tf); /** @brief Destructor. * @@ -171,21 +191,45 @@ Q_OBJECT * based on success or failure of the filter, including appropriate * error messages. */ template + [[deprecated("use a tf2_ros::MessageFilter instead")]] void registerFilterForTransformStatusCheck(tf::MessageFilter* filter, Display* display) { filter->registerCallback(boost::bind(&FrameManager::messageCallback, this, _1, display)); - filter->registerFailureCallback(boost::bind(&FrameManager::failureCallback, this, _1, _2, display)); + filter->registerFailureCallback(boost::bind( + &FrameManager::failureCallback, this, _1, _2, display + )); + } + + /** Connect success and failure callbacks to a tf2_ros::MessageFilter. + * @param filter The tf2_ros::MessageFilter to connect to. + * @param display The Display using the filter. + * + * FrameManager has internal functions for handling success and + * failure of tf2_ros::MessageFilters which call Display::setStatus() + * based on success or failure of the filter, including appropriate + * error messages. */ + template + void registerFilterForTransformStatusCheck(tf2_ros::MessageFilter* filter, Display* display) + { + filter->registerCallback(boost::bind(&FrameManager::messageCallback, this, _1, display)); + filter->registerFailureCallback(boost::bind( + &FrameManager::failureCallback, this, _1, _2, display + )); } /** @brief Return the current fixed frame name. */ const std::string& getFixedFrame() { return fixed_frame_; } /** @brief Return the tf::TransformListener used to receive transform data. */ + [[deprecated("use getTF2BufferPtr() instead")]] tf::TransformListener* getTFClient() { return tf_.get(); } /** @brief Return a boost shared pointer to the tf::TransformListener used to receive transform data. */ + [[deprecated("use getTF2BufferPtr() instead")]] const boost::shared_ptr& getTFClientPtr() { return tf_; } + const std::shared_ptr getTF2BufferPtr() { return tf_->getTF2BufferPtr(); } + /** @brief Create a description of a transform problem. * @param frame_id The name of the frame with issues. * @param stamp The time for which the problem was detected. @@ -195,11 +239,27 @@ Q_OBJECT * * Once a problem has been detected with a given frame or transform, * call this to get an error message describing the problem. */ + [[deprecated("used tf2 version instead")]] std::string discoverFailureReason(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, tf::FilterFailureReason reason); + /** Create a description of a transform problem. + * @param frame_id The name of the frame with issues. + * @param stamp The time for which the problem was detected. + * @param caller_id Dummy parameter, not used. + * @param reason The reason given by the tf2_ros::MessageFilter in its failure callback. + * @return An error message describing the problem. + * + * Once a problem has been detected with a given frame or transform, + * call this to get an error message describing the problem. */ + std::string discoverFailureReason( + const std::string& frame_id, + const ros::Time& stamp, + const std::string& caller_id, + tf2_ros::FilterFailureReason reason); + Q_SIGNALS: /** @brief Emitted whenever the fixed frame changes. */ void fixedFrameChanged(); @@ -217,8 +277,11 @@ Q_OBJECT messageArrived(msg->header.frame_id, msg->header.stamp, authority, display); } - template - void failureCallback(const ros::MessageEvent& msg_evt, tf::FilterFailureReason reason, Display* display) + template + void failureCallback( + const ros::MessageEvent& msg_evt, + TfFilterFailureReasonType reason, + Display* display) { boost::shared_ptr const &msg = msg_evt.getConstMessage(); std::string authority = msg_evt.getPublisherName(); @@ -227,7 +290,34 @@ Q_OBJECT } void messageArrived(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, Display* display); - void messageFailed(const std::string& frame_id, const ros::Time& stamp, const std::string& caller_id, tf::FilterFailureReason reason, Display* display); + + void messageFailedImpl( + const std::string& caller_id, + const std::string& status_text, + Display* display); + + template + void messageFailed( + const std::string& frame_id, + const ros::Time& stamp, + const std::string& caller_id, + TfFilterFailureReasonType reason, + Display* display) + { + // TODO(wjwwood): remove this when only Tf2 is supported +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + + std::string status_text = discoverFailureReason( frame_id, stamp, caller_id, reason ); + +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + + messageFailedImpl(caller_id, status_text, display); + } struct CacheKey { From 19e81d2309892f3d0bd3fd4d4a66a9326e654947 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:18:01 -0700 Subject: [PATCH 03/16] update VisualizationManager to avoid deprecated calls in FrameManager --- src/rviz/visualization_manager.cpp | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/src/rviz/visualization_manager.cpp b/src/rviz/visualization_manager.cpp index 5db0e8a13e..e90c5d21d4 100644 --- a/src/rviz/visualization_manager.cpp +++ b/src/rviz/visualization_manager.cpp @@ -407,7 +407,14 @@ void VisualizationManager::updateFrames() { typedef std::vector V_string; V_string frames; +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif frame_manager_->getTFClient()->getFrameStrings( frames ); +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif // Check the fixed frame to see if it's ok std::string error; @@ -435,7 +442,14 @@ void VisualizationManager::updateFrames() tf::TransformListener* VisualizationManager::getTFClient() const { +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif return frame_manager_->getTFClient(); +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif } std::shared_ptr VisualizationManager::getTF2BufferPtr() const @@ -446,7 +460,14 @@ std::shared_ptr VisualizationManager::getTF2BufferPtr() const void VisualizationManager::resetTime() { root_display_group_->reset(); +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif frame_manager_->getTFClient()->clear(); +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif ros_time_begin_ = ros::Time(); wall_clock_begin_ = ros::WallTime(); From 0f227e5fa7fd1c38389479936545157733b5b571 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:18:48 -0700 Subject: [PATCH 04/16] migrate MessageFilterDisplay to tf2 --- src/rviz/message_filter_display.h | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/src/rviz/message_filter_display.h b/src/rviz/message_filter_display.h index d0384dc14c..39745a69a9 100644 --- a/src/rviz/message_filter_display.h +++ b/src/rviz/message_filter_display.h @@ -34,7 +34,7 @@ #include #include -#include +#include #endif #include "rviz/display_context.h" @@ -72,10 +72,10 @@ protected Q_SLOTS: BoolProperty* unreliable_property_; }; -/** @brief Display subclass using a tf::MessageFilter, templated on the ROS message type. +/** @brief Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type. * * This class brings together some common things used in many Display - * types. It has a tf::MessageFilter to filter incoming messages, and + * types. It has a tf2_ros::MessageFilter to filter incoming messages, and * it handles subscribing and unsubscribing when the display is * enabled or disabled. It also has an Ogre::SceneNode which */ template @@ -98,8 +98,11 @@ class MessageFilterDisplay: public _RosTopicDisplay virtual void onInitialize() { - tf_filter_ = new tf::MessageFilter( *context_->getTFClient(), - fixed_frame_.toStdString(), 10, update_nh_ ); + tf_filter_ = new tf2_ros::MessageFilter( + *context_->getTF2BufferPtr(), + fixed_frame_.toStdString(), + 10, + update_nh_); tf_filter_->connectInput( sub_ ); tf_filter_->registerCallback( boost::bind( &MessageFilterDisplay::incomingMessage, this, _1 )); @@ -201,7 +204,7 @@ class MessageFilterDisplay: public _RosTopicDisplay virtual void processMessage( const typename MessageType::ConstPtr& msg ) = 0; message_filters::Subscriber sub_; - tf::MessageFilter* tf_filter_; + tf2_ros::MessageFilter* tf_filter_; uint32_t messages_received_; }; From ffdfad011c399cd3a9598d5be7bef26d46d9f6b3 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:20:03 -0700 Subject: [PATCH 05/16] migrate image based displays to tf2 --- src/rviz/default_plugin/camera_display.cpp | 15 +++++++++------ src/rviz/default_plugin/camera_display.h | 6 ++++-- src/rviz/default_plugin/image_display.cpp | 1 - src/rviz/image/image_display_base.cpp | 8 +++++++- src/rviz/image/image_display_base.h | 6 +++--- 5 files changed, 23 insertions(+), 13 deletions(-) diff --git a/src/rviz/default_plugin/camera_display.cpp b/src/rviz/default_plugin/camera_display.cpp index 7e6e13042e..82cd980646 100644 --- a/src/rviz/default_plugin/camera_display.cpp +++ b/src/rviz/default_plugin/camera_display.cpp @@ -41,7 +41,8 @@ #include #include -#include + +#include #include "rviz/bit_allocator.h" #include "rviz/frame_manager.h" @@ -82,7 +83,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) @@ -127,8 +128,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_); } } @@ -137,8 +136,12 @@ void CameraDisplay::onInitialize() { ImageDisplayBase::onInitialize(); - caminfo_tf_filter_ = new tf::MessageFilter( *context_->getTFClient(), fixed_frame_.toStdString(), - queue_size_property_->getInt(), update_nh_ ); + caminfo_tf_filter_.reset(new tf2_ros::MessageFilter( + *context_->getTF2BufferPtr(), + fixed_frame_.toStdString(), + queue_size_property_->getInt(), + update_nh_ + )); bg_scene_node_ = scene_node_->createChildSceneNode(); fg_scene_node_ = scene_node_->createChildSceneNode(); diff --git a/src/rviz/default_plugin/camera_display.h b/src/rviz/default_plugin/camera_display.h index 222e34163e..53c9123289 100644 --- a/src/rviz/default_plugin/camera_display.h +++ b/src/rviz/default_plugin/camera_display.h @@ -30,6 +30,8 @@ #ifndef RVIZ_CAMERA_DISPLAY_H #define RVIZ_CAMERA_DISPLAY_H +#include + #include #ifndef Q_MOC_RUN @@ -40,7 +42,7 @@ # include # include -# include +# include # include "rviz/image/image_display_base.h" # include "rviz/image/ros_image_texture.h" @@ -126,7 +128,7 @@ private Q_SLOTS: Ogre::MaterialPtr fg_material_; message_filters::Subscriber caminfo_sub_; - tf::MessageFilter* caminfo_tf_filter_; + std::unique_ptr> caminfo_tf_filter_; FloatProperty* alpha_property_; EnumProperty* image_position_property_; diff --git a/src/rviz/default_plugin/image_display.cpp b/src/rviz/default_plugin/image_display.cpp index 4baee047ce..f123f987b7 100644 --- a/src/rviz/default_plugin/image_display.cpp +++ b/src/rviz/default_plugin/image_display.cpp @@ -42,7 +42,6 @@ #include #include -#include #include "rviz/display_context.h" #include "rviz/frame_manager.h" diff --git a/src/rviz/image/image_display_base.cpp b/src/rviz/image/image_display_base.cpp index 09719bcd12..5a7042a903 100644 --- a/src/rviz/image/image_display_base.cpp +++ b/src/rviz/image/image_display_base.cpp @@ -176,7 +176,13 @@ void ImageDisplayBase::subscribe() } else { - tf_filter_.reset( new tf::MessageFilter(*sub_, (tf::Transformer&)*(context_->getTFClient()), targetFrame_, (uint32_t)queue_size_property_->getInt(), update_nh_)); + tf_filter_.reset(new tf2_ros::MessageFilter( + *sub_, + *context_->getTF2BufferPtr(), + targetFrame_, + queue_size_property_->getInt(), + update_nh_ + )); tf_filter_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, _1)); } } diff --git a/src/rviz/image/image_display_base.h b/src/rviz/image/image_display_base.h index 8e5d600429..005888d853 100644 --- a/src/rviz/image/image_display_base.h +++ b/src/rviz/image/image_display_base.h @@ -33,7 +33,7 @@ #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829 # include -# include +# include # include # include @@ -53,7 +53,7 @@ namespace rviz /** @brief Display subclass for subscribing and displaying to image messages. * * This class brings together some common things used for subscribing and displaying image messages in Display - * types. It has a tf::MessageFilter and image_tranport::SubscriberFilter to filter incoming image messages, and + * types. It has a tf2_ros::MessageFilter and image_tranport::SubscriberFilter to filter incoming image messages, and * it handles subscribing and unsubscribing when the display is * enabled or disabled. */ @@ -111,7 +111,7 @@ protected Q_SLOTS: boost::scoped_ptr it_; boost::shared_ptr sub_; - boost::shared_ptr > tf_filter_; + boost::shared_ptr > tf_filter_; std::string targetFrame_; From 2dc400d68e2d7813f0801f0164553de4349048f8 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:20:39 -0700 Subject: [PATCH 06/16] migrate DepthCloudDisplay to tf2 --- src/rviz/default_plugin/depth_cloud_display.cpp | 11 ++++++++--- src/rviz/default_plugin/depth_cloud_display.h | 4 ++-- 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/src/rviz/default_plugin/depth_cloud_display.cpp b/src/rviz/default_plugin/depth_cloud_display.cpp index b60f9febb5..a29ee50415 100644 --- a/src/rviz/default_plugin/depth_cloud_display.cpp +++ b/src/rviz/default_plugin/depth_cloud_display.cpp @@ -39,7 +39,7 @@ #include "rviz/properties/int_property.h" #include "rviz/frame_manager.h" -#include +#include #include #include @@ -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(*depthmap_sub_, *context_->getTFClient(), fixed_frame_.toStdString(), queue_size_, threaded_nh_)); + depthmap_tf_filter_.reset(new tf2_ros::MessageFilter( + *depthmap_sub_, + *context_->getTF2BufferPtr(), + fixed_frame_.toStdString(), + queue_size_, + threaded_nh_ + )); // subscribe to CameraInfo topic std::string info_topic = image_transport::getCameraInfoTopic(depthmap_topic); diff --git a/src/rviz/default_plugin/depth_cloud_display.h b/src/rviz/default_plugin/depth_cloud_display.h index 51a4be3e84..4d455a536d 100644 --- a/src/rviz/default_plugin/depth_cloud_display.h +++ b/src/rviz/default_plugin/depth_cloud_display.h @@ -40,7 +40,7 @@ # include # include # include -# include +# include # include "rviz/properties/enum_property.h" # include "rviz/properties/float_property.h" @@ -181,7 +181,7 @@ protected Q_SLOTS: // ROS image subscription & synchronization boost::scoped_ptr depthmap_it_; boost::shared_ptr depthmap_sub_; - boost::shared_ptr > depthmap_tf_filter_; + boost::shared_ptr > depthmap_tf_filter_; boost::scoped_ptr rgb_it_; boost::shared_ptr rgb_sub_; boost::shared_ptr > cam_info_sub_; From 8ebfd677dc9c380f137b718373642b4ec0cee492 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:21:27 -0700 Subject: [PATCH 07/16] suppress deprecation warnings in EffortDisplay --- src/rviz/default_plugin/effort_display.cpp | 2 -- src/rviz/default_plugin/effort_display.h | 23 +++++++++++++++++++++- 2 files changed, 22 insertions(+), 3 deletions(-) diff --git a/src/rviz/default_plugin/effort_display.cpp b/src/rviz/default_plugin/effort_display.cpp index d50e53a58b..d035722e6b 100644 --- a/src/rviz/default_plugin/effort_display.cpp +++ b/src/rviz/default_plugin/effort_display.cpp @@ -1,8 +1,6 @@ #include #include -#include - #include #include #include diff --git a/src/rviz/default_plugin/effort_display.h b/src/rviz/default_plugin/effort_display.h index c408421b98..d53d8dabc5 100644 --- a/src/rviz/default_plugin/effort_display.h +++ b/src/rviz/default_plugin/effort_display.h @@ -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() From 89b51e7a0ddcc35f0aba25580084c66f9d90623b Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:21:54 -0700 Subject: [PATCH 08/16] suppress deprecation warnings in GridCellsDisplay --- .../default_plugin/grid_cells_display.cpp | 30 +++++++++++++++++-- 1 file changed, 27 insertions(+), 3 deletions(-) diff --git a/src/rviz/default_plugin/grid_cells_display.cpp b/src/rviz/default_plugin/grid_cells_display.cpp index 1d5a23c25d..e3ff73412a 100644 --- a/src/rviz/default_plugin/grid_cells_display.cpp +++ b/src/rviz/default_plugin/grid_cells_display.cpp @@ -34,7 +34,6 @@ #include #include -#include #include "rviz/frame_manager.h" #include "rviz/ogre_helpers/arrow.h" @@ -73,8 +72,23 @@ GridCellsDisplay::GridCellsDisplay() void GridCellsDisplay::onInitialize() { - tf_filter_ = new tf::MessageFilter( *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( + *tf_client, + fixed_frame_.toStdString(), + 10, + update_nh_); static int count = 0; std::stringstream ss; ss << "PolyLine" << count++; @@ -88,7 +102,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() From 2d4e3454cc0cc713eed3c1a40dd1ff060ce4d81b Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:22:24 -0700 Subject: [PATCH 09/16] suppress deprecation warnings in InteractiveMarkerDisplay --- src/rviz/default_plugin/interactive_marker_display.cpp | 10 ++++++++++ .../interactive_markers/interactive_marker.cpp | 10 ++++++++++ 2 files changed, 20 insertions(+) diff --git a/src/rviz/default_plugin/interactive_marker_display.cpp b/src/rviz/default_plugin/interactive_marker_display.cpp index f3efe8b95b..a5cb23c744 100644 --- a/src/rviz/default_plugin/interactive_marker_display.cpp +++ b/src/rviz/default_plugin/interactive_marker_display.cpp @@ -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 ) ); diff --git a/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp b/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp index 709fbdc373..8029b9df95 100644 --- a/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp +++ b/src/rviz/default_plugin/interactive_markers/interactive_marker.cpp @@ -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; From 8bda93952419eb089d556dbd8f716e375154684c Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:22:40 -0700 Subject: [PATCH 10/16] suppress deprecation warnings in LaserScanDisplay --- src/rviz/default_plugin/laser_scan_display.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/src/rviz/default_plugin/laser_scan_display.cpp b/src/rviz/default_plugin/laser_scan_display.cpp index 5e433b6feb..d4c0909df6 100644 --- a/src/rviz/default_plugin/laser_scan_display.cpp +++ b/src/rviz/default_plugin/laser_scan_display.cpp @@ -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) From e8fc4758d525fe5f5f376d8e6ddaf4c8aebc492e Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:23:16 -0700 Subject: [PATCH 11/16] suppress deprecation warnings in MarkerDisplay --- src/rviz/default_plugin/marker_display.cpp | 29 +++++++++++++++++-- .../default_plugin/markers/arrow_marker.cpp | 2 -- .../default_plugin/markers/marker_base.cpp | 3 -- 3 files changed, 27 insertions(+), 7 deletions(-) diff --git a/src/rviz/default_plugin/marker_display.cpp b/src/rviz/default_plugin/marker_display.cpp index df332f8b38..461b2bde0c 100644 --- a/src/rviz/default_plugin/marker_display.cpp +++ b/src/rviz/default_plugin/marker_display.cpp @@ -73,7 +73,18 @@ MarkerDisplay::MarkerDisplay() void MarkerDisplay::onInitialize() { - tf_filter_ = new tf::MessageFilter( *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::MessageFilter( *tf_client, fixed_frame_.toStdString(), queue_size_property_->getInt(), update_nh_ ); @@ -272,7 +283,21 @@ void MarkerDisplay::failedMarker(const ros::MessageEventprocessMessage(marker); } std::string authority = marker_evt.getPublisherName(); - std::string error = context_->getFrameManager()->discoverFailureReason(marker->header.frame_id, marker->header.stamp, authority, reason); +// TODO(wjwwood): remove this and use tf2 interface instead +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + + std::string error = context_->getFrameManager()->discoverFailureReason( + marker->header.frame_id, + marker->header.stamp, + authority, + reason); + +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif setMarkerStatus(MarkerID(marker->ns, marker->id), StatusProperty::Error, error); } diff --git a/src/rviz/default_plugin/markers/arrow_marker.cpp b/src/rviz/default_plugin/markers/arrow_marker.cpp index 5ed0add4b8..67d271eb05 100644 --- a/src/rviz/default_plugin/markers/arrow_marker.cpp +++ b/src/rviz/default_plugin/markers/arrow_marker.cpp @@ -33,8 +33,6 @@ #include #include -#include - #include "rviz/default_plugin/marker_display.h" #include "rviz/default_plugin/markers/marker_selection_handler.h" #include "rviz/display_context.h" diff --git a/src/rviz/default_plugin/markers/marker_base.cpp b/src/rviz/default_plugin/markers/marker_base.cpp index b657ab4fc4..dc51972c4c 100644 --- a/src/rviz/default_plugin/markers/marker_base.cpp +++ b/src/rviz/default_plugin/markers/marker_base.cpp @@ -40,9 +40,6 @@ #include #include -#include -#include - namespace rviz { From c7f6a4a29a28c08989680a4c52e74c1cfb305bb3 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:24:33 -0700 Subject: [PATCH 12/16] suppress deprecation warnings in TfDisplay --- src/rviz/default_plugin/tf_display.cpp | 33 ++++++++++++++++++++++- src/rviz/properties/tf_frame_property.cpp | 10 +++++++ 2 files changed, 42 insertions(+), 1 deletion(-) diff --git a/src/rviz/default_plugin/tf_display.cpp b/src/rviz/default_plugin/tf_display.cpp index ef35876332..a792de7ffe 100644 --- a/src/rviz/default_plugin/tf_display.cpp +++ b/src/rviz/default_plugin/tf_display.cpp @@ -368,7 +368,17 @@ void TFDisplay::updateFrames() { typedef std::vector V_string; V_string frames; + // TODO(wjwwood): remove this and use tf2 interface instead +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + context_->getTFClient()->getFrameStrings( frames ); + +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif std::sort(frames.begin(), frames.end()); S_FrameInfo current_frames; @@ -494,8 +504,18 @@ Ogre::ColourValue lerpColor(const Ogre::ColourValue& start, const Ogre::ColourVa void TFDisplay::updateFrame( FrameInfo* frame ) { + // TODO(wjwwood): remove this and use tf2 interface instead +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + tf::TransformListener* tf = context_->getTFClient(); +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + // Check last received time so we can grey out/fade out frames that have stopped being published ros::Time latest_time; tf->getLatestCommonTime( fixed_frame_.toStdString(), frame->name_, latest_time, 0 ); @@ -617,7 +637,18 @@ void TFDisplay::updateFrame( FrameInfo* frame ) tf::StampedTransform transform; try { - context_->getFrameManager()->getTFClientPtr()->lookupTransform(frame->parent_,frame->name_,ros::Time(0),transform); + // 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_->getFrameManager()->getTFClientPtr(); + +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + tf_client->lookupTransform(frame->parent_,frame->name_,ros::Time(0),transform); } catch(tf::TransformException& e) { diff --git a/src/rviz/properties/tf_frame_property.cpp b/src/rviz/properties/tf_frame_property.cpp index fb3229057b..c8dbb40c97 100644 --- a/src/rviz/properties/tf_frame_property.cpp +++ b/src/rviz/properties/tf_frame_property.cpp @@ -86,7 +86,17 @@ void TfFrameProperty::setFrameManager( FrameManager* frame_manager ) void TfFrameProperty::fillFrameList() { std::vector std_frames; + // TODO(wjwwood): remove this and use tf2 interface instead +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + frame_manager_->getTFClient()->getFrameStrings( std_frames ); + +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif std::sort( std_frames.begin(), std_frames.end() ); clearOptions(); From 10d14ee108a9ff0ef930dd2658db4b411e1db5ae Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:26:12 -0700 Subject: [PATCH 13/16] [style] avoid `emit` variable name as it is used in Qt --- src/rviz/frame_manager.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rviz/frame_manager.cpp b/src/rviz/frame_manager.cpp index 9645e41a7e..6c01b53b32 100644 --- a/src/rviz/frame_manager.cpp +++ b/src/rviz/frame_manager.cpp @@ -101,17 +101,17 @@ void FrameManager::update() void FrameManager::setFixedFrame(const std::string& frame) { - bool emit = false; + bool should_emit = false; { boost::mutex::scoped_lock lock(cache_mutex_); if( fixed_frame_ != frame ) { fixed_frame_ = frame; cache_.clear(); - emit = true; + should_emit = true; } } - if( emit ) + if( should_emit ) { // This emission must be kept outside of the mutex lock to avoid deadlocks. Q_EMIT fixedFrameChanged(); From a58e0dcef207b8501646ccc9136e58587bdf32d3 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:26:50 -0700 Subject: [PATCH 14/16] [style] remove unused header includes --- src/rviz/default_plugin/map_display.cpp | 2 -- src/rviz/default_plugin/odometry_display.h | 1 - src/rviz/default_plugin/path_display.cpp | 2 -- src/rviz/default_plugin/point_cloud_common.cpp | 2 -- src/rviz/default_plugin/point_cloud_display.cpp | 2 -- src/rviz/default_plugin/robot_model_display.cpp | 2 -- 6 files changed, 11 deletions(-) diff --git a/src/rviz/default_plugin/map_display.cpp b/src/rviz/default_plugin/map_display.cpp index 449042cef8..f4e99480f5 100644 --- a/src/rviz/default_plugin/map_display.cpp +++ b/src/rviz/default_plugin/map_display.cpp @@ -39,8 +39,6 @@ #include -#include - #include "rviz/frame_manager.h" #include "rviz/ogre_helpers/custom_parameter_indices.h" #include "rviz/ogre_helpers/grid.h" diff --git a/src/rviz/default_plugin/odometry_display.h b/src/rviz/default_plugin/odometry_display.h index dc7629636d..49b3bc0901 100644 --- a/src/rviz/default_plugin/odometry_display.h +++ b/src/rviz/default_plugin/odometry_display.h @@ -38,7 +38,6 @@ #ifndef Q_MOC_RUN #include -#include #endif #include "rviz/message_filter_display.h" diff --git a/src/rviz/default_plugin/path_display.cpp b/src/rviz/default_plugin/path_display.cpp index b2c7201171..228ac22eb7 100644 --- a/src/rviz/default_plugin/path_display.cpp +++ b/src/rviz/default_plugin/path_display.cpp @@ -35,8 +35,6 @@ #include #include -#include - #include "rviz/display_context.h" #include "rviz/frame_manager.h" #include "rviz/properties/enum_property.h" diff --git a/src/rviz/default_plugin/point_cloud_common.cpp b/src/rviz/default_plugin/point_cloud_common.cpp index 4fcfb68529..a64e3aa521 100644 --- a/src/rviz/default_plugin/point_cloud_common.cpp +++ b/src/rviz/default_plugin/point_cloud_common.cpp @@ -35,8 +35,6 @@ #include -#include - #include #include "rviz/default_plugin/point_cloud_transformer.h" diff --git a/src/rviz/default_plugin/point_cloud_display.cpp b/src/rviz/default_plugin/point_cloud_display.cpp index bcdc34dcb5..f543430b89 100644 --- a/src/rviz/default_plugin/point_cloud_display.cpp +++ b/src/rviz/default_plugin/point_cloud_display.cpp @@ -32,8 +32,6 @@ #include -#include - #include "rviz/default_plugin/point_cloud_common.h" #include "rviz/display_context.h" #include "rviz/frame_manager.h" diff --git a/src/rviz/default_plugin/robot_model_display.cpp b/src/rviz/default_plugin/robot_model_display.cpp index 4c9cebd931..2776286ec0 100644 --- a/src/rviz/default_plugin/robot_model_display.cpp +++ b/src/rviz/default_plugin/robot_model_display.cpp @@ -33,8 +33,6 @@ #include #include -#include - #include "rviz/display_context.h" #include "rviz/robot/robot.h" #include "rviz/robot/tf_link_updater.h" From f6a98be9d02bc280985092bdf44ffaca3e13ecfc Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 8 May 2018 19:27:15 -0700 Subject: [PATCH 15/16] [macos] suppress warnings on macOS --- src/rviz/default_plugin/axes_display.cpp | 11 +++++++++ src/rviz/default_plugin/camera_display.cpp | 10 ++++++++ .../default_plugin/grid_cells_display.cpp | 13 ++++++++++ src/rviz/default_plugin/image_display.cpp | 15 ++++++++++++ src/rviz/frame_manager.h | 12 ++++++++++ src/rviz/ogre_helpers/point_cloud.h | 24 +++++++++++++++++++ src/rviz/ogre_helpers/render_system.cpp | 11 +++++++++ src/rviz/ogre_helpers/render_system.h | 11 +++++++++ 8 files changed, 107 insertions(+) diff --git a/src/rviz/default_plugin/axes_display.cpp b/src/rviz/default_plugin/axes_display.cpp index 6f44578ac9..7be6014298 100644 --- a/src/rviz/default_plugin/axes_display.cpp +++ b/src/rviz/default_plugin/axes_display.cpp @@ -29,9 +29,20 @@ #include +#ifndef _WIN32 +# pragma GCC diagnostic push +# ifdef __clang__ +# pragma clang diagnostic ignored "-W#warnings" +# endif +#endif + #include #include +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + #include "rviz/display_context.h" #include "rviz/frame_manager.h" #include "rviz/ogre_helpers/axes.h" diff --git a/src/rviz/default_plugin/camera_display.cpp b/src/rviz/default_plugin/camera_display.cpp index 82cd980646..6d83c3a743 100644 --- a/src/rviz/default_plugin/camera_display.cpp +++ b/src/rviz/default_plugin/camera_display.cpp @@ -29,6 +29,13 @@ #include +#ifndef _WIN32 +# pragma GCC diagnostic push +# ifdef __clang__ +# pragma clang diagnostic ignored "-W#warnings" +# endif +#endif + #include #include #include @@ -41,6 +48,9 @@ #include #include +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif #include diff --git a/src/rviz/default_plugin/grid_cells_display.cpp b/src/rviz/default_plugin/grid_cells_display.cpp index e3ff73412a..4b4dae04d1 100644 --- a/src/rviz/default_plugin/grid_cells_display.cpp +++ b/src/rviz/default_plugin/grid_cells_display.cpp @@ -29,11 +29,24 @@ #include +#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 #include #include #include +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif #include "rviz/frame_manager.h" #include "rviz/ogre_helpers/arrow.h" diff --git a/src/rviz/default_plugin/image_display.cpp b/src/rviz/default_plugin/image_display.cpp index f123f987b7..dd1b44f5db 100644 --- a/src/rviz/default_plugin/image_display.cpp +++ b/src/rviz/default_plugin/image_display.cpp @@ -29,6 +29,16 @@ #include +#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 #include #include @@ -42,6 +52,9 @@ #include #include +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif #include "rviz/display_context.h" #include "rviz/frame_manager.h" @@ -188,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(); diff --git a/src/rviz/frame_manager.h b/src/rviz/frame_manager.h index c4c4114428..6d6422c4b9 100644 --- a/src/rviz/frame_manager.h +++ b/src/rviz/frame_manager.h @@ -36,9 +36,21 @@ #include +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wpedantic" +# ifdef __clang__ +# pragma clang diagnostic ignored "-Wdeprecated-register" +# endif +#endif + #include #include +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + #include #include diff --git a/src/rviz/ogre_helpers/point_cloud.h b/src/rviz/ogre_helpers/point_cloud.h index 88128685ac..93fcfed219 100644 --- a/src/rviz/ogre_helpers/point_cloud.h +++ b/src/rviz/ogre_helpers/point_cloud.h @@ -30,6 +30,16 @@ #ifndef OGRE_TOOLS_OGRE_POINT_CLOUD_H #define OGRE_TOOLS_OGRE_POINT_CLOUD_H +#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 #include #include @@ -41,6 +51,10 @@ #include #include +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + #include #include @@ -68,7 +82,17 @@ class PointCloudRenderable : public Ogre::SimpleRenderable PointCloudRenderable(PointCloud* parent, int num_points, bool use_tex_coords); ~PointCloudRenderable(); +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Woverloaded-virtual" +#endif + Ogre::RenderOperation* getRenderOperation() { return &mRenderOp; } + +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + Ogre::HardwareVertexBufferSharedPtr getBuffer(); virtual Ogre::Real getBoundingRadius(void) const; diff --git a/src/rviz/ogre_helpers/render_system.cpp b/src/rviz/ogre_helpers/render_system.cpp index 3b92c94acc..c8d95f21b4 100644 --- a/src/rviz/ogre_helpers/render_system.cpp +++ b/src/rviz/ogre_helpers/render_system.cpp @@ -50,12 +50,23 @@ #include // This dependency should be moved out of here, it is just used for a search path. #include +#ifndef _WIN32 +# pragma GCC diagnostic push +# ifdef __clang__ +# pragma clang diagnostic ignored "-W#warnings" +# endif +#endif + #include #include #if ((OGRE_VERSION_MAJOR == 1 && OGRE_VERSION_MINOR >= 9) || OGRE_VERSION_MAJOR >= 2 ) #include #endif +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + #include "rviz/env_config.h" #include "rviz/ogre_helpers/ogre_logging.h" diff --git a/src/rviz/ogre_helpers/render_system.h b/src/rviz/ogre_helpers/render_system.h index 5da744adf8..c9432379cd 100644 --- a/src/rviz/ogre_helpers/render_system.h +++ b/src/rviz/ogre_helpers/render_system.h @@ -29,9 +29,20 @@ #ifndef RENDER_SYSTEM_H #define RENDER_SYSTEM_H +#ifndef _WIN32 +# pragma GCC diagnostic push +# ifdef __clang__ +# pragma clang diagnostic ignored "-W#warnings" +# endif +#endif + #include #include +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + namespace Ogre { class OverlaySystem; From ac1c2b1d5d828d2ca231dd19c58642a8428ccc26 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Wed, 9 May 2018 17:26:11 -0700 Subject: [PATCH 16/16] suppress missed use of deprecated constructor internally --- src/rviz/visualization_manager.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/rviz/visualization_manager.cpp b/src/rviz/visualization_manager.cpp index e90c5d21d4..e7f2ffbdd9 100644 --- a/src/rviz/visualization_manager.cpp +++ b/src/rviz/visualization_manager.cpp @@ -146,8 +146,17 @@ VisualizationManager::VisualizationManager( // visibility_bit_allocator_ is listed after default_visibility_bit_ (and thus initialized later be default): default_visibility_bit_ = visibility_bit_allocator_.allocBit(); +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + frame_manager_ = new FrameManager(tf); +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif + render_panel->setAutoRender(false); private_->threaded_nh_.setCallbackQueue(&private_->threaded_queue_);