amcl_odom.cpp
Go to the documentation of this file.
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  */
22 //
23 // Desc: AMCL odometry routines
24 // Author: Andrew Howard
25 // Date: 6 Feb 2003
26 // CVS: $Id: amcl_odom.cc 7057 2008-10-02 00:44:06Z gbiggs $
27 //
29 
30 #include <algorithm>
31 
32 #include <sys/types.h> // required by Darwin
33 #include <math.h>
34 
35 #include "amcl/sensors/amcl_odom.h"
36 
37 using namespace amcl;
38 
39 static double
40 normalize(double z)
41 {
42  return atan2(sin(z),cos(z));
43 }
44 static double
45 angle_diff(double a, double b)
46 {
47  double d1, d2;
48  a = normalize(a);
49  b = normalize(b);
50  d1 = a-b;
51  d2 = 2*M_PI - fabs(d1);
52  if(d1 > 0)
53  d2 *= -1.0;
54  if(fabs(d1) < fabs(d2))
55  return(d1);
56  else
57  return(d2);
58 }
59 
61 // Default constructor
63 {
64  this->time = 0.0;
65 }
66 
67 void
69  double alpha2,
70  double alpha3,
71  double alpha4)
72 {
74  this->alpha1 = alpha1;
75  this->alpha2 = alpha2;
76  this->alpha3 = alpha3;
77  this->alpha4 = alpha4;
78 }
79 
80 void
82  double alpha2,
83  double alpha3,
84  double alpha4,
85  double alpha5)
86 {
88  this->alpha1 = alpha1;
89  this->alpha2 = alpha2;
90  this->alpha3 = alpha3;
91  this->alpha4 = alpha4;
92  this->alpha5 = alpha5;
93 }
94 
95 void
97  double alpha1,
98  double alpha2,
99  double alpha3,
100  double alpha4,
101  double alpha5 )
102 {
103  this->model_type = type;
104  this->alpha1 = alpha1;
105  this->alpha2 = alpha2;
106  this->alpha3 = alpha3;
107  this->alpha4 = alpha4;
108  this->alpha5 = alpha5;
109 }
110 
112 // Apply the action model
114 {
115  AMCLOdomData *ndata;
116  ndata = (AMCLOdomData*) data;
117 
118  // Compute the new sample poses
119  pf_sample_set_t *set;
120 
121  set = pf->sets + pf->current_set;
122  pf_vector_t old_pose = pf_vector_sub(ndata->pose, ndata->delta);
123 
124  switch( this->model_type )
125  {
126  case ODOM_MODEL_OMNI:
127  {
128  double delta_trans, delta_rot, delta_bearing;
129  double delta_trans_hat, delta_rot_hat, delta_strafe_hat;
130 
131  delta_trans = sqrt(ndata->delta.v[0]*ndata->delta.v[0] +
132  ndata->delta.v[1]*ndata->delta.v[1]);
133  delta_rot = ndata->delta.v[2];
134 
135  // Precompute a couple of things
136  double trans_hat_stddev = (alpha3 * (delta_trans*delta_trans) +
137  alpha1 * (delta_rot*delta_rot));
138  double rot_hat_stddev = (alpha4 * (delta_rot*delta_rot) +
139  alpha2 * (delta_trans*delta_trans));
140  double strafe_hat_stddev = (alpha1 * (delta_rot*delta_rot) +
141  alpha5 * (delta_trans*delta_trans));
142 
143  for (int i = 0; i < set->sample_count; i++)
144  {
145  pf_sample_t* sample = set->samples + i;
146 
147  delta_bearing = angle_diff(atan2(ndata->delta.v[1], ndata->delta.v[0]),
148  old_pose.v[2]) + sample->pose.v[2];
149  double cs_bearing = cos(delta_bearing);
150  double sn_bearing = sin(delta_bearing);
151 
152  // Sample pose differences
153  delta_trans_hat = delta_trans + pf_ran_gaussian(trans_hat_stddev);
154  delta_rot_hat = delta_rot + pf_ran_gaussian(rot_hat_stddev);
155  delta_strafe_hat = 0 + pf_ran_gaussian(strafe_hat_stddev);
156  // Apply sampled update to particle pose
157  sample->pose.v[0] += (delta_trans_hat * cs_bearing +
158  delta_strafe_hat * sn_bearing);
159  sample->pose.v[1] += (delta_trans_hat * sn_bearing -
160  delta_strafe_hat * cs_bearing);
161  sample->pose.v[2] += delta_rot_hat ;
162  }
163  }
164  break;
165  case ODOM_MODEL_DIFF:
166  {
167  // Implement sample_motion_odometry (Prob Rob p 136)
168  double delta_rot1, delta_trans, delta_rot2;
169  double delta_rot1_hat, delta_trans_hat, delta_rot2_hat;
170  double delta_rot1_noise, delta_rot2_noise;
171 
172  // Avoid computing a bearing from two poses that are extremely near each
173  // other (happens on in-place rotation).
174  if(sqrt(ndata->delta.v[1]*ndata->delta.v[1] +
175  ndata->delta.v[0]*ndata->delta.v[0]) < 0.01)
176  delta_rot1 = 0.0;
177  else
178  delta_rot1 = angle_diff(atan2(ndata->delta.v[1], ndata->delta.v[0]),
179  old_pose.v[2]);
180  delta_trans = sqrt(ndata->delta.v[0]*ndata->delta.v[0] +
181  ndata->delta.v[1]*ndata->delta.v[1]);
182  delta_rot2 = angle_diff(ndata->delta.v[2], delta_rot1);
183 
184  // We want to treat backward and forward motion symmetrically for the
185  // noise model to be applied below. The standard model seems to assume
186  // forward motion.
187  delta_rot1_noise = std::min(fabs(angle_diff(delta_rot1,0.0)),
188  fabs(angle_diff(delta_rot1,M_PI)));
189  delta_rot2_noise = std::min(fabs(angle_diff(delta_rot2,0.0)),
190  fabs(angle_diff(delta_rot2,M_PI)));
191 
192  for (int i = 0; i < set->sample_count; i++)
193  {
194  pf_sample_t* sample = set->samples + i;
195 
196  // Sample pose differences
197  delta_rot1_hat = angle_diff(delta_rot1,
198  pf_ran_gaussian(this->alpha1*delta_rot1_noise*delta_rot1_noise +
199  this->alpha2*delta_trans*delta_trans));
200  delta_trans_hat = delta_trans -
201  pf_ran_gaussian(this->alpha3*delta_trans*delta_trans +
202  this->alpha4*delta_rot1_noise*delta_rot1_noise +
203  this->alpha4*delta_rot2_noise*delta_rot2_noise);
204  delta_rot2_hat = angle_diff(delta_rot2,
205  pf_ran_gaussian(this->alpha1*delta_rot2_noise*delta_rot2_noise +
206  this->alpha2*delta_trans*delta_trans));
207 
208  // Apply sampled update to particle pose
209  sample->pose.v[0] += delta_trans_hat *
210  cos(sample->pose.v[2] + delta_rot1_hat);
211  sample->pose.v[1] += delta_trans_hat *
212  sin(sample->pose.v[2] + delta_rot1_hat);
213  sample->pose.v[2] += delta_rot1_hat + delta_rot2_hat;
214  }
215  }
216  break;
218  {
219  double delta_trans, delta_rot, delta_bearing;
220  double delta_trans_hat, delta_rot_hat, delta_strafe_hat;
221 
222  delta_trans = sqrt(ndata->delta.v[0]*ndata->delta.v[0] +
223  ndata->delta.v[1]*ndata->delta.v[1]);
224  delta_rot = ndata->delta.v[2];
225 
226  // Precompute a couple of things
227  double trans_hat_stddev = sqrt( alpha3 * (delta_trans*delta_trans) +
228  alpha1 * (delta_rot*delta_rot) );
229  double rot_hat_stddev = sqrt( alpha4 * (delta_rot*delta_rot) +
230  alpha2 * (delta_trans*delta_trans) );
231  double strafe_hat_stddev = sqrt( alpha1 * (delta_rot*delta_rot) +
232  alpha5 * (delta_trans*delta_trans) );
233 
234  for (int i = 0; i < set->sample_count; i++)
235  {
236  pf_sample_t* sample = set->samples + i;
237 
238  delta_bearing = angle_diff(atan2(ndata->delta.v[1], ndata->delta.v[0]),
239  old_pose.v[2]) + sample->pose.v[2];
240  double cs_bearing = cos(delta_bearing);
241  double sn_bearing = sin(delta_bearing);
242 
243  // Sample pose differences
244  delta_trans_hat = delta_trans + pf_ran_gaussian(trans_hat_stddev);
245  delta_rot_hat = delta_rot + pf_ran_gaussian(rot_hat_stddev);
246  delta_strafe_hat = 0 + pf_ran_gaussian(strafe_hat_stddev);
247  // Apply sampled update to particle pose
248  sample->pose.v[0] += (delta_trans_hat * cs_bearing +
249  delta_strafe_hat * sn_bearing);
250  sample->pose.v[1] += (delta_trans_hat * sn_bearing -
251  delta_strafe_hat * cs_bearing);
252  sample->pose.v[2] += delta_rot_hat ;
253  }
254  }
255  break;
257  {
258  // Implement sample_motion_odometry (Prob Rob p 136)
259  double delta_rot1, delta_trans, delta_rot2;
260  double delta_rot1_hat, delta_trans_hat, delta_rot2_hat;
261  double delta_rot1_noise, delta_rot2_noise;
262 
263  // Avoid computing a bearing from two poses that are extremely near each
264  // other (happens on in-place rotation).
265  if(sqrt(ndata->delta.v[1]*ndata->delta.v[1] +
266  ndata->delta.v[0]*ndata->delta.v[0]) < 0.01)
267  delta_rot1 = 0.0;
268  else
269  delta_rot1 = angle_diff(atan2(ndata->delta.v[1], ndata->delta.v[0]),
270  old_pose.v[2]);
271  delta_trans = sqrt(ndata->delta.v[0]*ndata->delta.v[0] +
272  ndata->delta.v[1]*ndata->delta.v[1]);
273  delta_rot2 = angle_diff(ndata->delta.v[2], delta_rot1);
274 
275  // We want to treat backward and forward motion symmetrically for the
276  // noise model to be applied below. The standard model seems to assume
277  // forward motion.
278  delta_rot1_noise = std::min(fabs(angle_diff(delta_rot1,0.0)),
279  fabs(angle_diff(delta_rot1,M_PI)));
280  delta_rot2_noise = std::min(fabs(angle_diff(delta_rot2,0.0)),
281  fabs(angle_diff(delta_rot2,M_PI)));
282 
283  for (int i = 0; i < set->sample_count; i++)
284  {
285  pf_sample_t* sample = set->samples + i;
286 
287  // Sample pose differences
288  delta_rot1_hat = angle_diff(delta_rot1,
289  pf_ran_gaussian(sqrt(this->alpha1*delta_rot1_noise*delta_rot1_noise +
290  this->alpha2*delta_trans*delta_trans)));
291  delta_trans_hat = delta_trans -
292  pf_ran_gaussian(sqrt(this->alpha3*delta_trans*delta_trans +
293  this->alpha4*delta_rot1_noise*delta_rot1_noise +
294  this->alpha4*delta_rot2_noise*delta_rot2_noise));
295  delta_rot2_hat = angle_diff(delta_rot2,
296  pf_ran_gaussian(sqrt(this->alpha1*delta_rot2_noise*delta_rot2_noise +
297  this->alpha2*delta_trans*delta_trans)));
298 
299  // Apply sampled update to particle pose
300  sample->pose.v[0] += delta_trans_hat *
301  cos(sample->pose.v[2] + delta_rot1_hat);
302  sample->pose.v[1] += delta_trans_hat *
303  sin(sample->pose.v[2] + delta_rot1_hat);
304  sample->pose.v[2] += delta_rot1_hat + delta_rot2_hat;
305  }
306  }
307  break;
308  }
309  return true;
310 }
double alpha2
Definition: amcl_odom.h:92
void SetModelOmni(double alpha1, double alpha2, double alpha3, double alpha4, double alpha5)
Definition: amcl_odom.cpp:81
double v[3]
Definition: pf_vector.h:40
Definition: pf.h:112
double alpha5
Definition: amcl_odom.h:92
double time
Definition: amcl_odom.h:86
pf_vector_t pf_vector_sub(pf_vector_t a, pf_vector_t b)
Definition: pf_vector.c:93
virtual bool UpdateAction(pf_t *pf, AMCLSensorData *data)
Definition: amcl_odom.cpp:113
void SetModel(odom_model_t type, double alpha1, double alpha2, double alpha3, double alpha4, double alpha5=0)
Definition: amcl_odom.cpp:96
int current_set
Definition: pf.h:125
Definition: pf.h:59
pf_vector_t pose
Definition: amcl_odom.h:50
static double angle_diff(double a, double b)
Definition: amcl_odom.cpp:45
double alpha4
Definition: amcl_odom.h:92
pf_vector_t pose
Definition: pf.h:62
double alpha3
Definition: amcl_odom.h:92
double alpha1
Definition: amcl_odom.h:92
odom_model_t
Definition: amcl_odom.h:38
void SetModelDiff(double alpha1, double alpha2, double alpha3, double alpha4)
Definition: amcl_odom.cpp:68
double pf_ran_gaussian(double sigma)
Definition: pf_pdf.c:132
static double normalize(double z)
Definition: amcl_odom.cpp:40
pf_sample_set_t sets[2]
Definition: pf.h:126
odom_model_t model_type
Definition: amcl_odom.h:89
pf_vector_t delta
Definition: amcl_odom.h:53


amcl
Author(s): Brian P. Gerkey, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:36