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/core/utility.hpp> 8 #include <opencv2/imgcodecs.hpp> 13 nav_msgs::OccupancyGridConstPtr
loadMap(
const std::string& filename);
14 void saveMap(
const std::string& filename,
15 const nav_msgs::OccupancyGridConstPtr& map);
22 template <
typename InputIt>
23 std::vector<nav_msgs::OccupancyGridConstPtr>
loadMaps(InputIt filenames_begin,
24 InputIt filenames_end)
26 std::vector<nav_msgs::OccupancyGridConstPtr> result;
28 for (InputIt it = filenames_begin; it != filenames_end; ++it) {
29 result.emplace_back(
loadMap(*it));
34 nav_msgs::OccupancyGridConstPtr
loadMap(
const std::string& filename)
36 cv::Mat lookUpTable(1, 256, CV_8S);
37 signed char* p = lookUpTable.ptr<
signed char>();
42 cv::Mat img = cv::imread(filename, cv::IMREAD_GRAYSCALE);
44 throw std::runtime_error(
"could not load map");
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);
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);
59 const nav_msgs::OccupancyGridConstPtr& map)
61 cv::Mat lookUpTable(1, 256, CV_8U);
62 uchar* p = lookUpTable.ptr();
63 for (
int i = 0; i < 255; ++i) {
71 cv::Mat img(map->info.height, map->info.width, CV_8S,
72 const_cast<signed char*>(map->data.data()));
74 cv::LUT(img, lookUpTable, out_img);
75 cv::imwrite(filename, out_img);
80 static std::mt19937_64 g(156468754 );
81 std::uniform_real_distribution<double> rotation_dis(0., 2 * std::acos(-1));
82 std::uniform_real_distribution<double> translation_dis(-1000, 1000);
84 return std::tuple<double, double, double>(rotation_dis(g), translation_dis(g),
96 transform.
setOrigin(tf2::Vector3(tx, ty, 0.));
103 double angle, tx, ty;
106 (cv::Mat_<double>(3, 3) << std::cos(angle), -std::sin(angle), tx,
107 std::sin(angle), std::cos(angle), ty, 0., 0., 1.);
112 #endif // TESTING_HELPERS_H_
std::vector< nav_msgs::OccupancyGridConstPtr > loadMaps(InputIt filenames_begin, InputIt filenames_end)
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
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)
void saveMap(const std::string &filename, const nav_msgs::OccupancyGridConstPtr &map)
tf2::Transform randomTransform()