Go to the documentation of this file.
38 #ifndef TF2_ROS_BUFFER_CLIENT_H_
39 #define TF2_ROS_BUFFER_CLIENT_H_
41 #include <tf2_ros/buffer_interface.h>
43 #include <tf2_msgs/LookupTransformAction.h>
53 class BufferClient :
public BufferInterface
93 const std::string& source_frame,
const ros::Time& source_time,
120 const std::string& source_frame,
const ros::Time& source_time,
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
ros::Duration timeout_padding_
virtual bool canTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout=ros::Duration(0.0), std::string *errstr=NULL) const
geometry_msgs::TransformStamped processGoal(const tf2_msgs::LookupTransformGoal &goal) const
actionlib::SimpleActionClient< tf2_msgs::LookupTransformAction > LookupActionClient
BufferClient(std::string ns, double check_frequency=10.0, ros::Duration timeout_padding=ros::Duration(2.0))
LookupActionClient client_
geometry_msgs::TransformStamped processResult(const tf2_msgs::LookupTransformResult &result) const
bool waitForServer(const ros::Duration &timeout=ros::Duration(0))
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout=ros::Duration(0.0)) const
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:07