Program Listing for File on_motion.hpp

Return to documentation for file (include/beluga/policies/on_motion.hpp)

// Copyright 2024 Ekumen, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef BELUGA_POLICIES_ON_MOTION_HPP
#define BELUGA_POLICIES_ON_MOTION_HPP

#include <beluga/policies/policy.hpp>
#include <sophus/se2.hpp>

namespace beluga::policies {

namespace detail {


template <class Pose>
struct on_motion_policy_base;


template <class Scalar>
struct on_motion_policy_base<Sophus::SE2<Scalar>> {
 public:

  constexpr on_motion_policy_base(Scalar min_distance, Scalar min_angle)
      : min_distance_(min_distance), min_angle_(min_angle) {}


  constexpr bool operator()(const Sophus::SE2<Scalar>& prev, const Sophus::SE2<Scalar>& current) {
    const auto delta = prev.inverse() * current;
    return std::abs(delta.translation().x()) > min_distance_ ||  //
           std::abs(delta.translation().y()) > min_distance_ ||  //
           std::abs(delta.so2().log()) > min_angle_;
  }

 private:
  Scalar min_distance_{0.0};
  Scalar min_angle_{0.0};
};


template <class Pose>
struct on_motion_policy : public on_motion_policy_base<Pose> {
 public:
  using on_motion_policy_base<Pose>::on_motion_policy_base;
  using on_motion_policy_base<Pose>::operator();

  constexpr bool operator()(const Pose& pose) {
    if (!latest_pose_) {
      latest_pose_ = pose;
      return true;
    }

    const bool moved = (*this)(*latest_pose_, pose);
    if (moved) {
      latest_pose_ = pose;
    }

    return moved;
  }

 private:
  std::optional<Pose> latest_pose_;
};

struct on_motion_fn {

  template <class Scalar>
  constexpr auto operator()(Scalar min_distance, Scalar min_angle) const {
    return beluga::make_policy(on_motion_policy<Sophus::SE2<Scalar>>{min_distance, min_angle});
  }
};

}  // namespace detail


inline constexpr detail::on_motion_fn on_motion;

}  // namespace beluga::policies

#endif