Compare commits
2 Commits
3c8e1cdaf5
...
3.0
| Author | SHA1 | Date | |
|---|---|---|---|
| d0ad2d0e21 | |||
| 5583b3e0f2 |
@@ -1,7 +1,7 @@
|
||||
<Project Sdk="Microsoft.NET.Sdk">
|
||||
<PropertyGroup>
|
||||
<OutputType>Exe</OutputType>
|
||||
<TargetFramework>net6.0</TargetFramework>
|
||||
<TargetFramework>net10.0</TargetFramework>
|
||||
<AllowUnsafeBlocks>true</AllowUnsafeBlocks>
|
||||
</PropertyGroup>
|
||||
<ItemGroup>
|
||||
|
||||
@@ -83,6 +83,7 @@ extern "C" NavigationHandle navigation_create(void)
|
||||
// Using default constructor - initialization will be done via navigation_initialize()
|
||||
robot::PluginLoaderHelper loader;
|
||||
std::string path_file_so = loader.findLibraryPath("MoveBase");
|
||||
robot::log_warning("%s", path_file_so.c_str());
|
||||
auto move_base_loader = boost::dll::import_alias<robot::move_base_core::BaseNavigation::Ptr()>(
|
||||
path_file_so, "MoveBase", boost::dll::load_mode::append_decorations);
|
||||
auto move_base_ptr = move_base_loader();
|
||||
|
||||
@@ -174,8 +174,9 @@ namespace two_points_planner
|
||||
// Tính toán khoảng cách giữa điểm bắt đầu và điểm đích
|
||||
const double dx = goal.pose.position.x - start.pose.position.x;
|
||||
const double dy = goal.pose.position.y - start.pose.position.y;
|
||||
double distance = std::sqrt(dx * dx + dy * dy);
|
||||
const double distance = std::sqrt(dx * dx + dy * dy);
|
||||
double theta;
|
||||
|
||||
if(fabs(dx) > 1e-9 || fabs(dy) > 1e-9)
|
||||
{
|
||||
theta = std::atan2(dy, dx);
|
||||
@@ -186,9 +187,13 @@ namespace two_points_planner
|
||||
if(cos(goal_theta - theta) < 0) theta += M_PI;
|
||||
}
|
||||
else
|
||||
{
|
||||
robot::log_error("[%s:%d]\n TwoPointsPlanner: can not calculating theta from 'start point' or 'goal point'", __FILE__, __LINE__);
|
||||
return false;
|
||||
{
|
||||
robot_geometry_msgs::PoseStamped pose = start;
|
||||
pose.pose.position.x += 0.01 * cos(theta);
|
||||
pose.pose.position.y += 0.01 * sin(theta);
|
||||
plan.push_back(pose);
|
||||
plan.push_back(goal);
|
||||
return true;
|
||||
}
|
||||
|
||||
// Lấy độ phân giải của costmap
|
||||
|
||||
@@ -89,7 +89,7 @@ public:
|
||||
|
||||
private:
|
||||
/**
|
||||
* @brief Resolve library path (handle relative paths, search in search_paths)
|
||||
* @brief Resolve library path (absolute, then PNKX_NAV_CORE_LIBRARY_PATH, search_paths_, cwd)
|
||||
* @param library_path Path from config (may be relative or absolute)
|
||||
* @return Resolved absolute path, or empty if not found
|
||||
*/
|
||||
|
||||
@@ -98,7 +98,6 @@ std::string PluginLoaderHelper::findLibraryPath(const std::string& symbol_name)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Try LD_LIBRARY_PATH as fallback
|
||||
const char* ld_path = std::getenv("LD_LIBRARY_PATH");
|
||||
if (ld_path) {
|
||||
@@ -199,21 +198,27 @@ std::string PluginLoaderHelper::resolveLibraryPath(const std::string& library_pa
|
||||
return "";
|
||||
}
|
||||
|
||||
// If relative path, search in search_paths (build directory is already added)
|
||||
std::string build_dir = getBuildDirectory();
|
||||
if (!build_dir.empty()) {
|
||||
// First try in build directory
|
||||
// Add .so extension if not present
|
||||
// If relative path, search under PNKX_NAV_CORE_LIBRARY_PATH (':'-separated, like LD_LIBRARY_PATH)
|
||||
const char* nav_lib_path_env = std::getenv("PNKX_NAV_CORE_LIBRARY_PATH");
|
||||
if (nav_lib_path_env) {
|
||||
std::string lib_path_with_ext = library_path;
|
||||
if (lib_path_with_ext.find(".so") == std::string::npos) {
|
||||
lib_path_with_ext += ".so";
|
||||
}
|
||||
std::filesystem::path full_path = std::filesystem::path(build_dir) / lib_path_with_ext;
|
||||
if (std::filesystem::exists(full_path)) {
|
||||
try {
|
||||
return std::filesystem::canonical(full_path).string();
|
||||
} catch (...) {
|
||||
return full_path.string();
|
||||
std::string nav_lib_paths(nav_lib_path_env);
|
||||
std::stringstream ss(nav_lib_paths);
|
||||
std::string base_dir;
|
||||
while (std::getline(ss, base_dir, ':')) {
|
||||
if (base_dir.empty()) {
|
||||
continue;
|
||||
}
|
||||
std::filesystem::path full_path = std::filesystem::path(base_dir) / lib_path_with_ext;
|
||||
if (std::filesystem::exists(full_path)) {
|
||||
try {
|
||||
return std::filesystem::canonical(full_path).string();
|
||||
} catch (...) {
|
||||
return full_path.string();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -271,6 +271,7 @@ void move_base::MoveBase::initialize(robot::TFListenerPtr tf)
|
||||
{
|
||||
robot::PluginLoaderHelper loader;
|
||||
std::string path_file_so = loader.findLibraryPath(global_planner);
|
||||
robot::log_info("[%s:%d]\n INFO: global_planner library path: %s", __FILE__, __LINE__, path_file_so.c_str());
|
||||
planner_loader_ = boost::dll::import_alias<robot_nav_core::BaseGlobalPlanner::Ptr()>(
|
||||
path_file_so, global_planner, boost::dll::load_mode::append_decorations);
|
||||
|
||||
@@ -314,6 +315,7 @@ void move_base::MoveBase::initialize(robot::TFListenerPtr tf)
|
||||
{
|
||||
robot::PluginLoaderHelper loader;
|
||||
std::string path_file_so = loader.findLibraryPath(local_planner);
|
||||
robot::log_info("[%s:%d]\n INFO: local_planner library path: %s", __FILE__, __LINE__, path_file_so.c_str());
|
||||
controller_loader_ =
|
||||
boost::dll::import_alias<robot_nav_core::BaseLocalPlanner::Ptr()>(
|
||||
path_file_so, local_planner, boost::dll::load_mode::append_decorations);
|
||||
@@ -401,7 +403,7 @@ void move_base::MoveBase::swapPlanner(std::string base_global_planner)
|
||||
boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
|
||||
robot::PluginLoaderHelper loader;
|
||||
std::string path_file_so = loader.findLibraryPath(base_global_planner);
|
||||
|
||||
robot::log_info("[%s:%d]\n INFO: global_planner library path: %s", __FILE__, __LINE__, path_file_so.c_str());
|
||||
auto new_loader = boost::dll::import_alias<robot_nav_core::BaseGlobalPlanner::Ptr()>(
|
||||
path_file_so, base_global_planner, boost::dll::load_mode::append_decorations);
|
||||
auto new_planner = new_loader();
|
||||
@@ -2005,6 +2007,7 @@ bool move_base::MoveBase::loadRecoveryBehaviors(const robot::NodeHandle &node)
|
||||
std::string behavior_name = behavior["name"].as<std::string>();
|
||||
robot::PluginLoaderHelper loader;
|
||||
std::string path_file_so = loader.findLibraryPath(behavior_type);
|
||||
robot::log_info("Loading recovery behavior '%s' of type '%s' from '%s'", behavior_name.c_str(), behavior_type.c_str(), path_file_so.c_str());
|
||||
// Load the factory function from the shared library
|
||||
recovery_loaders_[behavior_name] = boost::dll::import_alias<robot_nav_core::RecoveryBehavior::Ptr()>(
|
||||
path_file_so, behavior_type, boost::dll::load_mode::append_decorations);
|
||||
@@ -2864,7 +2867,7 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal)
|
||||
{
|
||||
robot::log_debug("Goal reached!");
|
||||
resetState();
|
||||
swapPlanner(default_config_.base_global_planner);
|
||||
// swapPlanner(default_config_.base_global_planner);
|
||||
// disable the planner thread
|
||||
boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
|
||||
runPlanner_ = false;
|
||||
@@ -3070,7 +3073,7 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal)
|
||||
{
|
||||
robot::log_debug("All recovery behaviors have failed, locking the planner and disabling it.");
|
||||
resetState();
|
||||
swapPlanner(default_config_.base_global_planner);
|
||||
// swapPlanner(default_config_.base_global_planner);
|
||||
|
||||
// disable the planner thread
|
||||
boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
|
||||
|
||||
Reference in New Issue
Block a user