#include <initialization.hpp>
|
| PoseT | guess (const tf2::BufferCore &tf_graph, tf2::TimePoint time_point, const std::string &target_frame, const std::string &source_frame) |
| |
|
| const Derived & | impl () const |
| |
| Derived & | impl () |
| |
template<typename Derived>
class autoware::localization::localization_common::PoseInitializerBase< Derived >
The Pose initializer helps initialize relative localizer algorithms with an initial guess. Extrapolation policy must be defined within the implementation class.
- Template Parameters
-
| Derived | CRTP implementation class |
◆ guess()
template<typename Derived >
Guess the pose at a given time point. This function will look the transform up in the transform graph between the specified frames. If extrapolation is required, the behavior is determined by the implementation class. tf2 lookup may generate exceptions if the lookup fails in other ways. For details, see tf2::BufferCore class.
- Parameters
-
| tf_graph | Transform graph that contains all the transforms to look up. |
| time_point | Time to guess the pose. |
| target_frame | Target frame of the transform. (i.e. "map") |
| source_frame | Source frame of the transform. (i.e. "base_link") |
- Returns
- The transform at the given time point
The documentation for this class was generated from the following file: