differential_drive_model.hpp
Go to the documentation of this file.
1 // Copyright 2022-2023 Ekumen, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef BELUGA_MOTION_DIFFERENTIAL_DRIVE_MODEL_HPP
16 #define BELUGA_MOTION_DIFFERENTIAL_DRIVE_MODEL_HPP
17 
18 #include <random>
19 #include <sophus/se3.hpp>
20 #include <tuple>
21 
23 
24 #include <beluga/3d_embedding.hpp>
25 #include <sophus/se2.hpp>
26 #include <sophus/so2.hpp>
27 #include <type_traits>
28 
34 namespace beluga {
35 
37 
42 
48 
54 
60 
65 
67  double distance_threshold = 0.01;
68 };
69 
71 
79 template <class StateType = Sophus::SE2d>
81  static_assert(
82  std::is_same_v<StateType, Sophus::SE2d> or std::is_same_v<StateType, Sophus::SE3d>,
83  "Differential model only supports SE2 and SE3 state types.");
84 
85  public:
87  using state_type = StateType;
88 
90  using control_type = std::tuple<state_type, state_type>;
91 
94 
96 
100  explicit DifferentialDriveModel(const param_type& params) : params_{params} {}
101 
103 
108  template <class Control, typename = common_tuple_type_t<Control, control_type>>
109  [[nodiscard]] auto operator()(const Control& action) const {
110  const auto& [pose, previous_pose] = action;
111  if constexpr (std::is_same_v<state_type, Sophus::SE2d>) {
112  return sampling_fn_2d(pose, previous_pose);
113  } else {
114  return sampling_fn_3d(pose, previous_pose);
115  }
116  }
117 
118  private:
119  using control_type_2d = std::tuple<Sophus::SE2d, Sophus::SE2d>;
120  using control_type_3d = std::tuple<Sophus::SE3d, Sophus::SE3d>;
121 
122  [[nodiscard]] auto sampling_fn_3d(const Sophus::SE3d& pose, const Sophus::SE3d& previous_pose) const {
123  const auto current_pose_2d = To2d(pose);
124  const auto previous_pose_pose_2d = To2d(previous_pose);
125  const auto two_d_sampling_fn = sampling_fn_2d(current_pose_2d, previous_pose_pose_2d);
126  return [=](const state_type& state, auto& gen) { return To3d(two_d_sampling_fn(To2d(state), gen)); };
127  }
128 
129  [[nodiscard]] auto sampling_fn_2d(const Sophus::SE2d& pose, const Sophus::SE2d& previous_pose) const {
130  const auto translation = pose.translation() - previous_pose.translation();
131  const double distance = translation.norm();
132  const double distance_variance = distance * distance;
133 
134  const auto& previous_orientation = previous_pose.so2();
135  const auto& current_orientation = pose.so2();
136  const auto heading_rotation = Sophus::SO2d{std::atan2(translation.y(), translation.x())};
137  const auto first_rotation =
138  distance > params_.distance_threshold ? heading_rotation * previous_orientation.inverse() : Sophus::SO2d{};
139  const auto second_rotation = current_orientation * previous_orientation.inverse() * first_rotation.inverse();
140 
141  using DistributionParam = typename std::normal_distribution<double>::param_type;
142  const auto first_rotation_params = DistributionParam{
143  first_rotation.log(), std::sqrt(
145  params_.rotation_noise_from_translation * distance_variance)};
146  const auto translation_params = DistributionParam{
147  distance, std::sqrt(
148  params_.translation_noise_from_translation * distance_variance +
150  (rotation_variance(first_rotation) + rotation_variance(second_rotation)))};
151  const auto second_rotation_params = DistributionParam{
152  second_rotation.log(), std::sqrt(
154  params_.rotation_noise_from_translation * distance_variance)};
155 
156  return [=](const auto& state, auto& gen) {
157  static thread_local auto distribution = std::normal_distribution<double>{};
158  const auto first_rotation = Sophus::SO2d{distribution(gen, first_rotation_params)};
159  const auto translation = Eigen::Vector2d{distribution(gen, translation_params), 0.0};
160  const auto second_rotation = Sophus::SO2d{distribution(gen, second_rotation_params)};
161  return state * Sophus::SE2d{first_rotation, Eigen::Vector2d{0.0, 0.0}} *
162  Sophus::SE2d{second_rotation, translation};
163  };
164  }
166 
167  static double rotation_variance(const Sophus::SO2d& rotation) {
168  // Treat backward and forward motion symmetrically for the noise models.
169  static const auto kFlippingRotation = Sophus::SO2d{Sophus::Constants<double>::pi()};
170  const auto flipped_rotation = rotation * kFlippingRotation;
171  const auto delta = std::min(std::abs(rotation.log()), std::abs(flipped_rotation.log()));
172  return delta * delta;
173  }
174 };
175 
178 
181 
182 } // namespace beluga
183 
184 #endif
beluga::To2d
Sophus::SE2d To2d(const Sophus::SE3d &tf)
Transforms a SE3 transform into a SE2 transform, by flattening the Z axis.
Definition: 3d_embedding.hpp:24
Sophus::SO2
beluga::DifferentialDriveModel::control_type_3d
std::tuple< Sophus::SE3d, Sophus::SE3d > control_type_3d
Definition: differential_drive_model.hpp:120
beluga::DifferentialDriveModel::sampling_fn_2d
auto sampling_fn_2d(const Sophus::SE2d &pose, const Sophus::SE2d &previous_pose) const
Definition: differential_drive_model.hpp:129
beluga::DifferentialDriveModel::sampling_fn_3d
auto sampling_fn_3d(const Sophus::SE3d &pose, const Sophus::SE3d &previous_pose) const
Definition: differential_drive_model.hpp:122
beluga::state
constexpr state_detail::state_fn state
Customization point object for accessing the state of a particle.
Definition: primitives.hpp:163
beluga::To3d
Sophus::SE3d To3d(const Sophus::SE2d &tf)
Embed a SE2 transform into 3D space with zero Z translation and only rotation about the Z axis.
Definition: 3d_embedding.hpp:29
beluga::DifferentialDriveModelParam::rotation_noise_from_translation
double rotation_noise_from_translation
Rotational noise from translation.
Definition: differential_drive_model.hpp:52
Sophus::SE2::so2
SOPHUS_FUNC SO2Member & so2()
beluga::DifferentialDriveModelParam
Parameters to construct a DifferentialDriveModel instance.
Definition: differential_drive_model.hpp:40
se2.hpp
beluga::DifferentialDriveModelParam::rotation_noise_from_rotation
double rotation_noise_from_rotation
Rotational noise from rotation.
Definition: differential_drive_model.hpp:46
beluga::DifferentialDriveModel::control_type
std::tuple< state_type, state_type > control_type
Current and previous odometry estimates as motion model control action.
Definition: differential_drive_model.hpp:90
3d_embedding.hpp
beluga::DifferentialDriveModelParam::translation_noise_from_rotation
double translation_noise_from_rotation
Translational noise from rotation.
Definition: differential_drive_model.hpp:64
Sophus::SE2
beluga::DifferentialDriveModelParam::translation_noise_from_translation
double translation_noise_from_translation
Translational noise from translation.
Definition: differential_drive_model.hpp:58
so2.hpp
Sophus::SE3
beluga::DifferentialDriveModel::rotation_variance
static double rotation_variance(const Sophus::SO2d &rotation)
Definition: differential_drive_model.hpp:167
beluga::DifferentialDriveModel
Sampled odometry model for a differential drive.
Definition: differential_drive_model.hpp:80
tuple_traits.hpp
Implementation of traits for tuple-like types.
Sophus::Constants::pi
static SOPHUS_FUNC Scalar pi()
beluga::DifferentialDriveModel::params_
param_type params_
Definition: differential_drive_model.hpp:165
beluga::DifferentialDriveModel::state_type
StateType state_type
2D or flattened 3D pose as motion model state (to match that of the particles).
Definition: differential_drive_model.hpp:87
Sophus::SE2::translation
SOPHUS_FUNC TranslationMember & translation()
beluga::DifferentialDriveModel::operator()
auto operator()(const Control &action) const
Computes a state sampling function conditioned on a given control action.
Definition: differential_drive_model.hpp:109
beluga::DifferentialDriveModelParam::distance_threshold
double distance_threshold
Distance threshold to detect in-place rotation.
Definition: differential_drive_model.hpp:67
beluga::DifferentialDriveModel::control_type_2d
std::tuple< Sophus::SE2d, Sophus::SE2d > control_type_2d
Definition: differential_drive_model.hpp:119
beluga
The main Beluga namespace.
Definition: 3d_embedding.hpp:21
beluga::DifferentialDriveModel::DifferentialDriveModel
DifferentialDriveModel(const param_type &params)
Constructs a DifferentialDriveModel instance.
Definition: differential_drive_model.hpp:100
se3.hpp


beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:53