update file cmake

This commit is contained in:
2026-03-30 08:00:01 +00:00
parent 603ea7ff6b
commit 4a84452dc5
5 changed files with 83 additions and 105 deletions

View File

@@ -20,22 +20,17 @@ set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_EXTENSIONS OFF)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
add_compile_options(-Wall -Wextra -Wpedantic)
# ========================================================
# Dependencies common
# Dependencies
# ========================================================
find_package(Boost REQUIRED COMPONENTS thread)
find_package(Eigen3 REQUIRED CONFIG)
if(NOT EIGEN3_INCLUDE_DIRS AND Eigen3_INCLUDE_DIRS)
set(EIGEN3_INCLUDE_DIRS ${Eigen3_INCLUDE_DIRS})
endif()
if(NOT EIGEN3_LIBRARIES AND Eigen3_LIBRARIES)
set(EIGEN3_LIBRARIES ${Eigen3_LIBRARIES})
endif()
find_package(Eigen3 REQUIRED)
# ========================================================
# Catkin
# Catkin configuration
# ========================================================
if(BUILDING_WITH_CATKIN)
@@ -49,31 +44,13 @@ if(BUILDING_WITH_CATKIN)
robot_cpp
tf3
robot_tf3_geometry_msgs
voxel_grid
robot_voxel_grid
data_convert
)
# generate_messages(
# DEPENDENCIES std_msgs
# )
endif()
# ========================================================
# Dynamic reconfigure (only for Catkin)
# ========================================================
if(BUILDING_WITH_CATKIN)
# set(CATKIN_ENV_HOOK_CMAKE_PATH_SETUP_CUSTOM_PYTHONPATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake/setup_custom_pythonpath.sh.in)
# generate_dynamic_reconfigure_options(
# cfg/BaseLocalPlanner.cfg
# )
catkin_package(
INCLUDE_DIRS include
LIBRARIES robot_base_local_planner
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS
robot_angles
robot_costmap_2d
@@ -86,42 +63,53 @@ if(BUILDING_WITH_CATKIN)
robot_tf3_geometry_msgs
robot_voxel_grid
data_convert
DEPENDS Boost
)
include_directories(
include
${catkin_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
DEPENDS Boost Eigen3
)
else()
# =========================
# Standalone build
# =========================
# ========================================================
# Standalone configuration
# ========================================================
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
set(CMAKE_BUILD_RPATH_USE_ORIGIN TRUE)
set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE)
set(CMAKE_BUILD_RPATH "${CMAKE_BINARY_DIR}")
set(PACKAGES_DIR
robot_angles
robot_costmap_2d
robot_std_msgs
robot_geometry_msgs
robot_sensor_msgs
robot_nav_msgs
robot_cpp
tf3
robot_tf3_geometry_msgs
robot_voxel_grid
data_convert
)
endif()
# ========================================================
# Check headers
# ========================================================
include(CheckIncludeFile)
check_include_file(sys/time.h HAVE_SYS_TIME_H)
if(HAVE_SYS_TIME_H)
add_definitions(-DHAVE_SYS_TIME_H)
endif()
# ========================================================
# Libraries
# Library
# ========================================================
add_library(robot_base_local_planner SHARED
add_library(${PROJECT_NAME} SHARED
src/footprint_helper.cpp
src/goal_functions.cpp
src/map_cell.cpp
@@ -140,39 +128,63 @@ add_library(robot_base_local_planner SHARED
src/voxel_grid_model.cpp
)
if(BUILDING_WITH_CATKIN)
add_dependencies(robot_base_local_planner
# ${PROJECT_NAME}_gencfg
# ${PROJECT_NAME}_generate_messages_cpp
# nav_msgs_generate_messages_cpp
${catkin_EXPORTED_TARGETS}
)
endif()
# ========================================================
# Include directories
# ========================================================
target_include_directories(${PROJECT_NAME}
target_include_directories(robot_base_local_planner
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)
target_link_libraries(robot_base_local_planner
# ========================================================
# Dependencies
# ========================================================
if(BUILDING_WITH_CATKIN)
add_dependencies(${PROJECT_NAME}
${catkin_EXPORTED_TARGETS}
)
target_link_libraries(${PROJECT_NAME}
PUBLIC
${Boost_LIBRARIES}
${catkin_LIBRARIES}
PRIVATE
Boost::thread
Eigen3::Eigen
)
if(BUILDING_WITH_CATKIN)
target_link_libraries(robot_base_local_planner PUBLIC ${catkin_LIBRARIES})
endif()
else()
target_link_libraries(${PROJECT_NAME}
PUBLIC
${PACKAGES_DIR}
PRIVATE
Boost::thread
Eigen3::Eigen
)
set_target_properties(${PROJECT_NAME} PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
BUILD_RPATH "${CMAKE_BINARY_DIR}"
INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib"
)
endif()
# ========================================================
# Install
# ========================================================
if(BUILDING_WITH_CATKIN)
install(TARGETS
robot_base_local_planner
install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
@@ -184,14 +196,7 @@ if(BUILDING_WITH_CATKIN)
else()
set_target_properties(robot_base_local_planner PROPERTIES
LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}
BUILD_RPATH "${CMAKE_BINARY_DIR}"
INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/lib"
)
install(TARGETS
robot_base_local_planner
install(TARGETS ${PROJECT_NAME}
EXPORT ${PROJECT_NAME}-targets
LIBRARY DESTINATION lib
ARCHIVE DESTINATION lib
@@ -207,38 +212,11 @@ else()
DESTINATION include
)
install(FILES blp_plugin.xml
DESTINATION share/${PROJECT_NAME}
)
message(STATUS "=================================")
message(STATUS "Project: ${PROJECT_NAME}")
message(STATUS "Version: ${PROJECT_VERSION}")
message(STATUS "C++ Standard: ${CMAKE_CXX_STANDARD}")
message(STATUS "Libraries: robot_base_local_planner")
message(STATUS "Libraries: ${PROJECT_NAME}")
message(STATUS "=================================")
endif()
# ========================================================
# Testing
# ========================================================
# if(BUILDING_WITH_CATKIN AND CATKIN_ENABLE_TESTING)
# find_package(rostest REQUIRED)
# catkin_add_gtest(base_local_planner_utest
# test/gtest_main.cpp
# test/utest.cpp
# test/velocity_iterator_test.cpp
# test/footprint_helper_test.cpp
# test/trajectory_generator_test.cpp
# test/map_grid_test.cpp
# )
# target_link_libraries(base_local_planner_utest
# robot_base_local_planner
# )
# catkin_add_gtest(line_iterator
# test/line_iterator_test.cpp
# )
# endif()

0
cfg/BaseLocalPlanner.cfg Executable file → Normal file
View File

0
cfg/LocalPlannerLimits.cfg Executable file → Normal file
View File

View File

@@ -38,8 +38,8 @@
#define ROBOT_BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_H_
#include <robot/robot.h>
#include <nav_msgs/Odometry.h>
#include <nav_msgs/Path.h>
#include <robot_nav_msgs/Odometry.h>
#include <robot_nav_msgs/Path.h>
#include <robot_geometry_msgs/PoseStamped.h>
#include <robot_geometry_msgs/Twist.h>
#include <robot_geometry_msgs/Point.h>
@@ -136,7 +136,7 @@ namespace robot_base_local_planner {
const robot_costmap_2d::Costmap2D& costmap,
const std::string& global_frame,
robot_geometry_msgs::PoseStamped& global_pose,
const nav_msgs::Odometry& base_odom,
const robot_nav_msgs::Odometry& base_odom,
double rot_stopped_vel, double trans_stopped_vel,
double xy_goal_tolerance, double yaw_goal_tolerance);
@@ -147,7 +147,7 @@ namespace robot_base_local_planner {
* @param trans_stopped_velocity The translational velocity below which the robot is considered stopped
* @return True if the robot is stopped, false otherwise
*/
bool stopped(const nav_msgs::Odometry& base_odom,
bool stopped(const robot_nav_msgs::Odometry& base_odom,
const double& rot_stopped_velocity,
const double& trans_stopped_velocity);
}

View File

@@ -61,7 +61,7 @@ namespace robot_base_local_planner {
// return;
// //create a path message
// nav_msgs::Path gui_path;
// robot_nav_msgs::Path gui_path;
// gui_path.poses.resize(path.size());
// gui_path.header.frame_id = path[0].header.frame_id;
// gui_path.header.stamp = path[0].header.stamp;
@@ -221,7 +221,7 @@ namespace robot_base_local_planner {
const robot_costmap_2d::Costmap2D& costmap GOAL_ATTRIBUTE_UNUSED,
const std::string& global_frame,
robot_geometry_msgs::PoseStamped& global_pose,
const nav_msgs::Odometry& base_odom,
const robot_nav_msgs::Odometry& base_odom,
double rot_stopped_vel, double trans_stopped_vel,
double xy_goal_tolerance, double yaw_goal_tolerance){
@@ -246,7 +246,7 @@ namespace robot_base_local_planner {
return false;
}
bool stopped(const nav_msgs::Odometry& base_odom,
bool stopped(const robot_nav_msgs::Odometry& base_odom,
const double& rot_stopped_velocity, const double& trans_stopped_velocity){
return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity
&& fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity