Skip to content

Commit

Permalink
deprecate tf in favor of tf2 in VisualizationManager
Browse files Browse the repository at this point in the history
  • Loading branch information
wjwwood committed May 9, 2018
1 parent 71c66a6 commit b1bb6a2
Show file tree
Hide file tree
Showing 3 changed files with 56 additions and 3 deletions.
12 changes: 11 additions & 1 deletion src/rviz/display_context.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,8 @@
#ifndef DISPLAY_CONTEXT_H
#define DISPLAY_CONTEXT_H

#include <stdint.h> // for uint64_t
#include <cstdint> // for uint64_t
#include <memory>

#include <QObject>
#include <QString>
Expand All @@ -51,6 +52,11 @@ namespace tf
class TransformListener;
}

namespace tf2_ros
{
class Buffer;
}

namespace rviz
{

Expand Down Expand Up @@ -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<tf2_ros::Buffer> getTF2BufferPtr() const = 0;

/** @brief Return the fixed frame name. */
virtual QString getFixedFrame() const = 0;

Expand Down
21 changes: 20 additions & 1 deletion src/rviz/visualization_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,21 @@ class VisualizationManagerPrivate
boost::mutex render_mutex_;
};

VisualizationManager::VisualizationManager( RenderPanel* render_panel, WindowManagerInterface* wm, boost::shared_ptr<tf::TransformListener> 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<tf::TransformListener>())
{}
#ifndef _WIN32
# pragma GCC diagnostic pop
#endif

VisualizationManager::VisualizationManager(
RenderPanel* render_panel,
WindowManagerInterface* wm,
boost::shared_ptr<tf::TransformListener> tf)
: ogre_root_( Ogre::Root::getSingletonPtr() )
, update_timer_(0)
, shutting_down_(false)
Expand Down Expand Up @@ -424,6 +438,11 @@ tf::TransformListener* VisualizationManager::getTFClient() const
return frame_manager_->getTFClient();
}

std::shared_ptr<tf2_ros::Buffer> VisualizationManager::getTF2BufferPtr() const
{
return frame_manager_->getTF2BufferPtr();
}

void VisualizationManager::resetTime()
{
root_display_group_->reset();
Expand Down
26 changes: 25 additions & 1 deletion src/rviz/visualization_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -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::TransformListener> tf = boost::shared_ptr<tf::TransformListener>() );
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<tf::TransformListener>, "
"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<tf2_ros::Buffer> and a "
"std::shared_ptr<tf2_ros::TransformListener>. "
"However, that cannot occur until the use of tf::TransformListener is "
"removed internally."
)]]
VisualizationManager(
RenderPanel* render_panel,
WindowManagerInterface* wm,
boost::shared_ptr<tf::TransformListener> tf);

/**
* \brief Destructor
Expand Down Expand Up @@ -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<tf2_ros::Buffer> getTF2BufferPtr() const;

/**
* @brief Returns the Ogre::SceneManager used for the main RenderPanel.
*/
Expand Down

0 comments on commit b1bb6a2

Please sign in to comment.