Class Transformer
Defined in File transformer.h
Inheritance Relationships
Derived Types
public swri_transform_util::UtmTransformer
(Class UtmTransformer)public swri_transform_util::Wgs84Transformer
(Class Wgs84Transformer)
Class Documentation
-
class Transformer
A base class for transformers.
Instantiations of this class implement an interface to get transforms from certain types of frames (e.g. TF, WGS84) to other types of frames.
Subclassed by swri_transform_util::UtmTransformer, swri_transform_util::Wgs84Transformer
Public Functions
-
Transformer()
-
virtual ~Transformer() = default
Initialize the Transformer from a tf::TransformListener.
- Parameters:
tf – A shared pointer to a tf::TransformListener that the Transformer wraps. It is recommended that every Transformer in a node use the same tf::TransformListener to reduce redundant computation.
-
virtual std::map<std::string, std::vector<std::string>> Supports() const = 0
Get a map of the transforms supported by this Transformer
- Returns:
A map from source frame IDs to list of destination frame IDs. A source->destination entry does not imply that the inverse transform is supported as well.
-
virtual bool GetTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, Transform &transform) = 0
Get a swri_transform_util::Transform
Gets the swri_transform_util::Transform that transforms coordinates from the source_frame into the target_frame. If the transform is not available, return false.
- Parameters:
target_frame – [in] Destination frame for transform
source_frame – [in] Source frame for transform
time – [in] Time that the transform is valid for. To get the most recent transform, use tf2::TimePoint(0)
transform – [out] Output container for the transform
- Returns:
True if the transform was found, false if no transform between the specified frames is available for the specified time.
Protected Functions
-
virtual bool Initialize()
-
virtual bool GetTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, geometry_msgs::msg::TransformStamped &transform) const
Protected Attributes
-
bool initialized_
-
std::shared_ptr<tf2_ros::Buffer> tf_buffer_
-
std::shared_ptr<LocalXyWgs84Util> local_xy_util_
-
rclcpp::Logger logger_
-
Transformer()