|
| Buffer (ros::Duration cache_time=ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug=false) |
| Constructor for a Buffer object. More...
|
|
virtual bool | canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const |
| Test if a transform is possible. More...
|
|
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, std::string *errstr=NULL) const |
| Test if a transform is possible. More...
|
|
virtual geometry_msgs::TransformStamped | lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const |
| Get the transform between two frames by frame ID. More...
|
|
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) const |
| Get the transform between two frames by frame ID assuming fixed frame. More...
|
|
template<class T > |
T & | transform (const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const |
| Transform an input into the target frame. This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). More...
|
|
template<class T > |
T | transform (const T &in, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const |
| Transform an input into the target frame. This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). More...
|
|
template<class A , class B > |
B & | transform (const A &in, B &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const |
| Transform an input into the target frame and convert to a specified output type. It is templated on two types: the type of the input object and the type of the transformed output. For example, the template types could be Transform, Pose, Vector, or Quaternion messages type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. More...
|
|
template<class T > |
T & | transform (const T &in, T &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const |
| Transform an input into the target frame (advanced). This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
|
|
template<class T > |
T | transform (const T &in, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const |
| Transform an input into the target frame (advanced). This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
|
|
template<class A , class B > |
B & | transform (const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const |
| Transform an input into the target frame and convert to a specified output type (advanced). It is templated on two types: the type of the input object and the type of the transformed output. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
|
|
boost::signals2::connection | _addTransformsChangedListener (boost::function< void(void)> callback) |
|
std::string | _allFramesAsDot (double current_time) const |
|
std::string | _allFramesAsDot () const |
|
void | _chainAsVector (const std::string &target_frame, ros::Time target_time, const std::string &source_frame, ros::Time source_time, const std::string &fixed_frame, std::vector< std::string > &output) const |
|
bool | _frameExists (const std::string &frame_id_str) const |
|
void | _getFrameStrings (std::vector< std::string > &ids) const |
|
int | _getLatestCommonTime (CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const |
|
bool | _getParent (const std::string &frame_id, ros::Time time, std::string &parent) const |
|
CompactFrameID | _lookupFrameNumber (const std::string &frameid_str) const |
|
CompactFrameID | _lookupOrInsertFrameNumber (const std::string &frameid_str) |
|
void | _removeTransformsChangedListener (boost::signals2::connection c) |
|
CompactFrameID | _validateFrameId (const char *function_name_arg, const std::string &frame_id) const |
|
TransformableCallbackHandle | addTransformableCallback (const TransformableCallback &cb) |
|
TransformableRequestHandle | addTransformableRequest (TransformableCallbackHandle handle, const std::string &target_frame, const std::string &source_frame, ros::Time time) |
|
std::string | allFramesAsString () const |
|
std::string | allFramesAsYAML (double current_time) const |
|
std::string | allFramesAsYAML () const |
|
| BufferCore (ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME)) |
|
void | cancelTransformableRequest (TransformableRequestHandle handle) |
|
bool | canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const |
|
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, std::string *error_msg=NULL) const |
|
void | clear () |
|
ros::Duration | getCacheLength () |
|
bool | isUsingDedicatedThread () const |
|
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 |
|
geometry_msgs::TransformStamped | lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const |
|
void | removeTransformableCallback (TransformableCallbackHandle handle) |
|
bool | setTransform (const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false) |
|
void | setUsingDedicatedThread (bool value) |
|
virtual | ~BufferCore (void) |
|
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Inherits tf2_ros::BufferInterface and tf2::BufferCore. Stores known frames and offers a ROS service, "tf_frames", which responds to client requests with a response containing a tf2_msgs::FrameGraph representing the relationship of known frames.
Definition at line 51 of file buffer.h.