10 #define __STDC_FORMAT_MACROS 13 #include <nav_msgs/OccupancyGrid.h> 16 #include <mrpt/version.h> 17 #include <mrpt/maps/COccupancyGridMap2D.h> 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);
44 srcRos.info.origin.orientation.x = 1;
46 srcRos.info.origin.orientation.x = 0;
52 for (
uint32_t h = 0; h < srcRos.info.width; h++)
62 TEST(Map, check_ros2mrpt_and_back)
72 for (
uint32_t h = 0; h < srcRos.info.width; h++)
77 desRos.data[h * srcRos.info.width + h],
82 for (
int i = 0; i <= 100; i++)
88 for (
int i = 0; i <= 100; i++)
94 EXPECT_NEAR(srcRos.data[i], desRos.data[i], 1) <<
"ros to mprt to ros";
GLubyte GLubyte GLubyte GLubyte w
#define EXPECT_NEAR(val1, val2, abs_error)
#define ASSERT_TRUE(condition)
TEST(Map, basicTestHeader)
float getResolution() const
bool convert(const mrpt_msgs::ObservationRangeBeacon &_msg, const mrpt::poses::CPose3D &_pose, mrpt::obs::CObservationBeaconRanges &_obj)
unsigned int getSizeY() const
unsigned int getSizeX() const
float getCell(int x, int y) const
#define EXPECT_EQ(val1, val2)
void getEmptyRosMsg(nav_msgs::OccupancyGrid &msg)
#define EXPECT_TRUE(condition)
#define EXPECT_FALSE(condition)
float getPos(float x, float y) const