1 #ifndef TESTING_HELPERS_H_ 2 #define TESTING_HELPERS_H_ 4 #include <nav_msgs/OccupancyGrid.h> 6 #include <opencv2/core/utility.hpp> 7 #include <opencv2/imgcodecs.hpp> 12 nav_msgs::OccupancyGridConstPtr
loadMap(
const std::string& filename);
13 void saveMap(
const std::string& filename,
14 const nav_msgs::OccupancyGridConstPtr& map);
21 template <
typename InputIt>
22 std::vector<nav_msgs::OccupancyGridConstPtr>
loadMaps(InputIt filenames_begin,
23 InputIt filenames_end)
25 std::vector<nav_msgs::OccupancyGridConstPtr> result;
27 for (InputIt it = filenames_begin; it != filenames_end; ++it) {
28 result.emplace_back(
loadMap(*it));
33 nav_msgs::OccupancyGridConstPtr
loadMap(
const std::string& filename)
35 cv::Mat lookUpTable(1, 256, CV_8S);
36 signed char* p = lookUpTable.ptr<
signed char>();
41 cv::Mat img = cv::imread(filename, cv::IMREAD_GRAYSCALE);
43 throw std::runtime_error(
"could not load map");
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);
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);
58 const nav_msgs::OccupancyGridConstPtr& map)
60 cv::Mat lookUpTable(1, 256, CV_8U);
61 uchar* p = lookUpTable.ptr();
62 for (
int i = 0; i < 255; ++i) {
70 cv::Mat img(map->info.height, map->info.width, CV_8S,
71 const_cast<signed char*>(map->data.data()));
73 cv::LUT(img, lookUpTable, out_img);
74 cv::imwrite(filename, out_img);
79 static std::mt19937_64 g(156468754 );
80 std::uniform_real_distribution<double> rotation_dis(0., 2 * std::acos(-1));
81 std::uniform_real_distribution<double> translation_dis(-1000, 1000);
83 return std::tuple<double, double, double>(rotation_dis(g), translation_dis(g),
96 transform.
setOrigin(tf2::Vector3(tx, ty, 0.));
98 auto msg =
toMsg(transform);
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.;
113 double angle, tx, ty;
116 (cv::Mat_<double>(3, 3) << std::cos(angle), -std::sin(angle), tx,
117 std::sin(angle), std::cos(angle), ty, 0., 0., 1.);
122 static inline bool isIdentity(
const geometry_msgs::Transform& transform)
129 static inline bool isIdentity(
const geometry_msgs::Quaternion& rotation)
139 return grid.info.width * grid.info.height == grid.data.size();
143 static inline bool operator==(
const nav_msgs::OccupancyGrid& grid1,
144 const nav_msgs::OccupancyGrid& grid2)
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];
158 #endif // TESTING_HELPERS_H_
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)
std::tuple< double, double, double > randomAngleTxTy()
cv::Mat randomTransformMatrix()
geometry_msgs::TransformStamped t
nav_msgs::OccupancyGridConstPtr loadMap(const std::string &filename)
void fromMsg(const A &, B &b)
void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
void saveMap(const std::string &filename, const nav_msgs::OccupancyGridConstPtr &map)
static bool consistentData(const nav_msgs::OccupancyGrid &grid)
geometry_msgs::Transform randomTransform()