Skip to content

Commit

Permalink
deprecate tf in favor of tf2 in FrameManager
Browse files Browse the repository at this point in the history
  • Loading branch information
wjwwood committed May 9, 2018
1 parent b1bb6a2 commit 7ee47f3
Show file tree
Hide file tree
Showing 2 changed files with 144 additions and 9 deletions.
53 changes: 49 additions & 4 deletions src/rviz/frame_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<tf::TransformListener>())
{}

#ifndef _WIN32
# pragma GCC diagnostic pop
#endif

FrameManager::FrameManager(boost::shared_ptr<tf::TransformListener> tf)
{
if (!tf) tf_.reset(new tf::TransformListener(ros::NodeHandle(), ros::Duration(10*60), true));
Expand Down Expand Up @@ -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)
{
Expand All @@ -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 );
}
Expand Down
100 changes: 95 additions & 5 deletions src/rviz/frame_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,13 +45,19 @@

#ifndef Q_MOC_RUN
#include <tf/message_filter.h>
#include <tf2_ros/message_filter.h>
#endif

namespace tf
{
class TransformListener;
}

namespace tf2_ros
{
class Buffer;
}

namespace rviz
{
class Display;
Expand All @@ -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::TransformListener> tf = boost::shared_ptr<tf::TransformListener>());
[[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 constructor with a single, "
"optional argument 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."
)]]
explicit FrameManager(boost::shared_ptr<tf::TransformListener> tf);

/** @brief Destructor.
*
Expand Down Expand Up @@ -171,21 +191,45 @@ Q_OBJECT
* based on success or failure of the filter, including appropriate
* error messages. */
template<class M>
[[deprecated("use a tf2_ros::MessageFilter instead")]]
void registerFilterForTransformStatusCheck(tf::MessageFilter<M>* filter, Display* display)
{
filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
filter->registerFailureCallback(boost::bind(&FrameManager::failureCallback<M>, this, _1, _2, display));
filter->registerFailureCallback(boost::bind(
&FrameManager::failureCallback<M, tf::FilterFailureReason>, 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<class M>
void registerFilterForTransformStatusCheck(tf2_ros::MessageFilter<M>* filter, Display* display)
{
filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
filter->registerFailureCallback(boost::bind(
&FrameManager::failureCallback<M, tf2_ros::FilterFailureReason>, 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<tf::TransformListener>& getTFClientPtr() { return tf_; }

const std::shared_ptr<tf2_ros::Buffer> 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.
Expand All @@ -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();
Expand All @@ -217,8 +277,11 @@ Q_OBJECT
messageArrived(msg->header.frame_id, msg->header.stamp, authority, display);
}

template<class M>
void failureCallback(const ros::MessageEvent<M const>& msg_evt, tf::FilterFailureReason reason, Display* display)
template<class M, class TfFilterFailureReasonType>
void failureCallback(
const ros::MessageEvent<M const>& msg_evt,
TfFilterFailureReasonType reason,
Display* display)
{
boost::shared_ptr<M const> const &msg = msg_evt.getConstMessage();
std::string authority = msg_evt.getPublisherName();
Expand All @@ -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<class TfFilterFailureReasonType>
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
{
Expand Down

0 comments on commit 7ee47f3

Please sign in to comment.