motion_cache.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018-2019, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <algorithm>
31 #include <unordered_map>
32 #include <vector>
33 
36 
38  const float linear_resolution,
39  const float angular_resolution,
40  const int range,
41  const std::function<void(CyclicVecInt<3, 2>, size_t&, size_t&)> gm_addr)
42 {
43  const int angle = std::lround(M_PI * 2 / angular_resolution);
44 
45  page_size_ = angle;
46  cache_.resize(angle);
47  for (int syaw = 0; syaw < angle; syaw++)
48  {
49  const float yaw = syaw * angular_resolution;
51  for (d[0] = -range; d[0] <= range; d[0]++)
52  {
53  for (d[1] = -range; d[1] <= range; d[1]++)
54  {
55  if (d[0] == 0 && d[1] == 0)
56  continue;
57  if (d.sqlen() > range * range)
58  continue;
59  for (d[2] = 0; d[2] < angle; d[2]++)
60  {
61  Page page;
62  const float yaw_e = d[2] * angular_resolution;
63  const float diff_val[3] =
64  {
65  d[0] * linear_resolution,
66  d[1] * linear_resolution,
67  d[2] * angular_resolution
68  };
69  std::unordered_map<CyclicVecInt<3, 2>, bool, CyclicVecInt<3, 2>> registered;
70  registered[d] = true;
71 
72  CyclicVecFloat<3, 2> motion(diff_val[0], diff_val[1], diff_val[2]);
73  motion.rotate(-syaw * angular_resolution);
74  const float cos_v = cosf(motion[2]);
75  const float sin_v = sinf(motion[2]);
76 
77  const float inter = 1.0 / d.len();
78 
79  if (fabs(sin_v) < 0.1)
80  {
81  for (float i = 0; i < 1.0; i += inter)
82  {
83  const float x = diff_val[0] * i;
84  const float y = diff_val[1] * i;
85 
87  x / linear_resolution, y / linear_resolution, yaw / angular_resolution);
88  pos.cycleUnsigned(angle);
89  if (registered.find(pos) == registered.end())
90  {
91  page.motion_.push_back(pos);
92  registered[pos] = true;
93  }
94  }
95  page.distance_ = d.len();
96  cache_[syaw][d] = page;
97  continue;
98  }
99 
100  float distf = 0.0;
101  const float r1 = motion[1] + motion[0] * cos_v / sin_v;
102  const float r2 = std::copysign(
103  sqrtf(powf(motion[0], 2.0) + powf(motion[0] * cos_v / sin_v, 2.0)),
104  motion[0] * sin_v);
105 
106  float dyaw = yaw_e - yaw;
107  if (dyaw < -M_PI)
108  dyaw += 2 * M_PI;
109  else if (dyaw > M_PI)
110  dyaw -= 2 * M_PI;
111 
112  const float cx = d[0] * linear_resolution + r2 * cosf(yaw_e + M_PI / 2);
113  const float cy = d[1] * linear_resolution + r2 * sinf(yaw_e + M_PI / 2);
114  const float cx_s = r1 * cosf(yaw + M_PI / 2);
115  const float cy_s = r1 * sinf(yaw + M_PI / 2);
116 
117  CyclicVecFloat<3, 2> posf_prev(0, 0, 0);
118 
119  for (float i = 0; i < 1.0; i += inter)
120  {
121  const float r = r1 * (1.0 - i) + r2 * i;
122  const float cx2 = cx_s * (1.0 - i) + cx * i;
123  const float cy2 = cy_s * (1.0 - i) + cy * i;
124  const float cyaw = yaw + i * dyaw;
125 
126  const float posf_raw[3] =
127  {
128  (cx2 - r * cosf(cyaw + M_PI / 2)) / linear_resolution,
129  (cy2 - r * sinf(cyaw + M_PI / 2)) / linear_resolution,
130  cyaw / angular_resolution
131  };
132  const CyclicVecFloat<3, 2> posf(posf_raw[0], posf_raw[1], posf_raw[2]);
133  CyclicVecInt<3, 2> pos(posf_raw[0], posf_raw[1], posf_raw[2]);
134  pos.cycleUnsigned(angle);
135  if (registered.find(pos) == registered.end())
136  {
137  page.motion_.push_back(pos);
138  registered[pos] = true;
139  }
140  distf += (posf - posf_prev).len();
141  posf_prev = posf;
142  }
143  distf += (CyclicVecFloat<3, 2>(d) - posf_prev).len();
144  page.distance_ = distf;
145  cache_[syaw][d] = page;
146  }
147  }
148  }
149  // Sort to improve cache hit rate
150  for (auto& cache : cache_[syaw])
151  {
152  auto comp = [this, &gm_addr](const CyclicVecInt<3, 2> a, const CyclicVecInt<3, 2> b)
153  {
154  size_t a_baddr, a_addr;
155  size_t b_baddr, b_addr;
156  gm_addr(a, a_baddr, a_addr);
157  gm_addr(b, b_baddr, b_addr);
158  if (a_baddr == b_baddr)
159  {
160  return (a_addr < b_addr);
161  }
162  return (a_baddr < b_baddr);
163  };
164  std::sort(cache.second.motion_.begin(), cache.second.motion_.end(), comp);
165  }
166  }
167 }
d
void cycleUnsigned(const int res, const ArgList &...rest)
Definition: cyclic_vec.h:279
void rotate(const float ang)
Definition: cyclic_vec.h:258
T sqlen() const
Definition: cyclic_vec.h:230
TFSIMD_FORCE_INLINE const tfScalar & y() const
float len() const
Definition: cyclic_vec.h:239
std::vector< Cache > cache_
Definition: motion_cache.h:90
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< CyclicVecInt< 3, 2 > > motion_
Definition: motion_cache.h:46
void reset(const float linear_resolution, const float angular_resolution, const int range, const std::function< void(CyclicVecInt< 3, 2 >, size_t &, size_t &)> gm_addr)


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:13