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/imgcodecs.hpp>
8 #include <random>
9 
10 const float resolution = 0.05f;
11 
12 nav_msgs::OccupancyGridConstPtr loadMap(const std::string& filename);
13 void saveMap(const std::string& filename,
14  const nav_msgs::OccupancyGridConstPtr& map);
15 std::tuple<double, double, double> randomAngleTxTy();
16 geometry_msgs::Transform randomTransform();
17 cv::Mat randomTransformMatrix();
18 
19 /* map_server is really bad. until there is no replacement I will implement it
20  * by myself */
21 template <typename InputIt>
22 std::vector<nav_msgs::OccupancyGridConstPtr> loadMaps(InputIt filenames_begin,
23  InputIt filenames_end)
24 {
25  std::vector<nav_msgs::OccupancyGridConstPtr> result;
26 
27  for (InputIt it = filenames_begin; it != filenames_end; ++it) {
28  result.emplace_back(loadMap(*it));
29  }
30  return result;
31 }
32 
33 nav_msgs::OccupancyGridConstPtr loadMap(const std::string& filename)
34 {
35  cv::Mat lookUpTable(1, 256, CV_8S);
36  signed char* p = lookUpTable.ptr<signed char>();
37  p[254] = 0;
38  p[205] = -1;
39  p[0] = 100;
40 
41  cv::Mat img = cv::imread(filename, cv::IMREAD_GRAYSCALE);
42  if (img.empty()) {
43  throw std::runtime_error("could not load map");
44  }
45  nav_msgs::OccupancyGridPtr grid{new nav_msgs::OccupancyGrid()};
46  grid->info.width = static_cast<uint>(img.size().width);
47  grid->info.height = static_cast<uint>(img.size().height);
48  grid->info.resolution = resolution;
49  grid->data.resize(static_cast<size_t>(img.size().area()));
50  cv::Mat grid_view(img.size(), CV_8S,
51  const_cast<signed char*>(grid->data.data()));
52  cv::LUT(img, lookUpTable, grid_view);
53 
54  return grid;
55 }
56 
57 void saveMap(const std::string& filename,
58  const nav_msgs::OccupancyGridConstPtr& map)
59 {
60  cv::Mat lookUpTable(1, 256, CV_8U);
61  uchar* p = lookUpTable.ptr();
62  for (int i = 0; i < 255; ++i) {
63  if (i >= 0 && i < 10)
64  p[i] = 254;
65  else
66  p[i] = 0;
67  }
68  p[255] = 205;
69 
70  cv::Mat img(map->info.height, map->info.width, CV_8S,
71  const_cast<signed char*>(map->data.data()));
72  cv::Mat out_img;
73  cv::LUT(img, lookUpTable, out_img);
74  cv::imwrite(filename, out_img);
75 }
76 
77 std::tuple<double, double, double> randomAngleTxTy()
78 {
79  static std::mt19937_64 g(156468754 /*magic*/);
80  std::uniform_real_distribution<double> rotation_dis(0., 2 * std::acos(-1));
81  std::uniform_real_distribution<double> translation_dis(-1000, 1000);
82 
83  return std::tuple<double, double, double>(rotation_dis(g), translation_dis(g),
84  translation_dis(g));
85 }
86 
87 geometry_msgs::Transform randomTransform()
88 {
89  double angle, tx, ty;
90  std::tie(angle, tx, ty) = randomAngleTxTy();
91  tf2::Transform transform;
92  tf2::Quaternion rotation;
93  rotation.setEuler(0., 0., angle);
94  rotation.normalize();
95  transform.setRotation(rotation);
96  transform.setOrigin(tf2::Vector3(tx, ty, 0.));
97 
98  auto msg = toMsg(transform);
99  // normalize quaternion such that w > 0 (q and -q represents the same
100  // transformation)
101  if (msg.rotation.w < 0.) {
102  msg.rotation.x *= -1.;
103  msg.rotation.y *= -1.;
104  msg.rotation.z *= -1.;
105  msg.rotation.w *= -1.;
106  }
107 
108  return msg;
109 }
110 
112 {
113  double angle, tx, ty;
114  std::tie(angle, tx, ty) = randomAngleTxTy();
115  cv::Mat transform =
116  (cv::Mat_<double>(3, 3) << std::cos(angle), -std::sin(angle), tx,
117  std::sin(angle), std::cos(angle), ty, 0., 0., 1.);
118 
119  return transform;
120 }
121 
122 static inline bool isIdentity(const geometry_msgs::Transform& transform)
123 {
125  tf2::fromMsg(transform, t);
126  return tf2::Transform::getIdentity() == t;
127 }
128 
129 static inline bool isIdentity(const geometry_msgs::Quaternion& rotation)
130 {
131  tf2::Quaternion q;
132  tf2::fromMsg(rotation, q);
133  return tf2::Quaternion::getIdentity() == q;
134 }
135 
136 // data size is consistent with height and width
137 static inline bool consistentData(const nav_msgs::OccupancyGrid& grid)
138 {
139  return grid.info.width * grid.info.height == grid.data.size();
140 }
141 
142 // ignores header, map_load_time and origin
143 static inline bool operator==(const nav_msgs::OccupancyGrid& grid1,
144  const nav_msgs::OccupancyGrid& grid2)
145 {
146  bool equal = true;
147  equal &= grid1.info.width == grid2.info.width;
148  equal &= grid1.info.height == grid2.info.height;
149  equal &= std::abs(grid1.info.resolution - grid2.info.resolution) <
150  std::numeric_limits<float>::epsilon();
151  equal &= grid1.data.size() == grid2.data.size();
152  for (size_t i = 0; i < grid1.data.size(); ++i) {
153  equal &= grid1.data[i] == grid2.data[i];
154  }
155  return equal;
156 }
157 
158 #endif // TESTING_HELPERS_H_
const float resolution
std::vector< nav_msgs::OccupancyGridConstPtr > loadMaps(InputIt filenames_begin, InputIt filenames_end)
static const Quaternion & getIdentity()
static bool operator==(const nav_msgs::OccupancyGrid &grid1, const nav_msgs::OccupancyGrid &grid2)
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
static bool isIdentity(const geometry_msgs::Transform &transform)
TF2SIMD_FORCE_INLINE void setRotation(const Quaternion &q)
std::tuple< double, double, double > randomAngleTxTy()
cv::Mat randomTransformMatrix()
geometry_msgs::TransformStamped t
nav_msgs::OccupancyGridConstPtr loadMap(const std::string &filename)
Quaternion & normalize()
void fromMsg(const A &, B &b)
static const Transform & getIdentity()
void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
TF2SIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
B toMsg(const A &a)
void saveMap(const std::string &filename, const nav_msgs::OccupancyGridConstPtr &map)
static bool consistentData(const nav_msgs::OccupancyGrid &grid)
geometry_msgs::Transform randomTransform()


map_merge
Author(s): Jiri Horner
autogenerated on Mon Feb 28 2022 22:46:02