Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
differential_motion_model.cpp
1 /*
2  * Player - One Hell of a Robot Server
3  * Copyright (C) 2000 Brian Gerkey & Kasper Stoy
4  * gerkey@usc.edu kaspers@robotics.usc.edu
5  *
6  * This library is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU Lesser General Public
8  * License as published by the Free Software Foundation; either
9  * version 2.1 of the License, or (at your option) any later version.
10  *
11  * This library is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
14  * Lesser General Public License for more details.
15  *
16  * You should have received a copy of the GNU Lesser General Public
17  * License along with this library; if not, write to the Free Software
18  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
19  *
20  */
21 
22 #include <cmath>
23 
24 #include "nav2_amcl/angleutils.hpp"
25 #include "nav2_amcl/motion_model/differential_motion_model.hpp"
26 #include "nav2_amcl/pf/pf_pdf.hpp"
27 
28 namespace nav2_amcl
29 {
30 
31 void
33  double alpha1, double alpha2, double alpha3, double alpha4,
34  double alpha5)
35 {
36  alpha1_ = alpha1;
37  alpha2_ = alpha2;
38  alpha3_ = alpha3;
39  alpha4_ = alpha4;
40  alpha5_ = alpha5;
41 }
42 
43 void
45  pf_t * pf, const pf_vector_t & pose,
46  const pf_vector_t & delta)
47 {
48  // Compute the new sample poses
49  pf_sample_set_t * set;
50 
51  set = pf->sets + pf->current_set;
52  pf_vector_t old_pose = pf_vector_sub(pose, delta);
53 
54  // Implement sample_motion_odometry (Prob Rob p 136)
55  double delta_rot1, delta_trans, delta_rot2;
56  double delta_rot1_hat, delta_trans_hat, delta_rot2_hat;
57  double delta_rot1_noise, delta_rot2_noise;
58 
59  // Avoid computing a bearing from two poses that are extremely near each
60  // other (happens on in-place rotation).
61  if (sqrt(
62  delta.v[1] * delta.v[1] +
63  delta.v[0] * delta.v[0]) < 0.01)
64  {
65  delta_rot1 = 0.0;
66  } else {
67  delta_rot1 = angleutils::angle_diff(
68  atan2(delta.v[1], delta.v[0]),
69  old_pose.v[2]);
70  }
71  delta_trans = sqrt(
72  delta.v[0] * delta.v[0] +
73  delta.v[1] * delta.v[1]);
74  delta_rot2 = angleutils::angle_diff(delta.v[2], delta_rot1);
75 
76  // We want to treat backward and forward motion symmetrically for the
77  // noise model to be applied below. The standard model seems to assume
78  // forward motion.
79  delta_rot1_noise = std::min(
80  fabs(angleutils::angle_diff(delta_rot1, 0.0)),
81  fabs(angleutils::angle_diff(delta_rot1, M_PI)));
82  delta_rot2_noise = std::min(
83  fabs(angleutils::angle_diff(delta_rot2, 0.0)),
84  fabs(angleutils::angle_diff(delta_rot2, M_PI)));
85 
86  for (int i = 0; i < set->sample_count; i++) {
87  pf_sample_t * sample = set->samples + i;
88 
89  // Sample pose differences
90  delta_rot1_hat = angleutils::angle_diff(
91  delta_rot1,
92  pf_ran_gaussian(
93  sqrt(
94  alpha1_ * delta_rot1_noise * delta_rot1_noise +
95  alpha2_ * delta_trans * delta_trans)));
96  delta_trans_hat = delta_trans -
97  pf_ran_gaussian(
98  sqrt(
99  alpha3_ * delta_trans * delta_trans +
100  alpha4_ * delta_rot1_noise * delta_rot1_noise +
101  alpha4_ * delta_rot2_noise * delta_rot2_noise));
102  delta_rot2_hat = angleutils::angle_diff(
103  delta_rot2,
104  pf_ran_gaussian(
105  sqrt(
106  alpha1_ * delta_rot2_noise * delta_rot2_noise +
107  alpha2_ * delta_trans * delta_trans)));
108 
109  // Apply sampled update to particle pose
110  sample->pose.v[0] += delta_trans_hat *
111  cos(sample->pose.v[2] + delta_rot1_hat);
112  sample->pose.v[1] += delta_trans_hat *
113  sin(sample->pose.v[2] + delta_rot1_hat);
114  sample->pose.v[2] += delta_rot1_hat + delta_rot2_hat;
115  }
116 }
117 
118 } // namespace nav2_amcl
119 
120 #include <pluginlib/class_list_macros.hpp>
virtual void initialize(double alpha1, double alpha2, double alpha3, double alpha4, double alpha5)
An factory to create motion models.
virtual void odometryUpdate(pf_t *pf, const pf_vector_t &pose, const pf_vector_t &delta)
Update on new odometry data.
An abstract motion model class.
Definition: pf.hpp:112