Nav2 Navigation Stack - jazzy  jazzy
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 "nav2_amcl/motion_model/differential_motion_model.hpp"
23 
24 namespace nav2_amcl
25 {
26 
27 void
29  double alpha1, double alpha2, double alpha3, double alpha4,
30  double alpha5)
31 {
32  alpha1_ = alpha1;
33  alpha2_ = alpha2;
34  alpha3_ = alpha3;
35  alpha4_ = alpha4;
36  alpha5_ = alpha5;
37 }
38 
39 void
41  pf_t * pf, const pf_vector_t & pose,
42  const pf_vector_t & delta)
43 {
44  // Compute the new sample poses
45  pf_sample_set_t * set;
46 
47  set = pf->sets + pf->current_set;
48  pf_vector_t old_pose = pf_vector_sub(pose, delta);
49 
50  // Implement sample_motion_odometry (Prob Rob p 136)
51  double delta_rot1, delta_trans, delta_rot2;
52  double delta_rot1_hat, delta_trans_hat, delta_rot2_hat;
53  double delta_rot1_noise, delta_rot2_noise;
54 
55  // Avoid computing a bearing from two poses that are extremely near each
56  // other (happens on in-place rotation).
57  if (sqrt(
58  delta.v[1] * delta.v[1] +
59  delta.v[0] * delta.v[0]) < 0.01)
60  {
61  delta_rot1 = 0.0;
62  } else {
63  delta_rot1 = angleutils::angle_diff(
64  atan2(delta.v[1], delta.v[0]),
65  old_pose.v[2]);
66  }
67  delta_trans = sqrt(
68  delta.v[0] * delta.v[0] +
69  delta.v[1] * delta.v[1]);
70  delta_rot2 = angleutils::angle_diff(delta.v[2], delta_rot1);
71 
72  // We want to treat backward and forward motion symmetrically for the
73  // noise model to be applied below. The standard model seems to assume
74  // forward motion.
75  delta_rot1_noise = std::min(
76  fabs(angleutils::angle_diff(delta_rot1, 0.0)),
77  fabs(angleutils::angle_diff(delta_rot1, M_PI)));
78  delta_rot2_noise = std::min(
79  fabs(angleutils::angle_diff(delta_rot2, 0.0)),
80  fabs(angleutils::angle_diff(delta_rot2, M_PI)));
81 
82  for (int i = 0; i < set->sample_count; i++) {
83  pf_sample_t * sample = set->samples + i;
84 
85  // Sample pose differences
86  delta_rot1_hat = angleutils::angle_diff(
87  delta_rot1,
88  pf_ran_gaussian(
89  sqrt(
90  alpha1_ * delta_rot1_noise * delta_rot1_noise +
91  alpha2_ * delta_trans * delta_trans)));
92  delta_trans_hat = delta_trans -
93  pf_ran_gaussian(
94  sqrt(
95  alpha3_ * delta_trans * delta_trans +
96  alpha4_ * delta_rot1_noise * delta_rot1_noise +
97  alpha4_ * delta_rot2_noise * delta_rot2_noise));
98  delta_rot2_hat = angleutils::angle_diff(
99  delta_rot2,
100  pf_ran_gaussian(
101  sqrt(
102  alpha1_ * delta_rot2_noise * delta_rot2_noise +
103  alpha2_ * delta_trans * delta_trans)));
104 
105  // Apply sampled update to particle pose
106  sample->pose.v[0] += delta_trans_hat *
107  cos(sample->pose.v[2] + delta_rot1_hat);
108  sample->pose.v[1] += delta_trans_hat *
109  sin(sample->pose.v[2] + delta_rot1_hat);
110  sample->pose.v[2] += delta_rot1_hat + delta_rot2_hat;
111  }
112 }
113 
114 } // namespace nav2_amcl
115 
116 #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