Skip to content

Commit 342a379

Browse files
committed
Heuristic -> Initialization
Renamed confusing 'heuristic' word for 'initialization'
1 parent 06ab3c1 commit 342a379

File tree

9 files changed

+32
-32
lines changed

9 files changed

+32
-32
lines changed

README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ To adapt LIMO-Velo to our own hardware infrastructure, a [YAML](https://yaml.org
9696
Relevant parameters are:
9797
- ``real_time`` if you want to get real time experience.
9898
- ``mapping_offline`` is on an pre-alpha stage and it does not work 100% as it should of.
99-
- ``heuristic`` which you can choose how you want the initialization of the pointcloud sizes (sizes =: deltas, in seconds).
99+
- ``initialization`` which you can choose how you want the initialization of the pointcloud sizes (sizes =: deltas, in seconds).
100100

101101
## 4. Modifying the LiDAR driver to get true real-time performance
102102
*TODO* - This section is intended to explain how to modify the LiDAR driver to increase its frequency by publishing parts of the pointcloud instead of waiting for all of it.

config/kitti.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,6 @@ degeneracy_threshold: 400.
4747
print_degeneracy_values: false
4848

4949
# Delta refinement
50-
Heuristic:
50+
Initialization:
5151
times: []
5252
deltas: [0.1]

config/ouster.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -58,11 +58,11 @@ print_degeneracy_values: false # Print the degeneracy eigenvalues to guess w
5858
# Choose a set of times and field of view sizes (deltas) for the initialization.
5959
# The delta (t2 - t1) that will be used through the algorithm therefore is the last one in the 'deltas' vector
6060
# Tick the 'Localizator' box in RViz to see the initialization in action
61-
Heuristic:
62-
# No heuristic
61+
Initialization:
62+
# No initialization
6363
times: []
6464
deltas: [0.1]
6565

66-
# # With heuristic
66+
# # With initialization
6767
# times: [2.0]
6868
# deltas: [0.1, 0.025]

config/params.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -56,11 +56,11 @@ print_degeneracy_values: false # Print the degeneracy eigenvalues to guess w
5656
# Choose a set of times and field of view sizes (deltas) for the initialization.
5757
# The delta (t2 - t1) that will be used through the algorithm therefore is the last one in the 'deltas' vector
5858
# Tick the 'Localizator' box in RViz to see the initialization in action
59-
Heuristic:
60-
# # No heuristic
59+
Initialization:
60+
# # No initialization
6161
# times: []
6262
# deltas: [0.1]
6363

64-
# With heuristic
64+
# With initialization
6565
times: [0.5, 1.0]
6666
deltas: [0.1, 0.05, 0.02]

config/xaloc.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -51,11 +51,11 @@ degeneracy_threshold: 5.
5151
print_degeneracy_values: false
5252

5353
# Delta refinement
54-
Heuristic:
55-
# # No heuristic
54+
Initialization:
55+
# # No initialization
5656
# times: []
5757
# deltas: [0.1]
5858

59-
# With heuristic
59+
# With initialization
6060
times: [0.5, 1.0, 1.25]
6161
deltas: [0.1, 0.05, 0.02]

include/Headers/Accumulator.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ class Accumulator {
4747

4848
// Time management
4949

50-
double update_delta(const HeuristicParams&, double t);
50+
double update_delta(const InitializationParams&, double t);
5151
double latest_time();
5252

5353
private:
@@ -111,7 +111,7 @@ class Accumulator {
111111

112112
bool enough_imus();
113113
void set_initial_time();
114-
double interpret_heuristic(const HeuristicParams&, double t);
114+
double interpret_initialization(const InitializationParams&, double t);
115115

116116
bool missing_data(const Points&);
117117
void throw_warning(const Points&);

include/Headers/Common.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ namespace LIDAR_TYPE {
4848
const std::string Custom = "custom";
4949
}
5050

51-
struct HeuristicParams {
51+
struct InitializationParams {
5252
std::vector<double> times;
5353
std::vector<double> deltas;
5454
};
@@ -103,7 +103,7 @@ struct Params {
103103
std::string points_topic;
104104
std::string imus_topic;
105105

106-
HeuristicParams Heuristic;
106+
InitializationParams Initialization;
107107
};
108108

109109
namespace velodyne_ros {

src/Modules/Accumulator.cpp

+13-13
Original file line numberDiff line numberDiff line change
@@ -113,9 +113,9 @@ extern struct Params Config;
113113
return this->get_imus(t - 3., t).size() < 2;
114114
}
115115

116-
double Accumulator::update_delta(const HeuristicParams& heuristic, double t) {
117-
assert(("There has to be exactly one more delta value than time delimiters", heuristic.times.size() + 1 == heuristic.deltas.size()));
118-
return this->interpret_heuristic(heuristic, t);
116+
double Accumulator::update_delta(const InitializationParams& initialization, double t) {
117+
assert(("There has to be exactly one more delta value than time delimiters", initialization.times.size() + 1 == initialization.deltas.size()));
118+
return this->interpret_initialization(initialization, t);
119119
}
120120

121121
double Accumulator::latest_time() {
@@ -154,27 +154,27 @@ extern struct Params Config;
154154
this->initial_time = latest_imu_time - Config.real_time_delay;
155155
}
156156

157-
double Accumulator::interpret_heuristic(const HeuristicParams& heuristic, double t) {
157+
double Accumulator::interpret_initialization(const InitializationParams& initialization, double t) {
158158
// If is after last time
159-
if (heuristic.times.empty()) return heuristic.deltas.back();
160-
if (t - this->initial_time >= heuristic.times.back()) return heuristic.deltas.back();
159+
if (initialization.times.empty()) return initialization.deltas.back();
160+
if (t - this->initial_time >= initialization.times.back()) return initialization.deltas.back();
161161

162162
// If we have to find it in the list
163-
for (int k = 0; k < heuristic.times.size(); ++k)
164-
if (t - this->initial_time < heuristic.times[k])
165-
return heuristic.deltas[k];
163+
for (int k = 0; k < initialization.times.size(); ++k)
164+
if (t - this->initial_time < initialization.times[k])
165+
return initialization.deltas[k];
166166

167-
return heuristic.deltas.back();
167+
return initialization.deltas.back();
168168
}
169169

170170
bool Accumulator::missing_data(const Points& time_sorted_points) {
171171
if (time_sorted_points.size() < Config.MAX_POINTS2MATCH) return false;
172172

173173
// Check missing 'time' information
174174
if (time_sorted_points.front().time == 0 and time_sorted_points.back().time == 0) {
175-
// Remove Heuristic
176-
Config.Heuristic.times = {};
177-
Config.Heuristic.deltas = {Config.full_rotation_time};
175+
// Remove Initialization
176+
Config.Initialization.times = {};
177+
Config.Initialization.deltas = {Config.full_rotation_time};
178178

179179
return true;
180180
}

src/main.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ int main(int argc, char** argv) {
4545
t2 = DBL_MAX;
4646

4747
// (Delta = t2 - t1) Size of the field of view we use to localize
48-
double delta = Config.Heuristic.deltas.front();
48+
double delta = Config.Initialization.deltas.front();
4949

5050
ros::Rate rate(5000);
5151

@@ -63,7 +63,7 @@ int main(int argc, char** argv) {
6363
else t2 = std::min(t2 + delta, accum.latest_time());
6464

6565
// Update delta value
66-
delta = accum.update_delta(Config.Heuristic, t2);
66+
delta = accum.update_delta(Config.Initialization, t2);
6767

6868
// Define t1 but don't use to localize repeated points
6969
t1 = std::max(t2 - delta, loc.last_time_updated);
@@ -168,8 +168,8 @@ void fill_config(ros::NodeHandle& nh) {
168168
nh.param<std::string>("imus_topic", Config.imus_topic, "/vectornav/IMU");
169169
nh.param<bool>("offset_beginning", Config.offset_beginning, false);
170170
nh.param<bool>("stamp_beginning", Config.stamp_beginning, false);
171-
nh.param<std::vector<double>>("/Heuristic/times", Config.Heuristic.times, {});
172-
nh.param<std::vector<double>>("/Heuristic/deltas", Config.Heuristic.deltas, {Config.full_rotation_time});
171+
nh.param<std::vector<double>>("/Initialization/times", Config.Initialization.times, {});
172+
nh.param<std::vector<double>>("/Initialization/deltas", Config.Initialization.deltas, {Config.full_rotation_time});
173173
nh.param<std::vector<float>>("initial_gravity", Config.initial_gravity, {0.0, 0.0, -9.807});
174174
nh.param<std::vector<float>>("I_Translation_L", Config.I_Translation_L, std::vector<float> (3, 0.));
175175
nh.param<std::vector<float>>("I_Rotation_L", Config.I_Rotation_L, std::vector<float> (9, 0.));

0 commit comments

Comments
 (0)