Compare commits
7 Commits
3.0
...
768a257b33
| Author | SHA1 | Date | |
|---|---|---|---|
| 768a257b33 | |||
| 3c8e1cdaf5 | |||
| cf0c6e7caf | |||
| 6ff54e4154 | |||
| 56ccd202d0 | |||
| e5c04f476b | |||
| f02c20cc5c |
1
.gitignore
vendored
1
.gitignore
vendored
@@ -422,3 +422,4 @@ build
|
|||||||
install
|
install
|
||||||
devel
|
devel
|
||||||
|
|
||||||
|
obstacle
|
||||||
@@ -138,6 +138,22 @@ if (NOT TARGET pnkx_local_planner)
|
|||||||
add_subdirectory(${CMAKE_SOURCE_DIR}/src/Algorithms/Packages/local_planners/pnkx_local_planner)
|
add_subdirectory(${CMAKE_SOURCE_DIR}/src/Algorithms/Packages/local_planners/pnkx_local_planner)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
|
if (NOT TARGET robot_angles)
|
||||||
|
add_subdirectory(${CMAKE_SOURCE_DIR}/obstacle/angles)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (NOT TARGET grid_map_core)
|
||||||
|
add_subdirectory(${CMAKE_SOURCE_DIR}/obstacle/grid_map_core)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (NOT TARGET robot_base_local_planner)
|
||||||
|
add_subdirectory(${CMAKE_SOURCE_DIR}/obstacle/base_local_planner)
|
||||||
|
endif()
|
||||||
|
|
||||||
|
if (NOT TARGET hybrid_local_planner)
|
||||||
|
add_subdirectory(${CMAKE_SOURCE_DIR}/obstacle/hybrid_local_planner)
|
||||||
|
endif()
|
||||||
|
|
||||||
if (NOT TARGET robot_actionlib_msgs)
|
if (NOT TARGET robot_actionlib_msgs)
|
||||||
add_subdirectory(${CMAKE_SOURCE_DIR}/src/Navigations/Libraries/robot_actionlib_msgs)
|
add_subdirectory(${CMAKE_SOURCE_DIR}/src/Navigations/Libraries/robot_actionlib_msgs)
|
||||||
endif()
|
endif()
|
||||||
|
|||||||
@@ -19,17 +19,33 @@ virtual_walls_map:
|
|||||||
lethal_cost_threshold: 100
|
lethal_cost_threshold: 100
|
||||||
|
|
||||||
obstacles:
|
obstacles:
|
||||||
observation_sources: f_scan_marking f_scan_clearing b_scan_marking b_scan_clearing
|
observation_sources: l_scan_marking l_scan_clearing r_scan_marking r_scan_clearing b_scan_marking b_scan_clearing
|
||||||
f_scan_marking:
|
l_scan_marking:
|
||||||
topic: /f_scan
|
topic: /l_scan
|
||||||
data_type: LaserScan
|
data_type: LaserScan
|
||||||
clearing: false
|
clearing: false
|
||||||
marking: true
|
marking: true
|
||||||
inf_is_valid: true
|
inf_is_valid: true
|
||||||
min_obstacle_height: 0.0
|
min_obstacle_height: 0.0
|
||||||
max_obstacle_height: 0.25
|
max_obstacle_height: 0.25
|
||||||
f_scan_clearing:
|
l_scan_clearing:
|
||||||
topic: /f_scan
|
topic: /l_scan
|
||||||
|
data_type: LaserScan
|
||||||
|
clearing: true
|
||||||
|
marking: false
|
||||||
|
inf_is_valid: true
|
||||||
|
min_obstacle_height: 0.0
|
||||||
|
max_obstacle_height: 0.25
|
||||||
|
r_scan_marking:
|
||||||
|
topic: /r_scan
|
||||||
|
data_type: LaserScan
|
||||||
|
clearing: false
|
||||||
|
marking: true
|
||||||
|
inf_is_valid: true
|
||||||
|
min_obstacle_height: 0.0
|
||||||
|
max_obstacle_height: 0.25
|
||||||
|
r_scan_clearing:
|
||||||
|
topic: /r_scan
|
||||||
data_type: LaserScan
|
data_type: LaserScan
|
||||||
clearing: true
|
clearing: true
|
||||||
marking: false
|
marking: false
|
||||||
@@ -52,5 +68,6 @@ obstacles:
|
|||||||
inf_is_valid: true
|
inf_is_valid: true
|
||||||
min_obstacle_height: 0.0
|
min_obstacle_height: 0.0
|
||||||
max_obstacle_height: 0.25
|
max_obstacle_height: 0.25
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -4,7 +4,7 @@ global_costmap:
|
|||||||
global_frame: map
|
global_frame: map
|
||||||
update_frequency: 1.0
|
update_frequency: 1.0
|
||||||
publish_frequency: 1.0
|
publish_frequency: 1.0
|
||||||
raytrace_range: 2.0
|
raytrace_range: 3.5
|
||||||
resolution: 0.05
|
resolution: 0.05
|
||||||
z_resolution: 0.2
|
z_resolution: 0.2
|
||||||
rolling_window: false
|
rolling_window: false
|
||||||
|
|||||||
@@ -5,7 +5,7 @@ local_costmap:
|
|||||||
update_frequency: 6.0
|
update_frequency: 6.0
|
||||||
publish_frequency: 6.0
|
publish_frequency: 6.0
|
||||||
rolling_window: true
|
rolling_window: true
|
||||||
raytrace_range: 2.0
|
raytrace_range: 3.5
|
||||||
resolution: 0.05
|
resolution: 0.05
|
||||||
z_resolution: 0.15
|
z_resolution: 0.15
|
||||||
z_voxels: 8
|
z_voxels: 8
|
||||||
|
|||||||
59
config/hybrid_local_planner_params.yaml
Normal file
59
config/hybrid_local_planner_params.yaml
Normal file
@@ -0,0 +1,59 @@
|
|||||||
|
LocalPlannerAdapter:
|
||||||
|
library_path: liblocal_planner_adapter
|
||||||
|
yaw_goal_tolerance: 0.017
|
||||||
|
xy_goal_tolerance: 0.03
|
||||||
|
min_approach_linear_velocity: 0.06
|
||||||
|
|
||||||
|
HybridLocalPlanner:
|
||||||
|
# base_local_planner: "hybrid_local_planner/HybridLocalPlanner"
|
||||||
|
# HybridLocalPlanner:
|
||||||
|
library_path: libhybrid_local_planner
|
||||||
|
odom_topic: odom
|
||||||
|
# Trajectory
|
||||||
|
max_global_plan_lookahead_dist: 4.0
|
||||||
|
global_plan_viapoint_sep: 0.5
|
||||||
|
global_plan_prune_distance: 0.0
|
||||||
|
global_plan_goal_sep: 0.05
|
||||||
|
|
||||||
|
# Robot
|
||||||
|
|
||||||
|
robot_max_v_ac: 0.4
|
||||||
|
robot_max_w_ac: 0.4
|
||||||
|
robot_max_v_pt: 1.0
|
||||||
|
robot_max_w_pt: 0.4
|
||||||
|
robot_max_v_backwards_pt: -0.2
|
||||||
|
acc_lim_x: 1.0
|
||||||
|
acc_lim_theta: 2.0
|
||||||
|
turn_around_priority: True
|
||||||
|
stop_dist: 0.5
|
||||||
|
dec_dist: 1.0
|
||||||
|
|
||||||
|
|
||||||
|
# GoalTolerance
|
||||||
|
|
||||||
|
xy_goal_tolerance: 0.1
|
||||||
|
yaw_goal_tolerance: 0.07
|
||||||
|
|
||||||
|
# Optimization
|
||||||
|
|
||||||
|
# PP Parameters
|
||||||
|
w_vel: 0.8
|
||||||
|
w_omega: 1.0
|
||||||
|
# DWA Parameters
|
||||||
|
enable_backward_motion: false
|
||||||
|
w_targetheading_ac: 1.7
|
||||||
|
w_velocity_ac: 0.2
|
||||||
|
w_clearance_ac: 0.2
|
||||||
|
w_pathDistance_ac: 0.05
|
||||||
|
w_smoothness_ac: 0.3
|
||||||
|
w_targetheading_pt: 0.2
|
||||||
|
w_velocity_pt: 0.8
|
||||||
|
w_clearance_pt: 0.1
|
||||||
|
w_pathDistance_pt: 2.1
|
||||||
|
w_smoothness_pt: 0.3
|
||||||
|
time_horizon: 3.0
|
||||||
|
velocity_resolution: 0.015
|
||||||
|
|
||||||
|
segment_transition_threshold: 0.01 # Ngưỡng khoảng cách chuyển segment
|
||||||
|
calibration_factor: 1.5 # Hệ số hiệu chuẩn
|
||||||
|
use_obstacle_avoidance: true # Bật tắt tránh vật cản
|
||||||
@@ -37,7 +37,7 @@ charger:
|
|||||||
- {name: charger, docking_planner: "DockPlanner", docking_nav: ""}
|
- {name: charger, docking_planner: "DockPlanner", docking_nav: ""}
|
||||||
|
|
||||||
charger:
|
charger:
|
||||||
maker_goal_frame: charger_goal
|
maker_goal_frame: charger
|
||||||
footprint: [[0.583,-0.48],[0.583,0.48],[-0.583,0.48],[-0.583,-0.48]]
|
footprint: [[0.583,-0.48],[0.583,0.48],[-0.583,0.48],[-0.583,-0.48]]
|
||||||
delay: 1.5 # Cấm sửa không là không chạy được
|
delay: 1.5 # Cấm sửa không là không chạy được
|
||||||
timeout: 60
|
timeout: 60
|
||||||
|
|||||||
@@ -560,7 +560,7 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::dockingHanlde(const robot_nav_
|
|||||||
{
|
{
|
||||||
if(!dkpl_.empty())
|
if(!dkpl_.empty())
|
||||||
{
|
{
|
||||||
if(dkpl_.front()) delete(dkpl_.front());
|
// if(dkpl_.front()) delete(dkpl_.front());
|
||||||
dkpl_.erase(dkpl_.begin());
|
dkpl_.erase(dkpl_.begin());
|
||||||
}
|
}
|
||||||
start_docking_ = false;
|
start_docking_ = false;
|
||||||
|
|||||||
@@ -66,7 +66,6 @@ std::string PluginLoaderHelper::findLibraryPath(const std::string& symbol_name)
|
|||||||
}
|
}
|
||||||
// Try to read from NodeHandle
|
// Try to read from NodeHandle
|
||||||
std::string library_path;
|
std::string library_path;
|
||||||
robot::log_info_at(__FILE__, __LINE__, "%s", symbol_name.c_str());
|
|
||||||
if (nh_.hasParam(param_path)) {
|
if (nh_.hasParam(param_path)) {
|
||||||
nh_.getParam(param_path, library_path, std::string(""));
|
nh_.getParam(param_path, library_path, std::string(""));
|
||||||
if (!library_path.empty()) {
|
if (!library_path.empty()) {
|
||||||
@@ -339,7 +338,7 @@ std::string PluginLoaderHelper::getBuildDirectory()
|
|||||||
std::string PluginLoaderHelper::getWorkspacePath()
|
std::string PluginLoaderHelper::getWorkspacePath()
|
||||||
{
|
{
|
||||||
// Method 1: Từ environment variable PNKX_NAV_CORE_DIR
|
// Method 1: Từ environment variable PNKX_NAV_CORE_DIR
|
||||||
const char* workspace_path = std::getenv("PNKX_NAV_CORE_LIBRARY_PATH");
|
const char* workspace_path = std::getenv("PNKX_NAV_CORE_DIR");
|
||||||
if (workspace_path && std::filesystem::exists(workspace_path)) {
|
if (workspace_path && std::filesystem::exists(workspace_path)) {
|
||||||
return std::string(workspace_path);
|
return std::string(workspace_path);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -271,6 +271,7 @@ void move_base::MoveBase::initialize(robot::TFListenerPtr tf)
|
|||||||
{
|
{
|
||||||
robot::PluginLoaderHelper loader;
|
robot::PluginLoaderHelper loader;
|
||||||
std::string path_file_so = loader.findLibraryPath(global_planner);
|
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()>(
|
planner_loader_ = boost::dll::import_alias<robot_nav_core::BaseGlobalPlanner::Ptr()>(
|
||||||
path_file_so, global_planner, boost::dll::load_mode::append_decorations);
|
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;
|
robot::PluginLoaderHelper loader;
|
||||||
std::string path_file_so = loader.findLibraryPath(local_planner);
|
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_ =
|
controller_loader_ =
|
||||||
boost::dll::import_alias<robot_nav_core::BaseLocalPlanner::Ptr()>(
|
boost::dll::import_alias<robot_nav_core::BaseLocalPlanner::Ptr()>(
|
||||||
path_file_so, local_planner, boost::dll::load_mode::append_decorations);
|
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_);
|
boost::unique_lock<boost::recursive_mutex> lock(planner_mutex_);
|
||||||
robot::PluginLoaderHelper loader;
|
robot::PluginLoaderHelper loader;
|
||||||
std::string path_file_so = loader.findLibraryPath(base_global_planner);
|
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()>(
|
auto new_loader = boost::dll::import_alias<robot_nav_core::BaseGlobalPlanner::Ptr()>(
|
||||||
path_file_so, base_global_planner, boost::dll::load_mode::append_decorations);
|
path_file_so, base_global_planner, boost::dll::load_mode::append_decorations);
|
||||||
auto new_planner = new_loader();
|
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>();
|
std::string behavior_name = behavior["name"].as<std::string>();
|
||||||
robot::PluginLoaderHelper loader;
|
robot::PluginLoaderHelper loader;
|
||||||
std::string path_file_so = loader.findLibraryPath(behavior_type);
|
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
|
// Load the factory function from the shared library
|
||||||
recovery_loaders_[behavior_name] = boost::dll::import_alias<robot_nav_core::RecoveryBehavior::Ptr()>(
|
recovery_loaders_[behavior_name] = boost::dll::import_alias<robot_nav_core::RecoveryBehavior::Ptr()>(
|
||||||
path_file_so, behavior_type, boost::dll::load_mode::append_decorations);
|
path_file_so, behavior_type, boost::dll::load_mode::append_decorations);
|
||||||
|
|||||||
Reference in New Issue
Block a user