testing_helpers.h
Go to the documentation of this file.
1 #ifndef TESTING_HELPERS_H_
2 #define TESTING_HELPERS_H_
3 
4 #include <nav_msgs/OccupancyGrid.h>
6 #include <opencv2/core/utility.hpp>
7 #include <opencv2/core/utility.hpp>
8 #include <opencv2/imgcodecs.hpp>
9 #include <random>
10 
11 const float resolution = 0.05f;
12 
13 nav_msgs::OccupancyGridConstPtr loadMap(const std::string& filename);
14 void saveMap(const std::string& filename,
15  const nav_msgs::OccupancyGridConstPtr& map);
16 std::tuple<double, double, double> randomAngleTxTy();
18 cv::Mat randomTransformMatrix();
19 
20 /* map_server is really bad. until there is no replacement I will implement it
21  * by myself */
22 template <typename InputIt>
23 std::vector<nav_msgs::OccupancyGridConstPtr> loadMaps(InputIt filenames_begin,
24  InputIt filenames_end)
25 {
26  std::vector<nav_msgs::OccupancyGridConstPtr> result;
27 
28  for (InputIt it = filenames_begin; it != filenames_end; ++it) {
29  result.emplace_back(loadMap(*it));
30  }
31  return result;
32 }
33 
34 nav_msgs::OccupancyGridConstPtr loadMap(const std::string& filename)
35 {
36  cv::Mat lookUpTable(1, 256, CV_8S);
37  signed char* p = lookUpTable.ptr<signed char>();
38  p[254] = 0;
39  p[205] = -1;
40  p[0] = 100;
41 
42  cv::Mat img = cv::imread(filename, cv::IMREAD_GRAYSCALE);
43  if (img.empty()) {
44  throw std::runtime_error("could not load map");
45  }
46  nav_msgs::OccupancyGridPtr grid{new nav_msgs::OccupancyGrid()};
47  grid->info.width = static_cast<uint>(img.size().width);
48  grid->info.height = static_cast<uint>(img.size().height);
49  grid->info.resolution = resolution;
50  grid->data.resize(static_cast<size_t>(img.size().area()));
51  cv::Mat grid_view(img.size(), CV_8S,
52  const_cast<signed char*>(grid->data.data()));
53  cv::LUT(img, lookUpTable, grid_view);
54 
55  return grid;
56 }
57 
58 void saveMap(const std::string& filename,
59  const nav_msgs::OccupancyGridConstPtr& map)
60 {
61  cv::Mat lookUpTable(1, 256, CV_8U);
62  uchar* p = lookUpTable.ptr();
63  for (int i = 0; i < 255; ++i) {
64  if (i >= 0 && i < 10)
65  p[i] = 254;
66  else
67  p[i] = 0;
68  }
69  p[255] = 205;
70 
71  cv::Mat img(map->info.height, map->info.width, CV_8S,
72  const_cast<signed char*>(map->data.data()));
73  cv::Mat out_img;
74  cv::LUT(img, lookUpTable, out_img);
75  cv::imwrite(filename, out_img);
76 }
77 
78 std::tuple<double, double, double> randomAngleTxTy()
79 {
80  static std::mt19937_64 g(156468754 /*magic*/);
81  std::uniform_real_distribution<double> rotation_dis(0., 2 * std::acos(-1));
82  std::uniform_real_distribution<double> translation_dis(-1000, 1000);
83 
84  return std::tuple<double, double, double>(rotation_dis(g), translation_dis(g),
85  translation_dis(g));
86 }
87 
89 {
90  double angle, tx, ty;
91  std::tie(angle, tx, ty) = randomAngleTxTy();
92  tf2::Transform transform;
93  tf2::Quaternion rotation;
94  rotation.setEuler(0., 0., angle);
95  transform.setRotation(rotation);
96  transform.setOrigin(tf2::Vector3(tx, ty, 0.));
97 
98  return transform;
99 }
100 
102 {
103  double angle, tx, ty;
104  std::tie(angle, tx, ty) = randomAngleTxTy();
105  cv::Mat transform =
106  (cv::Mat_<double>(3, 3) << std::cos(angle), -std::sin(angle), tx,
107  std::sin(angle), std::cos(angle), ty, 0., 0., 1.);
108 
109  return transform;
110 }
111 
112 #endif // TESTING_HELPERS_H_
const float resolution
std::vector< nav_msgs::OccupancyGridConstPtr > loadMaps(InputIt filenames_begin, InputIt filenames_end)
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
TF2SIMD_FORCE_INLINE void setRotation(const Quaternion &q)
std::tuple< double, double, double > randomAngleTxTy()
cv::Mat randomTransformMatrix()
nav_msgs::OccupancyGridConstPtr loadMap(const std::string &filename)
void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
TF2SIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
void saveMap(const std::string &filename, const nav_msgs::OccupancyGridConstPtr &map)
tf2::Transform randomTransform()


map_merge
Author(s): Jiri Horner
autogenerated on Mon Jun 10 2019 13:56:52