Skip to content

Commit

Permalink
Add tf2 Buffer accessor in FrameManager
Browse files Browse the repository at this point in the history
  • Loading branch information
IanTheEngineer committed Apr 22, 2018
1 parent 7995873 commit f347dd6
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -136,6 +136,7 @@ find_package(catkin REQUIRED
std_msgs
std_srvs
tf
tf2_ros
urdf
visualization_msgs
urdfdom_headers
Expand Down
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
<build_depend>std_msgs</build_depend>
<build_depend>std_srvs</build_depend>
<build_depend>tf</build_depend>
<build_depend>tf2_ros</build_depend>
<build_depend>tinyxml</build_depend>
<build_depend>urdf</build_depend>
<build_depend>visualization_msgs</build_depend>
Expand Down Expand Up @@ -77,6 +78,7 @@
<run_depend>std_msgs</run_depend>
<run_depend>std_srvs</run_depend>
<run_depend>tf</run_depend>
<run_depend>tf2_ros</run_depend>
<run_depend>tinyxml</run_depend>
<run_depend>urdf</run_depend>
<run_depend>visualization_msgs</run_depend>
Expand Down
5 changes: 5 additions & 0 deletions src/rviz/frame_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@
#include "properties/property.h"

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

#include <std_msgs/Float32.h>
Expand All @@ -44,6 +46,9 @@ FrameManager::FrameManager(boost::shared_ptr<tf::TransformListener> tf)
if (!tf) tf_.reset(new tf::TransformListener(ros::NodeHandle(), ros::Duration(10*60), true));
else tf_ = tf;

tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(ros::Duration(10*60));
tf2_listener_.reset(new tf2_ros::TransformListener(*tf2_buffer_));

setSyncMode( SyncOff );
setPause(false);
}
Expand Down
11 changes: 11 additions & 0 deletions src/rviz/frame_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,12 @@ namespace tf
class TransformListener;
}

namespace tf2_ros
{
class Buffer;
class TransformListener;
}

namespace rviz
{
class Display;
Expand Down Expand Up @@ -186,6 +192,9 @@ Q_OBJECT
/** @brief Return a boost shared pointer to the tf::TransformListener used to receive transform data. */
const boost::shared_ptr<tf::TransformListener>& getTFClientPtr() { return tf_; }

/** @brief Return a shared pointer to the tf2_ros::Buffer object used to receive tf2 transform data. */
const std::shared_ptr<tf2_ros::Buffer> getTFBufferPtr() { return tf2_buffer_; };

/** @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 Down Expand Up @@ -266,6 +275,8 @@ Q_OBJECT
M_Cache cache_;

boost::shared_ptr<tf::TransformListener> tf_;
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
std::unique_ptr<tf2_ros::TransformListener> tf2_listener_;
std::string fixed_frame_;

bool pause_;
Expand Down

0 comments on commit f347dd6

Please sign in to comment.