12 #include "grid_map_msgs/GridMap.h" 24 *groundTruthHighRes =
createMap(mapLength, highResolution, mapPosition);
25 *groundTruthLowRes =
createMap(mapLength, lowResolution, mapPosition);
51 throw std::runtime_error(
"Interpolation demo: Unknown world requested.");
62 func.
f_ = [](
double x,
double y) {
63 return (-x*x -
y*
y +2.0*x*
y +x*x*
y*
y);
77 const double w1 = 1.0;
78 const double w2 = 2.0;
79 const double w3 = 3.0;
80 const double w4 = 4.0;
82 func.
f_ = [w1,w2,w3,w4](
double x,
double y) {
83 return std::cos(w1*x) + std::sin(w2*
y) + std::cos(w3*x) + std::sin(w4*y);
98 func.
f_ = [s](
double x,
double y) {
99 const double expZx = std::exp(2 *s* x);
100 const double tanX = (expZx - 1) / (expZx + 1);
101 const double expZy = std::exp(2 *s*
y);
102 const double tanY = (expZy - 1) / (expZy + 1);
122 constexpr
int numGaussians = 7;
123 std::array<std::pair<double, double>, numGaussians> vars = { { { 1.0, 0.3 }, { 0.25, 0.25 }, {
124 0.1, 0.1 }, { 0.1, 0.1 }, { 0.1, 0.1 }, { 0.1, 0.05 }, { 0.05, 0.05 } } };
125 std::array<std::pair<double, double>, numGaussians> means = { { { 1, -1 }, { 1, 1.7 },
126 { -1, 1.6 }, { -1.8, -1.8 }, { -1, 1.8 }, { 0, 0 }, { -1.2, 0 } } };
127 std::array<double, numGaussians> scales = { -2.0, -1.0, 2.0, 1.0, 3.0, 4.0, 1.0 };
129 std::array<Gaussian, numGaussians> g;
131 for (
int i = 0; i < numGaussians; ++i) {
132 g.at(i).x0 = means.at(i).first;
133 g.at(i).y0 = means.at(i).second;
134 g.at(i).varX = vars.at(i).first;
135 g.at(i).varY = vars.at(i).second;
136 g.at(i).s = scales.at(i);
139 func.
f_ = [g](
double x,
double y) {
141 for (
size_t i{0}; i < g.size(); ++i) {
142 const double x0 = g.at(i).x0;
143 const double y0 = g.at(i).y0;
144 const double varX = g.at(i).varX;
145 const double varY = g.at(i).varY;
146 const double s = g.at(i).s;
147 value += s * std::exp(-(x-x0)*(x-x0) / (2.0*varX) - (
y-y0)*(
y-y0) / (2.0 * varY));
165 data(index(0), index(1)) = functions.
f_(pos.x(), pos.y());
182 double desiredResolution)
187 interpolatedMap.
add(layer, 0.0);
190 return interpolatedMap;
202 interpolatedMap->
at(
demoLayer, index) = interpolatedHeight;
209 unsigned int count = 0;
211 const int nRow = map.
getSize().x();
212 const int nCol = map.
getSize().y();
214 const auto row = (*iterator).x();
215 const auto col = (*iterator).y();
216 const bool skipEvaluation = row < 2 || col < 2 || col > (nCol - 3) || row > (nRow - 3);
217 if (skipEvaluation) {
223 const double f_ = groundTruth.
f_(pos.x(), pos.y());
224 const double e = std::fabs(f - f_);
228 if (e > error.
max_) {
241 nh->
param<std::string>(
"interpolation_type", interpolationMethod_,
"Nearest");
242 nh->
param<std::string>(
"world", world_,
"Sine");
243 nh->
param<
double>(
"groundtruth_resolution", groundTruthResolution_, 0.02);
244 nh->
param<
double>(
"interpolation/data_resolution", dataResolution_, 0.1);
245 nh->
param<
double>(
"interpolation/interpolated_resolution", interpolatedResolution_, 0.02);
246 nh->
param<
double>(
"world_size/length", worldLength_, 4.0);
247 nh->
param<
double>(
"world_size/width", worldWidth_, 4.0);
249 groundTruthMapPub_ = nh->
advertise<grid_map_msgs::GridMap>(
"ground_truth", 1,
true);
250 dataSparseMapPub_ = nh->
advertise<grid_map_msgs::GridMap>(
"data_sparse", 1,
true);
251 interpolatedMapPub_ = nh->
advertise<grid_map_msgs::GridMap>(
"interpolated", 1,
true);
260 groundTruth_ =
createWorld(
worlds.at(world_), groundTruthResolution_, dataResolution_,
261 worldLength_, worldWidth_, &groundTruthMap_, &dataSparseMap_);
268 std::cout <<
"\n \n visualized the world: " << world_ << std::endl;
271 const auto statistics = computeStatistics();
272 printStatistics(statistics);
279 for (
auto world =
worlds.cbegin(); world !=
worlds.cend(); ++world) {
280 std::map<std::string, Statistic> methodsStats;
283 const auto errorAndDuration = interpolateAndComputeError(world->first, method->first);
285 statistic.
duration_ = errorAndDuration.second;
286 statistic.
error_ = errorAndDuration.first;
288 statistic.
world_ = world->first;
289 methodsStats.insert( { method->first, statistic });
291 stats.insert( { world->first, methodsStats });
298 const std::string world,
const std::string &method)
const 301 auto groundTruth =
createWorld(
worlds.at(world), groundTruthResolution_, dataResolution_,
302 worldLength_, worldWidth_, &highResMap, &dataMap);
305 const auto start = clk::now();
307 const auto end = clk::now();
308 const auto count = std::chrono::duration_cast<std::chrono::microseconds>(end - start).count();
309 const unsigned int numElements = interpolatedMap_.getSize().x() * interpolatedMap_.getSize().y();
313 errorAndDuration.second =
static_cast<double>(count) / numElements;
314 return errorAndDuration;
319 std::cout <<
" \n \n ================================== \n";
320 printf(
"Interpolated map of size: %f x %f \n", interpolatedMap_.getLength().x(),
321 interpolatedMap_.getLength().y());
322 printf(
"Resolution of the data: %f, resolution of the interpolated map: %f, \n \n",
323 dataSparseMap_.getResolution(), interpolatedMap_.getResolution());
325 for (
auto world =
worlds.cbegin(); world !=
worlds.cend(); ++world) {
326 std::cout <<
"Stats for the world: " << world->first << std::endl;
329 Statistic s = stats.at(world->first).at(method->first);
331 "Method: %-20s Mean absolute error: %-10f max error: %-10f avg query duration: %-10f microsec \n",
334 std::cout << std::endl;
340 grid_map_msgs::GridMap highResMsg, lowResMsg, interpolatedMsg;
344 groundTruthMapPub_.publish(highResMsg);
345 dataSparseMapPub_.publish(lowResMsg);
346 interpolatedMapPub_.publish(interpolatedMsg);
const Length & getLength() const
AnalyticalFunctions createPolyWorld(grid_map::GridMap *map)
static const std::string demoLayer
AnalyticalFunctions createSineWorld(grid_map::GridMap *map)
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
AnalyticalFunctions createWorld(Worlds world, double highResolution, double lowResolution, double length, double width, grid_map::GridMap *groundTruthHighRes, grid_map::GridMap *groundTruthLowRes)
float & atPosition(const std::string &layer, const Position &position)
std::map< std::string, std::map< std::string, Statistic > > Statistics
bool getPosition(const Index &index, Position &position) const
static const std::map< std::string, Worlds > worlds
std::pair< Error, double > ErrorAndDuration
ErrorAndDuration interpolateAndComputeError(const std::string world, const std::string &method) const
const std::string & getFrameId() const
static void toMessage(const grid_map::GridMap &gridMap, grid_map_msgs::GridMap &message)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void interpolateInputMap(const grid_map::GridMap &dataMap, grid_map::InterpolationMethods interpolationMethod, grid_map::GridMap *inteprolatedMap)
AnalyticalFunctions createGaussianWorld(grid_map::GridMap *map)
AnalyticalFunctions createTanhWorld(grid_map::GridMap *map)
std::function< double(double, double)> f_
void fillGridMap(grid_map::GridMap *map, const AnalyticalFunctions &functions)
std::string interpolationMethod_
void publishGridMaps() const
void printStatistics(const Statistics &stats) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
float & at(const std::string &layer, const Index &index)
Statistics computeStatistics() const
void add(const std::string &layer, const double value=NAN)
Error computeInterpolationError(const AnalyticalFunctions &groundTruth, const grid_map::GridMap &map)
static const std::map< std::string, grid_map::InterpolationMethods > interpolationMethods
InterpolationDemo(ros::NodeHandle *nh)
grid_map::GridMap createMap(const grid_map::Length &length, double resolution, const grid_map::Position &pos)
void setFrameId(const std::string &frameId)
grid_map::GridMap createInterpolatedMapFromDataMap(const grid_map::GridMap &dataMap, double desiredResolution)
const Size & getSize() const