8 #include <gtest/gtest.h> 10 #define __STDC_FORMAT_MACROS 13 #include <nav_msgs/OccupancyGrid.h> 16 #include <mrpt/version.h> 17 #include <mrpt/maps/COccupancyGridMap2D.h> 18 using mrpt::maps::COccupancyGridMap2D;
23 msg.info.height = 500;
24 msg.info.resolution = 0.1;
25 msg.info.origin.position.x = rand() % 10 - 5;
26 msg.info.origin.position.y = rand() % 10 - 5;
27 msg.info.origin.position.z = 0;
29 msg.info.origin.orientation.x = 0;
30 msg.info.origin.orientation.y = 0;
31 msg.info.origin.orientation.z = 0;
32 msg.info.origin.orientation.w = 1;
34 msg.data.resize(msg.info.width * msg.info.height, -1);
40 COccupancyGridMap2D desMrpt;
44 srcRos.info.origin.orientation.x = 1;
46 srcRos.info.origin.orientation.x = 0;
49 EXPECT_EQ(srcRos.info.width, desMrpt.getSizeX());
50 EXPECT_EQ(srcRos.info.height, desMrpt.getSizeY());
51 EXPECT_EQ(srcRos.info.resolution, desMrpt.getResolution());
52 for (
int h = 0; h < srcRos.info.width; h++)
54 for (
int w = 0;
w < srcRos.info.width;
w++)
57 desMrpt.getPos(
w, h), 0.5);
62 TEST(Map, check_ros2mrpt_and_back)
65 COccupancyGridMap2D desMrpt;
72 for (
int h = 0; h < srcRos.info.width; h++)
74 for (
int w = 0;
w < srcRos.info.width;
w++)
77 desRos.data[h * srcRos.info.width + h],
82 for (
int i = 0; i <= 100; i++)
88 for (
int i = 0; i <= 100; i++)
92 EXPECT_NEAR(1 - ((
float)i) / 100.0, desMrpt.getCell(i, 0), 0.03)
94 EXPECT_NEAR(srcRos.data[i], desRos.data[i], 1) <<
"ros to mprt to ros";
TEST(Map, basicTestHeader)
bool convert(const mrpt_msgs::ObservationRangeBeacon &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBeaconRanges &_obj)
TFSIMD_FORCE_INLINE const tfScalar & w() const
void getEmptyRosMsg(nav_msgs::OccupancyGrid &msg)