first commit
This commit is contained in:
26
nav_msgs/CMakeLists.txt
Normal file
26
nav_msgs/CMakeLists.txt
Normal file
@@ -0,0 +1,26 @@
|
||||
cmake_minimum_required(VERSION 3.10)
|
||||
project(nav_msgs)
|
||||
|
||||
set(CMAKE_CXX_STANDARD 17)
|
||||
set(CMAKE_CXX_STANDARD_REQUIRED ON)
|
||||
|
||||
if (NOT TARGET std_msgs)
|
||||
add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../std_msgs ${CMAKE_BINARY_DIR}/std_msgs_build)
|
||||
endif()
|
||||
if (NOT TARGET geometry_msgs)
|
||||
add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../geometry_msgs ${CMAKE_BINARY_DIR}/geometry_msgs_build)
|
||||
endif()
|
||||
|
||||
# Thư viện header-only
|
||||
add_library(nav_msgs INTERFACE)
|
||||
|
||||
# Include path tới thư mục chứa file header
|
||||
target_include_directories(nav_msgs INTERFACE
|
||||
${CMAKE_CURRENT_SOURCE_DIR}/include
|
||||
)
|
||||
|
||||
# Liên kết với std_msgs nếu bạn có file Header.h trong include/std_msgs/
|
||||
target_link_libraries(nav_msgs INTERFACE
|
||||
std_msgs
|
||||
geometry_msgs
|
||||
)
|
||||
23
nav_msgs/include/nav_msgs/MapMetaData.h
Normal file
23
nav_msgs/include/nav_msgs/MapMetaData.h
Normal file
@@ -0,0 +1,23 @@
|
||||
#ifndef MAP_META_DATA_H
|
||||
#define MAP_META_DATA_H
|
||||
|
||||
#include <cstdint>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include "geometry_msgs/Pose.h"
|
||||
|
||||
namespace nav_msgs
|
||||
{
|
||||
|
||||
struct MapMetaData
|
||||
{
|
||||
double map_load_time;
|
||||
float resolution;
|
||||
uint32_t width;
|
||||
uint32_t height;
|
||||
geometry_msgs::Pose origin;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif //MAP_META_DATA_H
|
||||
24
nav_msgs/include/nav_msgs/OccupancyGrid.h
Normal file
24
nav_msgs/include/nav_msgs/OccupancyGrid.h
Normal file
@@ -0,0 +1,24 @@
|
||||
#ifndef OCCUPANCY_GRID_H
|
||||
#define OCCUPANCY_GRID_H
|
||||
|
||||
#include <cstdint>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include "std_msgs/Header.h"
|
||||
#include <nav_msgs/MapMetaData.h>
|
||||
|
||||
namespace nav_msgs
|
||||
{
|
||||
|
||||
struct OccupancyGrid
|
||||
{
|
||||
std_msgs::Header header;
|
||||
|
||||
MapMetaData info;
|
||||
|
||||
std::vector<uint8_t> data;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif //OCCUPANCY_GRID_H
|
||||
Reference in New Issue
Block a user