Compare commits
1 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 7baa7000b8 |
1
.gitignore
vendored
1
.gitignore
vendored
@@ -422,4 +422,3 @@ build
|
||||
install
|
||||
devel
|
||||
|
||||
obstacle
|
||||
@@ -138,22 +138,6 @@ if (NOT TARGET pnkx_local_planner)
|
||||
add_subdirectory(${CMAKE_SOURCE_DIR}/src/Algorithms/Packages/local_planners/pnkx_local_planner)
|
||||
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)
|
||||
add_subdirectory(${CMAKE_SOURCE_DIR}/src/Navigations/Libraries/robot_actionlib_msgs)
|
||||
endif()
|
||||
|
||||
@@ -19,33 +19,17 @@ virtual_walls_map:
|
||||
lethal_cost_threshold: 100
|
||||
|
||||
obstacles:
|
||||
observation_sources: l_scan_marking l_scan_clearing r_scan_marking r_scan_clearing b_scan_marking b_scan_clearing
|
||||
l_scan_marking:
|
||||
topic: /l_scan
|
||||
observation_sources: f_scan_marking f_scan_clearing b_scan_marking b_scan_clearing
|
||||
f_scan_marking:
|
||||
topic: /f_scan
|
||||
data_type: LaserScan
|
||||
clearing: false
|
||||
marking: true
|
||||
inf_is_valid: true
|
||||
min_obstacle_height: 0.0
|
||||
max_obstacle_height: 0.25
|
||||
l_scan_clearing:
|
||||
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
|
||||
f_scan_clearing:
|
||||
topic: /f_scan
|
||||
data_type: LaserScan
|
||||
clearing: true
|
||||
marking: false
|
||||
@@ -68,6 +52,5 @@ obstacles:
|
||||
inf_is_valid: true
|
||||
min_obstacle_height: 0.0
|
||||
max_obstacle_height: 0.25
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -4,7 +4,7 @@ global_costmap:
|
||||
global_frame: map
|
||||
update_frequency: 1.0
|
||||
publish_frequency: 1.0
|
||||
raytrace_range: 3.5
|
||||
raytrace_range: 2.0
|
||||
resolution: 0.05
|
||||
z_resolution: 0.2
|
||||
rolling_window: false
|
||||
|
||||
@@ -5,7 +5,7 @@ local_costmap:
|
||||
update_frequency: 6.0
|
||||
publish_frequency: 6.0
|
||||
rolling_window: true
|
||||
raytrace_range: 3.5
|
||||
raytrace_range: 2.0
|
||||
resolution: 0.05
|
||||
z_resolution: 0.15
|
||||
z_voxels: 8
|
||||
|
||||
@@ -1,59 +0,0 @@
|
||||
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
|
||||
@@ -398,7 +398,6 @@ robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXDockingLocalPlanner::S
|
||||
else if (!ret_nav_)
|
||||
{
|
||||
traj = nav_algorithm_->calculator(pose, velocity);
|
||||
|
||||
if (!dkpl_.empty() && dkpl_.front()->initialized_ && dkpl_.front()->is_detected_ && !dkpl_.front()->is_goal_reached_)
|
||||
{
|
||||
if (dkpl_.front()->docking_nav_ && !dkpl_.front()->docking_planner_)
|
||||
@@ -406,9 +405,17 @@ robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXDockingLocalPlanner::S
|
||||
traj = dkpl_.front()->docking_nav_->calculator(pose, velocity);
|
||||
}
|
||||
}
|
||||
local_plan_.header.stamp = robot::Time::now();
|
||||
robot_nav_msgs::Path path = robot_nav_2d_utils::poses2DToPath(traj.poses, costmap_robot_->getBaseFrameID(), robot::Time::now());
|
||||
local_plan_ = robot_nav_2d_utils::pathToPath(path);
|
||||
}
|
||||
else
|
||||
{
|
||||
traj = rotate_algorithm_->calculator(pose, velocity);
|
||||
local_plan_.header.stamp = robot::Time::now();
|
||||
robot_nav_msgs::Path path = robot_nav_2d_utils::poses2DToPath(traj.poses, costmap_robot_->getBaseFrameID(), robot::Time::now());
|
||||
local_plan_ = robot_nav_2d_utils::pathToPath(path);
|
||||
}
|
||||
|
||||
cmd_vel.velocity = traj.velocity;
|
||||
return cmd_vel;
|
||||
|
||||
Reference in New Issue
Block a user