Compare commits
3 Commits
8f0cd33ec7
...
main
| Author | SHA1 | Date | |
|---|---|---|---|
| d51ecc0986 | |||
| 56d05e4322 | |||
| da82431cd9 |
@@ -44,6 +44,8 @@ if (NOT BUILDING_WITH_CATKIN)
|
|||||||
robot_cpp
|
robot_cpp
|
||||||
)
|
)
|
||||||
|
|
||||||
|
find_library(TF3_LIBRARY NAMES tf3 PATHS /usr/lib /usr/local/lib /usr/lib/x86_64-linux-gnu)
|
||||||
|
|
||||||
else()
|
else()
|
||||||
|
|
||||||
# ========================================================
|
# ========================================================
|
||||||
@@ -56,7 +58,6 @@ else()
|
|||||||
robot_nav_2d_utils
|
robot_nav_2d_utils
|
||||||
robot_std_msgs
|
robot_std_msgs
|
||||||
robot_geometry_msgs
|
robot_geometry_msgs
|
||||||
tf3
|
|
||||||
robot_time
|
robot_time
|
||||||
data_convert
|
data_convert
|
||||||
robot_costmap_2d
|
robot_costmap_2d
|
||||||
@@ -64,10 +65,15 @@ else()
|
|||||||
robot_cpp
|
robot_cpp
|
||||||
)
|
)
|
||||||
|
|
||||||
|
find_package(Boost REQUIRED COMPONENTS system thread filesystem)
|
||||||
|
find_package(Eigen3 REQUIRED)
|
||||||
|
# Find tf3 library
|
||||||
|
find_library(TF3_LIBRARY NAMES tf3 PATHS /usr/lib /usr/local/lib /usr/lib/x86_64-linux-gnu)
|
||||||
|
|
||||||
catkin_package(
|
catkin_package(
|
||||||
INCLUDE_DIRS include
|
INCLUDE_DIRS include
|
||||||
LIBRARIES ${PROJECT_NAME}
|
LIBRARIES ${PROJECT_NAME}
|
||||||
CATKIN_DEPENDS robot_visualization_msgs robot_nav_msgs robot_nav_2d_msgs robot_nav_2d_utils robot_std_msgs robot_geometry_msgs tf3 robot_time data_convert robot_costmap_2d robot_nav_core robot_cpp
|
CATKIN_DEPENDS robot_visualization_msgs robot_nav_msgs robot_nav_2d_msgs robot_nav_2d_utils robot_std_msgs robot_geometry_msgs robot_time data_convert robot_costmap_2d robot_nav_core robot_cpp
|
||||||
DEPENDS Eigen3 Boost
|
DEPENDS Eigen3 Boost
|
||||||
)
|
)
|
||||||
|
|
||||||
@@ -76,6 +82,7 @@ else()
|
|||||||
${catkin_INCLUDE_DIRS}
|
${catkin_INCLUDE_DIRS}
|
||||||
${EIGEN3_INCLUDE_DIRS}
|
${EIGEN3_INCLUDE_DIRS}
|
||||||
${Boost_INCLUDE_DIRS}
|
${Boost_INCLUDE_DIRS}
|
||||||
|
${TF3_INCLUDE_DIR}
|
||||||
)
|
)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
@@ -97,11 +104,13 @@ if(BUILDING_WITH_CATKIN)
|
|||||||
PUBLIC
|
PUBLIC
|
||||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
$<INSTALL_INTERFACE:include>
|
$<INSTALL_INTERFACE:include>
|
||||||
|
${TF3_INCLUDE_DIR}
|
||||||
)
|
)
|
||||||
|
|
||||||
target_link_libraries(${PROJECT_NAME}
|
target_link_libraries(${PROJECT_NAME}
|
||||||
PUBLIC ${catkin_LIBRARIES}
|
PUBLIC ${catkin_LIBRARIES}
|
||||||
PRIVATE Eigen3::Eigen Boost::system Boost::thread Boost::filesystem
|
PRIVATE Eigen3::Eigen Boost::system Boost::thread Boost::filesystem
|
||||||
|
${TF3_LIBRARY}
|
||||||
)
|
)
|
||||||
|
|
||||||
else()
|
else()
|
||||||
@@ -110,6 +119,7 @@ else()
|
|||||||
PUBLIC
|
PUBLIC
|
||||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||||
$<INSTALL_INTERFACE:include>
|
$<INSTALL_INTERFACE:include>
|
||||||
|
${TF3_INCLUDE_DIR}
|
||||||
)
|
)
|
||||||
|
|
||||||
target_link_libraries(${PROJECT_NAME}
|
target_link_libraries(${PROJECT_NAME}
|
||||||
@@ -117,6 +127,7 @@ else()
|
|||||||
${PACKAGES_DIR}
|
${PACKAGES_DIR}
|
||||||
PRIVATE
|
PRIVATE
|
||||||
Eigen3::Eigen Boost::system Boost::thread Boost::filesystem
|
Eigen3::Eigen Boost::system Boost::thread Boost::filesystem
|
||||||
|
${TF3_LIBRARY}
|
||||||
)
|
)
|
||||||
|
|
||||||
set_target_properties(${PROJECT_NAME} PROPERTIES
|
set_target_properties(${PROJECT_NAME} PROPERTIES
|
||||||
|
|||||||
@@ -19,6 +19,8 @@ namespace dock_planner {
|
|||||||
const robot_geometry_msgs::PoseStamped& goal,
|
const robot_geometry_msgs::PoseStamped& goal,
|
||||||
std::vector<robot_geometry_msgs::PoseStamped>& plan);
|
std::vector<robot_geometry_msgs::PoseStamped>& plan);
|
||||||
|
|
||||||
|
static robot_nav_core::BaseGlobalPlanner::Ptr create();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// Core components
|
// Core components
|
||||||
robot_costmap_2d::Costmap2DROBOT* costmap_robot_;
|
robot_costmap_2d::Costmap2DROBOT* costmap_robot_;
|
||||||
@@ -33,9 +35,6 @@ namespace dock_planner {
|
|||||||
bool check_free_space_;
|
bool check_free_space_;
|
||||||
|
|
||||||
DockCalc calc_plan_to_dock_;
|
DockCalc calc_plan_to_dock_;
|
||||||
|
|
||||||
|
|
||||||
void publishPlan(const std::vector<robot_geometry_msgs::PoseStamped>& plan);
|
|
||||||
};
|
};
|
||||||
} // namespace dock_planner
|
} // namespace dock_planner
|
||||||
|
|
||||||
|
|||||||
@@ -34,8 +34,8 @@
|
|||||||
<build_depend>robot_std_msgs</build_depend>
|
<build_depend>robot_std_msgs</build_depend>
|
||||||
<run_depend>robot_std_msgs</run_depend>
|
<run_depend>robot_std_msgs</run_depend>
|
||||||
|
|
||||||
<build_depend>tf3</build_depend>
|
|
||||||
<run_depend>tf3</run_depend>
|
|
||||||
|
|
||||||
<build_depend>robot_cpp</build_depend>
|
<build_depend>robot_cpp</build_depend>
|
||||||
<run_depend>robot_cpp</run_depend>
|
<run_depend>robot_cpp</run_depend>
|
||||||
|
|||||||
@@ -1,6 +1,7 @@
|
|||||||
#include "dock_planner/dock_planner.h"
|
#include "dock_planner/dock_planner.h"
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <algorithm>
|
#include <algorithm>
|
||||||
|
#include <boost/dll/alias.hpp>
|
||||||
|
|
||||||
namespace dock_planner
|
namespace dock_planner
|
||||||
{
|
{
|
||||||
@@ -79,6 +80,7 @@ namespace dock_planner
|
|||||||
initialized_ = true;
|
initialized_ = true;
|
||||||
// ROS_WARN("[dock_planner] check_free_space_(%d)", check_free_space_);
|
// ROS_WARN("[dock_planner] check_free_space_(%d)", check_free_space_);
|
||||||
}
|
}
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool DockPlanner::makePlan(const robot_geometry_msgs::PoseStamped& start,
|
bool DockPlanner::makePlan(const robot_geometry_msgs::PoseStamped& start,
|
||||||
@@ -108,7 +110,6 @@ namespace dock_planner
|
|||||||
pose.pose.orientation = planMoveToDock[i].orientation;
|
pose.pose.orientation = planMoveToDock[i].orientation;
|
||||||
plan.push_back(pose);
|
plan.push_back(pose);
|
||||||
}
|
}
|
||||||
publishPlan(plan);
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -121,4 +122,13 @@ namespace dock_planner
|
|||||||
// plan_pub_.publish(path_msg);
|
// plan_pub_.publish(path_msg);
|
||||||
// }
|
// }
|
||||||
|
|
||||||
} // namespace dock_planner
|
// Export factory function
|
||||||
|
robot_nav_core::BaseGlobalPlanner::Ptr DockPlanner::create() {
|
||||||
|
return std::make_shared<dock_planner::DockPlanner>();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
} // namespace dock_planner
|
||||||
|
|
||||||
|
// Alias cho Boost.DLL (nếu muốn dùng boost::dll::import_alias)
|
||||||
|
BOOST_DLL_ALIAS(dock_planner::DockPlanner::create, DockPlanner)
|
||||||
|
|||||||
Reference in New Issue
Block a user