fix file cmake

This commit is contained in:
duongtd 2025-12-02 10:39:03 +07:00
parent 11ff1baa79
commit 747c9697a2
2 changed files with 35 additions and 35 deletions

View File

@ -23,11 +23,6 @@ find_package(GTest REQUIRED) # Google Test cho unit test
find_package(PCL REQUIRED COMPONENTS common io) # Point Cloud Library
find_package(xmlrpcpp REQUIRED) # XML-RPC client/server library
# --- Include other message packages nếu cn ---
# Có th add_subdirectory nếu các package ROS msgs không có target
# ví d sensor_msgs, geometry_msgs, nav_msgs,...
# mc đích đ build mà không cn cài ROS
# --- Define macro đ dùng trong code ---
add_definitions(-DCOSTMAP_2D_DIR="${CMAKE_CURRENT_SOURCE_DIR}")
@ -86,15 +81,26 @@ target_include_directories(costmap_2d
$<INSTALL_INTERFACE:include/${PROJECT_NAME}> # Khi install
)
# --- Cài đt thư vin ---
# --- Cài đt thư vin vào h thng khi chy make install ---
install(TARGETS costmap_2d
EXPORT costmap_2dTargets
EXPORT costmap_2d-targets
ARCHIVE DESTINATION lib # Thư vin tĩnh .a
LIBRARY DESTINATION lib # Thư vin đng .so
RUNTIME DESTINATION bin # File thc thi (nếu )
INCLUDES DESTINATION include # Cài đt include
)
# --- Xut export set costmap_2dTargets thành file CMake module ---
# --- To file lib/cmake/costmap_2d/costmap_2dTargets.cmake ---
# --- File này cha cu hình giúp project khác có th dùng ---
# --- Find_package(costmap_2d REQUIRED) ---
# --- Target_link_libraries(my_app PRIVATE costmap_2d::costmap_2d) ---
install(EXPORT costmap_2d-targets
FILE costmap_2d-targets.cmake
NAMESPACE costmap_2d::
DESTINATION lib/cmake/costmap_2d
)
# --- Cài đt headers ---
install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION include/${PROJECT_NAME}
@ -102,29 +108,23 @@ install(DIRECTORY include/${PROJECT_NAME}/
# --- Plugin libraries ---
# To các plugin shared library
add_library(static_layer SHARED plugins/static_layer.cpp)
target_link_libraries(static_layer costmap_2d ${Boost_LIBRARIES} yaml-cpp)
add_library(plugins
SHARED
plugins/static_layer.cpp
plugins/obstacle_layer.cpp
plugins/inflation_layer.cpp
plugins/voxel_layer.cpp
plugins/critical_layer.cpp
plugins/directional_layer.cpp
plugins/preferred_layer.cpp
plugins/unpreferred_layer.cpp
)
add_library(obstacle_layer SHARED plugins/obstacle_layer.cpp)
target_link_libraries(obstacle_layer costmap_2d ${Boost_LIBRARIES} yaml-cpp)
add_library(inflation_layer SHARED plugins/inflation_layer.cpp)
target_link_libraries(inflation_layer costmap_2d ${Boost_LIBRARIES} yaml-cpp)
add_library(voxel_layer SHARED plugins/voxel_layer.cpp)
target_link_libraries(voxel_layer costmap_2d ${Boost_LIBRARIES} yaml-cpp)
add_library(critical_layer SHARED plugins/critical_layer.cpp)
target_link_libraries(critical_layer costmap_2d static_layer ${Boost_LIBRARIES} yaml-cpp)
add_library(directional_layer SHARED plugins/directional_layer.cpp)
target_link_libraries(directional_layer costmap_2d static_layer ${Boost_LIBRARIES} yaml-cpp)
add_library(preferred_layer SHARED plugins/preferred_layer.cpp)
target_link_libraries(preferred_layer costmap_2d static_layer ${Boost_LIBRARIES} yaml-cpp)
add_library(unpreferred_layer SHARED plugins/unpreferred_layer.cpp)
target_link_libraries(unpreferred_layer costmap_2d static_layer ${Boost_LIBRARIES} yaml-cpp)
target_link_libraries(plugins
costmap_2d
${Boost_LIBRARIES}
yaml-cpp
)
# --- Option đ bt/tt test ---

View File

@ -91,7 +91,7 @@ void Costmap2DROBOT::getParams(const std::string& config_file_name)
YAML::Node config = YAML::LoadFile(path_source);
YAML::Node layer = config["static_layer"];
YAML::Node layer = config["costmap_2d"];
global_frame_ = loadParam(layer, "global_frame", std::string("map"));
robot_base_frame_ = loadParam(layer, "robot_base_frame", std::string("base_link"));
@ -123,10 +123,10 @@ void Costmap2DROBOT::getParams(const std::string& config_file_name)
struct PluginInfo { std::string path; std::string name; };
std::vector<PluginInfo> plugins_to_load = {
{"./costmap_2d/libstatic_layer.so", "create_static_layer"},
{"./costmap_2d/libinflation_layer.so", "create_inflation_layer"},
{"./costmap_2d/libobstacle_layer.so", "create_obstacle_layer"},
{"./costmap_2d/libpreferred_layer.so", "create_preferred_layer"}
{"./src/costmap_2d/libplugins.so", "create_static_layer"},
{"./src/costmap_2d/libplugins.so", "create_inflation_layer"},
{"./src/costmap_2d/libplugins.so", "create_obstacle_layer"},
{"./src/costmap_2d/libplugins.so", "create_preferred_layer"}
};
// if (private_nh.hasParam("plugins"))
@ -158,7 +158,7 @@ void Costmap2DROBOT::getParams(const std::string& config_file_name)
}
// setUnpaddedRobotFootprint(makeFootprintFromParams(private_nh));
transform_tolerance_ = loadParam(layer, "transform_tolerance", false);
if (map_update_thread_ != NULL)
{