Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
omni_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/omni_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  double delta_trans, delta_rot, delta_bearing;
51  double delta_trans_hat, delta_rot_hat, delta_strafe_hat;
52 
53  delta_trans = sqrt(
54  delta.v[0] * delta.v[0] +
55  delta.v[1] * delta.v[1]);
56  delta_rot = delta.v[2];
57 
58  // Precompute a couple of things
59  double trans_hat_stddev = sqrt(
60  alpha3_ * (delta_trans * delta_trans) +
61  alpha4_ * (delta_rot * delta_rot) );
62  double rot_hat_stddev = sqrt(
63  alpha1_ * (delta_rot * delta_rot) +
64  alpha2_ * (delta_trans * delta_trans) );
65  double strafe_hat_stddev = sqrt(
66  alpha4_ * (delta_rot * delta_rot) +
67  alpha5_ * (delta_trans * delta_trans) );
68 
69  for (int i = 0; i < set->sample_count; i++) {
70  pf_sample_t * sample = set->samples + i;
71 
72  delta_bearing = angleutils::angle_diff(
73  atan2(delta.v[1], delta.v[0]),
74  old_pose.v[2]) + sample->pose.v[2];
75  double cs_bearing = cos(delta_bearing);
76  double sn_bearing = sin(delta_bearing);
77 
78  // Sample pose differences
79  delta_trans_hat = delta_trans + pf_ran_gaussian(trans_hat_stddev);
80  delta_rot_hat = delta_rot + pf_ran_gaussian(rot_hat_stddev);
81  delta_strafe_hat = 0 + pf_ran_gaussian(strafe_hat_stddev);
82  // Apply sampled update to particle pose
83  sample->pose.v[0] += (delta_trans_hat * cs_bearing +
84  delta_strafe_hat * sn_bearing);
85  sample->pose.v[1] += (delta_trans_hat * sn_bearing -
86  delta_strafe_hat * cs_bearing);
87  sample->pose.v[2] += delta_rot_hat;
88  }
89 }
90 
91 } // namespace nav2_amcl
92 
93 #include <pluginlib/class_list_macros.hpp>
An abstract motion model class.
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.
Definition: pf.hpp:112