Template Function Sophus::interpolate
Defined in File interpolate.hpp
Function Documentation
-
template<class G, class Scalar2 = typename G::Scalar>
enable_if_t<interp_details::Traits<G>::supported, G> Sophus::interpolate(G const &foo_T_bar, G const &foo_T_baz, Scalar2 p = Scalar2(0.5f)) This function interpolates between two Lie group elements
foo_T_bar
andfoo_T_baz
with an interpolation factor ofalpha
in [0, 1].It returns a pose
foo_T_quiz
withquiz
being a frame betweenbar
andbaz
. Ifalpha=0
it returnsfoo_T_bar
. If it is 1, it returnsfoo_T_baz
.(Since interpolation on Lie groups is inverse-invariant, we can equivalently think of the input arguments as being
bar_T_foo
,baz_T_foo
and the return value beingquiz_T_foo
.)Precondition:
p
must be in [0, 1].