37 #ifndef TF2_ROS_BUFFER_CLIENT_H_ 38 #define TF2_ROS_BUFFER_CLIENT_H_ 42 #include <tf2_msgs/LookupTransformAction.h> 74 virtual geometry_msgs::TransformStamped
75 lookupTransform(
const std::string& target_frame,
const std::string& source_frame,
90 virtual geometry_msgs::TransformStamped
92 const std::string& source_frame,
const ros::Time& source_time,
104 canTransform(
const std::string& target_frame,
const std::string& source_frame,
119 const std::string& source_frame,
const ros::Time& source_time,
132 geometry_msgs::TransformStamped
processGoal(
const tf2_msgs::LookupTransformGoal& goal)
const;
133 geometry_msgs::TransformStamped
processResult(
const tf2_msgs::LookupTransformResult& result)
const;
geometry_msgs::TransformStamped processResult(const tf2_msgs::LookupTransformResult &result) const
actionlib::SimpleActionClient< tf2_msgs::LookupTransformAction > LookupActionClient
Abstract interface for wrapping tf2::BufferCore in a ROS-based API. Implementations include tf2_ros::...
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
bool waitForServer(const ros::Duration &timeout=ros::Duration(0))
Block until the action server is ready to respond to requests.
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout=ros::Duration(0.0), std::string *errstr=NULL) const
Test if a transform is possible.
ros::Duration timeout_padding_
LookupActionClient client_
geometry_msgs::TransformStamped processGoal(const tf2_msgs::LookupTransformGoal &goal) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout=ros::Duration(0.0)) const
Get the transform between two frames by frame ID.
BufferClient(std::string ns, double check_frequency=10.0, ros::Duration timeout_padding=ros::Duration(2.0))
BufferClient constructor.
Action client-based implementation of the tf2_ros::BufferInterface abstract data type.