Compare commits

..

13 Commits

26 changed files with 294 additions and 257 deletions

1
.gitignore vendored
View File

@@ -422,3 +422,4 @@ build
install install
devel devel
obstacle

View File

@@ -20,11 +20,7 @@ The specified base path contains a CMakeLists.txt but "catkin_make" must be invo
# Build trong workspace mới # Build trong workspace mới
cd ../pnkx_nav_catkin_ws cd ../pnkx_nav_catkin_ws
rm -rf build devel catkin_make
catkin_make -DCMAKE_BUILD_TYPE=RelWithDebInfo \
-DCMAKE_CXX_FLAGS="-fsanitize=address -fno-omit-frame-pointer" \
-DCMAKE_C_FLAGS="-fsanitize=address -fno-omit-frame-pointer" \
-DCMAKE_EXE_LINKER_FLAGS="-fsanitize=address"
source devel/setup.bash source devel/setup.bash
``` ```

View File

@@ -356,7 +356,8 @@ export PNKX_NAV_CORE_CONFIG_DIR=/path/to/config
# Chỉ định workspace directory # Chỉ định workspace directory
export PNKX_NAV_CORE_DIR=/path/to/pnkx_nav_core export PNKX_NAV_CORE_DIR=/path/to/pnkx_nav_core
] không install)
# LD_LIBRARY_PATH (nếu không install)
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/path/to/pnkx_nav_core/build/lib export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/path/to/pnkx_nav_core/build/lib
``` ```

View File

@@ -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()

View File

@@ -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

View File

@@ -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

View File

@@ -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

View 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.05
yaw_goal_tolerance: 0.05
# 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

View File

@@ -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

View File

@@ -7,7 +7,7 @@ base_global_planner: CustomPlanner
PNKXLocalPlanner: PNKXLocalPlanner:
base_local_planner: LocalPlannerAdapter base_local_planner: LocalPlannerAdapter
base_global_planner: CustomPlanner base_global_planner: CustomPlanner
PNKXDockingLocalPlanner: PNKXDockingLocalPlanner:
base_local_planner: LocalPlannerAdapter base_local_planner: LocalPlannerAdapter
@@ -30,7 +30,7 @@ max_planning_retries: 0 # ... or after 10 attempts (whichever happens first)
oscillation_timeout: -1 # abort controller and trigger recovery behaviors after 30.0 s oscillation_timeout: -1 # abort controller and trigger recovery behaviors after 30.0 s
oscillation_distance: 0.5 oscillation_distance: 0.5
### recovery behaviors ### recovery behaviors
recovery_behavior_enabled: false recovery_behavior_enabled: true
recovery_behaviors: [ recovery_behaviors: [
{name: aggressive_reset, type: ClearCostmapRecovery}, {name: aggressive_reset, type: ClearCostmapRecovery},
{name: conservative_reset, type: ClearCostmapRecovery}, {name: conservative_reset, type: ClearCostmapRecovery},

View File

@@ -1,5 +1,5 @@
yaw_goal_tolerance: 0.02 yaw_goal_tolerance: 0.03
xy_goal_tolerance: 0.03 xy_goal_tolerance: 0.02
min_approach_linear_velocity: 0.05 min_approach_linear_velocity: 0.05
LocalPlannerAdapter: LocalPlannerAdapter:
@@ -48,17 +48,17 @@ LimitedAccelGenerator:
min_vel_y: 0.0 # diff drive robot min_vel_y: 0.0 # diff drive robot
max_speed_xy: 2.0 # max_trans_vel: 0.8 # choose slightly less than the base's capability max_speed_xy: 2.0 # max_trans_vel: 0.8 # choose slightly less than the base's capability
min_speed_xy: 0.25 # min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity min_speed_xy: 0.15 # min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity
max_vel_theta: 0.4 # max_rot_vel: 1.0 # choose slightly less than the base's capability max_vel_theta: 0.4 # max_rot_vel: 1.0 # choose slightly less than the base's capability
min_vel_theta: 0.05 # min_rot_vel: 0.1 default: 0.4 # this is the min angular velocity when there is negligible translational velocity min_vel_theta: 0.05 # min_rot_vel: 0.1 default: 0.4 # this is the min angular velocity when there is negligible translational velocity
acc_lim_x: 3.0 acc_lim_x: 1.5
acc_lim_y: 0.0 # diff drive robot acc_lim_y: 0.0 # diff drive robot
acc_lim_theta: 1.5 acc_lim_theta: 1.5
decel_lim_x: -3.0 decel_lim_x: -1.5
decel_lim_y: -0.0 decel_lim_y: -0.0
decel_lim_theta: -2.0 decel_lim_theta: -1.5
# Whether to split the path into segments or not # Whether to split the path into segments or not
split_path: true split_path: true
@@ -74,8 +74,8 @@ LimitedAccelGenerator:
MKTAlgorithmDiffPredictiveTrajectory: MKTAlgorithmDiffPredictiveTrajectory:
library_path: libmkt_algorithm_diff library_path: libmkt_algorithm_diff
xy_local_goal_tolerance: 0.05 xy_local_goal_tolerance: 0.02
angle_threshold: 0.6 angle_threshold: 0.47
index_samples: 60 index_samples: 60
follow_step_path: true follow_step_path: true
@@ -106,8 +106,8 @@ MKTAlgorithmDiffPredictiveTrajectory:
angular_decel_zone: 0.1 angular_decel_zone: 0.1
# stoped # stoped
rot_stopped_velocity: 0.03 rot_stopped_velocity: 0.05
trans_stopped_velocity: 0.03 trans_stopped_velocity: 0.06
use_final_heading_alignment: true use_final_heading_alignment: true
final_heading_xy_tolerance: 0.1 final_heading_xy_tolerance: 0.1
@@ -119,7 +119,7 @@ MKTAlgorithmDiffPredictiveTrajectory:
MKTAlgorithmDiffGoStraight: MKTAlgorithmDiffGoStraight:
library_path: libmkt_algorithm_diff library_path: libmkt_algorithm_diff
xy_local_goal_tolerance: 0.05 xy_local_goal_tolerance: 0.02
angle_threshold: 0.8 angle_threshold: 0.8
index_samples: 60 index_samples: 60
follow_step_path: true follow_step_path: true
@@ -143,8 +143,8 @@ MKTAlgorithmDiffGoStraight:
angular_decel_zone: 0.1 angular_decel_zone: 0.1
# stoped # stoped
rot_stopped_velocity: 0.03 rot_stopped_velocity: 0.05
trans_stopped_velocity: 0.03 trans_stopped_velocity: 0.06
use_final_heading_alignment: true use_final_heading_alignment: true
final_heading_xy_tolerance: 0.1 final_heading_xy_tolerance: 0.1
@@ -156,7 +156,7 @@ MKTAlgorithmDiffGoStraight:
MKTAlgorithmDiffRotateToGoal: MKTAlgorithmDiffRotateToGoal:
library_path: libmkt_algorithm_diff library_path: libmkt_algorithm_diff
xy_local_goal_tolerance: 0.05 xy_local_goal_tolerance: 0.02
angle_threshold: 0.47 angle_threshold: 0.47
index_samples: 60 index_samples: 60
follow_step_path: true follow_step_path: true
@@ -180,8 +180,8 @@ MKTAlgorithmDiffRotateToGoal:
angular_decel_zone: 0.1 angular_decel_zone: 0.1
# stoped # stoped
rot_stopped_velocity: 0.03 rot_stopped_velocity: 0.05
trans_stopped_velocity: 0.03 trans_stopped_velocity: 0.06
use_final_heading_alignment: true use_final_heading_alignment: true
final_heading_xy_tolerance: 0.1 final_heading_xy_tolerance: 0.1

View File

@@ -569,16 +569,10 @@ extern "C" bool navigation_set_twist_linear(NavigationHandle handle,
return false; return false;
robot_geometry_msgs::Vector3 linear; robot_geometry_msgs::Vector3 linear;
linear.x = 0.1; linear.x = linear_x;
linear.y = linear_y; linear.y = linear_y;
linear.z = linear_z; linear.z = linear_z;
bool result = nav_ptr->setTwistLinear(linear); return nav_ptr->setTwistLinear(linear);
robot::log_info("setTwistLinear Forward %f", linear.x);
linear.x = -0.1;
result &= result && nav_ptr->setTwistLinear(linear);
robot::log_info("setTwistLinear Backward %f", linear.x);
return result;
} }
catch (...) catch (...)
{ {

View File

@@ -206,7 +206,7 @@ bool score_algorithm::ScoreAlgorithm::computePlanCommand(const robot_nav_2d_msgs
// Process index_s with multiple elements // Process index_s with multiple elements
if (index_s.size() > 1) if (index_s.size() > 1)
{ {
for (size_t i = 1; i < index_s.size(); ++i) for (size_t i = 0; i < index_s.size(); ++i)
{ {
if (index_s[i - 1] >= (unsigned int)global_plan.poses.size() || index_s[i] >= (unsigned int)global_plan.poses.size()) if (index_s[i - 1] >= (unsigned int)global_plan.poses.size() || index_s[i] >= (unsigned int)global_plan.poses.size())
{ {
@@ -219,12 +219,11 @@ bool score_algorithm::ScoreAlgorithm::computePlanCommand(const robot_nav_2d_msgs
double x = cos(global_plan.poses[index_s[i - 1]].pose.theta) * dx + sin(global_plan.poses[index_s[i - 1]].pose.theta) * dy; double x = cos(global_plan.poses[index_s[i - 1]].pose.theta) * dx + sin(global_plan.poses[index_s[i - 1]].pose.theta) * dy;
double y = -sin(global_plan.poses[index_s[i - 1]].pose.theta) * dx + cos(global_plan.poses[index_s[i - 1]].pose.theta) * dy; double y = -sin(global_plan.poses[index_s[i - 1]].pose.theta) * dx + cos(global_plan.poses[index_s[i - 1]].pose.theta) * dy;
if (std::abs(std::sqrt(dx * dx + dy * dy)) <= xy_local_goal_tolerance_ + 0.2) if (std::abs(std::sqrt(dx * dx + dy * dy)) <= xy_local_goal_tolerance_ + 0.1)
{ {
double tolerance = fabs(cos(theta)) >= fabs(sin(theta)) ? x : y; double tolerance = fabs(cos(theta)) >= fabs(sin(theta)) ? x : y;
if (fabs(tolerance) <= xy_local_goal_tolerance_) if (fabs(tolerance) <= xy_local_goal_tolerance_)
{ {
if (index_s[i] > sub_goal_index_saved_) if (index_s[i] > sub_goal_index_saved_)
{ {
sub_goal_index = (i < index_s.size() - 1) ? index_s[i] : (unsigned int)global_plan.poses.size() - 1; sub_goal_index = (i < index_s.size() - 1) ? index_s[i] : (unsigned int)global_plan.poses.size() - 1;
@@ -258,7 +257,7 @@ bool score_algorithm::ScoreAlgorithm::computePlanCommand(const robot_nav_2d_msgs
double theta = angles::normalize_angle(robot_pose.pose.theta - global_plan.poses[sub_goal_index].pose.theta); double theta = angles::normalize_angle(robot_pose.pose.theta - global_plan.poses[sub_goal_index].pose.theta);
double x = cos(global_plan.poses[sub_goal_index].pose.theta) * dx + sin(global_plan.poses[sub_goal_index].pose.theta) * dy; double x = cos(global_plan.poses[sub_goal_index].pose.theta) * dx + sin(global_plan.poses[sub_goal_index].pose.theta) * dy;
double y = -sin(global_plan.poses[sub_goal_index].pose.theta) * dx + cos(global_plan.poses[sub_goal_index].pose.theta) * dy; double y = -sin(global_plan.poses[sub_goal_index].pose.theta) * dx + cos(global_plan.poses[sub_goal_index].pose.theta) * dy;
if (std::abs(std::sqrt(dx * dx + dy * dy)) <= xy_local_goal_tolerance_ + 0.2) if (std::abs(std::sqrt(dx * dx + dy * dy)) <= xy_local_goal_tolerance_ + 0.1)
{ {
double tolerance = fabs(cos(theta)) >= fabs(sin(theta)) ? x : y; double tolerance = fabs(cos(theta)) >= fabs(sin(theta)) ? x : y;
if (fabs(tolerance) <= xy_local_goal_tolerance_) if (fabs(tolerance) <= xy_local_goal_tolerance_)
@@ -416,7 +415,7 @@ bool score_algorithm::ScoreAlgorithm::computePlanCommand(const robot_nav_2d_msgs
robot_nav_2d_msgs::Pose2DStamped sub_pose; robot_nav_2d_msgs::Pose2DStamped sub_pose;
sub_pose = global_plan.poses[closet_index]; sub_pose = global_plan.poses[closet_index];
#ifdef BUILD_WITH_ROS #ifdef SCORE_ALGORITHM_WITH_ROS
{ {
robot_geometry_msgs::PoseStamped sub_pose_stamped = robot_nav_2d_utils::pose2DToPoseStamped(sub_pose); robot_geometry_msgs::PoseStamped sub_pose_stamped = robot_nav_2d_utils::pose2DToPoseStamped(sub_pose);
geometry_msgs::PoseStamped sub_pose_stamped_ros; geometry_msgs::PoseStamped sub_pose_stamped_ros;
@@ -424,7 +423,7 @@ bool score_algorithm::ScoreAlgorithm::computePlanCommand(const robot_nav_2d_msgs
sub_pose_stamped_ros.header.frame_id = sub_pose_stamped.header.frame_id; sub_pose_stamped_ros.header.frame_id = sub_pose_stamped.header.frame_id;
sub_pose_stamped_ros.pose.position.x = sub_pose_stamped.pose.position.x; sub_pose_stamped_ros.pose.position.x = sub_pose_stamped.pose.position.x;
sub_pose_stamped_ros.pose.position.y = sub_pose_stamped.pose.position.y; sub_pose_stamped_ros.pose.position.y = sub_pose_stamped.pose.position.y;
sub_pose_stamped_ros.pose.position.z = 0.9; sub_pose_stamped_ros.pose.position.z = sub_pose_stamped.pose.position.z;
sub_pose_stamped_ros.pose.orientation.x = sub_pose_stamped.pose.orientation.x; sub_pose_stamped_ros.pose.orientation.x = sub_pose_stamped.pose.orientation.x;
sub_pose_stamped_ros.pose.orientation.y = sub_pose_stamped.pose.orientation.y; sub_pose_stamped_ros.pose.orientation.y = sub_pose_stamped.pose.orientation.y;
sub_pose_stamped_ros.pose.orientation.z = sub_pose_stamped.pose.orientation.z; sub_pose_stamped_ros.pose.orientation.z = sub_pose_stamped.pose.orientation.z;
@@ -435,7 +434,7 @@ bool score_algorithm::ScoreAlgorithm::computePlanCommand(const robot_nav_2d_msgs
robot_nav_2d_msgs::Pose2DStamped sub_goal; robot_nav_2d_msgs::Pose2DStamped sub_goal;
sub_goal = global_plan.poses[goal_index]; sub_goal = global_plan.poses[goal_index];
#ifdef BUILD_WITH_ROS #ifdef SCORE_ALGORITHM_WITH_ROS
{ {
robot_geometry_msgs::PoseStamped sub_goal_stamped = robot_nav_2d_utils::pose2DToPoseStamped(sub_goal); robot_geometry_msgs::PoseStamped sub_goal_stamped = robot_nav_2d_utils::pose2DToPoseStamped(sub_goal);
geometry_msgs::PoseStamped sub_goal_stamped_ros; geometry_msgs::PoseStamped sub_goal_stamped_ros;
@@ -443,7 +442,7 @@ bool score_algorithm::ScoreAlgorithm::computePlanCommand(const robot_nav_2d_msgs
sub_goal_stamped_ros.header.frame_id = sub_goal_stamped.header.frame_id; sub_goal_stamped_ros.header.frame_id = sub_goal_stamped.header.frame_id;
sub_goal_stamped_ros.pose.position.x = sub_goal_stamped.pose.position.x; sub_goal_stamped_ros.pose.position.x = sub_goal_stamped.pose.position.x;
sub_goal_stamped_ros.pose.position.y = sub_goal_stamped.pose.position.y; sub_goal_stamped_ros.pose.position.y = sub_goal_stamped.pose.position.y;
sub_goal_stamped_ros.pose.position.z = 0.9; sub_goal_stamped_ros.pose.position.z = sub_goal_stamped.pose.position.z;
sub_goal_stamped_ros.pose.orientation.x = sub_goal_stamped.pose.orientation.x; sub_goal_stamped_ros.pose.orientation.x = sub_goal_stamped.pose.orientation.x;
sub_goal_stamped_ros.pose.orientation.y = sub_goal_stamped.pose.orientation.y; sub_goal_stamped_ros.pose.orientation.y = sub_goal_stamped.pose.orientation.y;
sub_goal_stamped_ros.pose.orientation.z = sub_goal_stamped.pose.orientation.z; sub_goal_stamped_ros.pose.orientation.z = sub_goal_stamped.pose.orientation.z;

View File

@@ -181,7 +181,7 @@ namespace mkt_algorithm
*/ */
robot_nav_2d_msgs::Path2D generateTrajectory( robot_nav_2d_msgs::Path2D generateTrajectory(
const robot_nav_2d_msgs::Path2D &path, const robot_nav_2d_msgs::Twist2D &drive_target, const robot_nav_2d_msgs::Path2D &path, const robot_nav_2d_msgs::Twist2D &drive_target,
const robot_nav_2d_msgs::Twist2D &velocity, const double &sign_x, robot_nav_2d_msgs::Twist2D &drive_cmd, const double &dt); const robot_nav_2d_msgs::Twist2D &velocity, const double &sign_x, robot_nav_2d_msgs::Twist2D &drive_cmd);
/** /**
* @brief Generate trajectory * @brief Generate trajectory
@@ -194,11 +194,11 @@ namespace mkt_algorithm
/** /**
* @brief Generate Hermite trajectory * @brief Generate Hermite trajectory
* @param path * @param pose
* @param sign_x * @param sign_x
* @return trajectory * @return trajectory
*/ */
robot_nav_2d_msgs::Path2D generateHermiteTrajectory(const robot_nav_2d_msgs::Path2D &path, const double &sign_x); robot_nav_2d_msgs::Path2D generateHermiteTrajectory(const robot_nav_2d_msgs::Pose2DStamped &pose, const double &sign_x);
/** /**
* @brief Generate Hermite quadratic trajectory * @brief Generate Hermite quadratic trajectory
@@ -206,7 +206,7 @@ namespace mkt_algorithm
* @param sign_x * @param sign_x
* @return trajectory * @return trajectory
*/ */
robot_nav_2d_msgs::Path2D generateHermiteQuadraticTrajectory(const robot_nav_2d_msgs::Path2D &path, const double &sign_x); robot_nav_2d_msgs::Path2D generateHermiteQuadraticTrajectory(const robot_nav_2d_msgs::Pose2DStamped &pose, const double &sign_x);
/** /**
* @brief Should rotate to path * @brief Should rotate to path

View File

@@ -131,19 +131,19 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::GoStraight::calculator(
auto carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan); auto carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan);
robot_geometry_msgs::PoseStamped carrot_pose_stamped = robot_nav_2d_utils::pose2DToPoseStamped(carrot_pose); robot_geometry_msgs::PoseStamped carrot_pose_stamped = robot_nav_2d_utils::pose2DToPoseStamped(carrot_pose);
// // === Final Heading Alignment Check === // === Final Heading Alignment Check ===
// double xy_error = 0.0, heading_error = 0.0; double xy_error = 0.0, heading_error = 0.0;
// if (shouldAlignToFinalHeading(transformed_plan, carrot_pose, velocity, xy_error, heading_error, sign_x)) if (shouldAlignToFinalHeading(transformed_plan, carrot_pose, velocity, xy_error, heading_error, sign_x))
// { {
// // Use Arc Motion controller for final heading alignment // Use Arc Motion controller for final heading alignment
// alignToFinalHeading(xy_error, heading_error, velocity, sign_x, dt, drive_cmd); alignToFinalHeading(xy_error, heading_error, velocity, sign_x, dt, drive_cmd);
// #ifdef BUILD_WITH_ROS #ifdef BUILD_WITH_ROS
// ROS_INFO("xy_err=%.3f, heading_err=%.3f deg, v=%.3f, w_current=%.3f, w_target=%.3f", ROS_INFO("xy_err=%.3f, heading_err=%.3f deg, v=%.3f, w_current=%.3f, w_target=%.3f",
// xy_error, heading_error * 180.0 / M_PI, drive_cmd.x, velocity.theta, drive_cmd.theta); xy_error, heading_error * 180.0 / M_PI, drive_cmd.x, velocity.theta, drive_cmd.theta);
// #endif #endif
// } }
// else else
// { {
// robot::log_info_at(__FILE__, __LINE__, "journey : %f lookahead_dist : %f", // robot::log_info_at(__FILE__, __LINE__, "journey : %f lookahead_dist : %f",
// journey(transformed_plan.poses, 0, transformed_plan.poses.size() - 1), lookahead_dist); // journey(transformed_plan.poses, 0, transformed_plan.poses.size() - 1), lookahead_dist);
if(fabs(carrot_pose.pose.y) > 0.2) if(fabs(carrot_pose.pose.y) > 0.2)
@@ -151,7 +151,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::GoStraight::calculator(
lookahead_dist = sqrt(carrot_pose.pose.y *carrot_pose.pose.y + lookahead_dist * lookahead_dist); lookahead_dist = sqrt(carrot_pose.pose.y *carrot_pose.pose.y + lookahead_dist * lookahead_dist);
} }
robot_nav_2d_msgs::Twist2D drive_target; robot_nav_2d_msgs::Twist2D drive_target;
transformed_plan = this->generateTrajectory(transformed_plan, drive_cmd, velocity, sign_x, drive_target, dt); transformed_plan = this->generateTrajectory(transformed_plan, drive_cmd, velocity, sign_x, drive_target);
carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan); carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan);
// Normal Pure Pursuit // Normal Pure Pursuit
@@ -164,7 +164,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::GoStraight::calculator(
sign_x, sign_x,
dt, dt,
drive_cmd); drive_cmd);
// } }
applyDistanceSpeedScaling(compute_plan_, velocity, drive_cmd, sign_x, dt); applyDistanceSpeedScaling(compute_plan_, velocity, drive_cmd, sign_x, dt);
if (this->nav_stop_) if (this->nav_stop_)

View File

@@ -368,7 +368,6 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
robot::log_warning("[%s:%d]\n Could not transform the global plan to the frame of the controller", __FILE__, __LINE__); robot::log_warning("[%s:%d]\n Could not transform the global plan to the frame of the controller", __FILE__, __LINE__);
return false; return false;
} }
const auto carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transform_plan_); const auto carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transform_plan_);
if(fabs(carrot_pose.pose.y) > 0.2) if(fabs(carrot_pose.pose.y) > 0.2)
{ {
@@ -405,47 +404,42 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
} }
} }
else if(compute_plan_.poses.size() == 1) else
{ {
try try
{ {
// auto carrot_pose_it = getLookAheadPoint(velocity, lookahead_dist, transform_plan_); auto carrot_pose_it = getLookAheadPoint(velocity, lookahead_dist, transform_plan_);
// auto prev_carrot_pose_it = transform_plan_.poses.begin(); auto prev_carrot_pose_it = transform_plan_.poses.begin();
// double distance_it = 0; double distance_it = 0;
// for (auto it = carrot_pose_it - 1; it != transform_plan_.poses.begin(); --it) for (auto it = carrot_pose_it - 1; it != transform_plan_.poses.begin(); --it)
// { {
// double dx = it->pose.x - carrot_pose_it->pose.x; double dx = it->pose.x - carrot_pose_it->pose.x;
// double dy = it->pose.y - carrot_pose_it->pose.y; double dy = it->pose.y - carrot_pose_it->pose.y;
// distance_it += std::hypot(dx, dy); distance_it += std::hypot(dx, dy);
// if (distance_it > costmap_robot_->getCostmap()->getResolution()) if (distance_it > costmap_robot_->getCostmap()->getResolution())
// { {
// prev_carrot_pose_it = it; prev_carrot_pose_it = it;
// break; break;
// } }
// } }
// robot_geometry_msgs::Pose front = journey(transform_plan_.poses, 0, transform_plan_.poses.size() - 1) > 5.0 * costmap_robot_->getCostmap()->getResolution() robot_geometry_msgs::Pose front = journey(transform_plan_.poses, 0, transform_plan_.poses.size() - 1) > 5.0 * costmap_robot_->getCostmap()->getResolution()
// ? robot_nav_2d_utils::pose2DToPose((*(prev_carrot_pose_it)).pose) ? robot_nav_2d_utils::pose2DToPose((*(prev_carrot_pose_it)).pose)
// : robot_nav_2d_utils::pose2DToPose(robot_geometry_msgs::Pose2D()); : robot_nav_2d_utils::pose2DToPose(robot_geometry_msgs::Pose2D());
// robot_geometry_msgs::Pose back = robot_nav_2d_utils::pose2DToPose((*(carrot_pose_it)).pose); robot_geometry_msgs::Pose back = robot_nav_2d_utils::pose2DToPose((*(carrot_pose_it)).pose);
// teb_local_planner::PoseSE2 start_pose(front); // teb_local_planner::PoseSE2 start_pose(front);
// teb_local_planner::PoseSE2 goal_pose(back); // teb_local_planner::PoseSE2 goal_pose(back);
// const double dir_path = (goal_pose.position() - start_pose.position()).dot(start_pose.orientationUnitVec()); // const double dir_path = (goal_pose.position() - start_pose.position()).dot(start_pose.orientationUnitVec());
const double dir_path = 0.0;
auto goal_pose = compute_plan_.poses.front().pose;
auto start_pose = pose.pose;
double angle_path = atan2(goal_pose.y - start_pose.y, goal_pose.x - start_pose.x);
double dir_path = cos(fabs(angle_path - goal_pose.theta));
if (fabs(dir_path) > M_PI / 6 || x_direction < 1e-9) if (fabs(dir_path) > M_PI / 6 || x_direction < 1e-9)
x_direction = dir_path > 0 ? FORWARD : BACKWARD; x_direction = dir_path > 0 ? FORWARD : BACKWARD;
} }
catch (std::exception &e) catch (std::exception &e)
{ {
robot::log_warning_throttle(0.2, "[%s:%d]\n getLookAheadPoint throw an exception: %s", __FILE__, __LINE__, e.what()); robot::log_error("[%s:%d]\n getLookAheadPoint throw an exception: %s", __FILE__, __LINE__, e.what());
x_direction = x_direction_; return false;
} }
} }
@@ -483,8 +477,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
} }
double v_max = sign_x > 0 ? traj_->getTwistLinear(true).x : traj_->getTwistLinear(false).x; double v_max = sign_x > 0 ? traj_->getTwistLinear(true).x : traj_->getTwistLinear(false).x;
drive_cmd.x = std::min(sqrt(twist.x * twist.x), fabs(v_max)); drive_cmd.x = std::min(sqrt(twist.x * twist.x), fabs(v_max));
// drive_cmd.x = sqrt(twist.x * twist.x);
robot_nav_2d_msgs::Path2D transformed_plan = this->transform_plan_; robot_nav_2d_msgs::Path2D transformed_plan = this->transform_plan_;
if (transformed_plan.poses.empty()) if (transformed_plan.poses.empty())
{ {
@@ -520,12 +513,8 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
const double distance_allow_rotate = min_journey_squared_; const double distance_allow_rotate = min_journey_squared_;
const double path_distance_to_rotate = journey(transformed_plan.poses, 0, transformed_plan.poses.size() - 1); const double path_distance_to_rotate = journey(transformed_plan.poses, 0, transformed_plan.poses.size() - 1);
allow_rotate |= path_distance_to_rotate >= distance_allow_rotate; allow_rotate |= path_distance_to_rotate >= distance_allow_rotate;
// robot_geometry_msgs::Pose2D back_pose = transformed_plan.poses.back().pose; allow_rotate &= std::hypot(compute_plan_.poses.front().pose.x - pose.pose.x, compute_plan_.poses.front().pose.y - pose.pose.y) <= 0.1;
// allow_rotate |= fabs(atan2(back_pose.y, back_pose.x) - back_pose.theta) > M_PI / 3.0; double angle_to_heading;
allow_rotate &= (fabs(transformed_plan.poses.front().pose.y) <= 0.5);
double angle_to_heading;
if (allow_rotate && shouldRotateToPath(transformed_plan, carrot_pose, velocity, angle_to_heading, sign_x)) if (allow_rotate && shouldRotateToPath(transformed_plan, carrot_pose, velocity, angle_to_heading, sign_x))
{ {
if (!stopped(velocity, max_vel_theta_ + rot_stopped_velocity_, trans_stopped_velocity_)) if (!stopped(velocity, max_vel_theta_ + rot_stopped_velocity_, trans_stopped_velocity_))
@@ -540,23 +529,26 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
} }
else else
{ {
// // === Final Heading Alignment Check === // === Final Heading Alignment Check ===
// double xy_error = 0.0, heading_error = 0.0; double xy_error = 0.0, heading_error = 0.0;
// if (shouldAlignToFinalHeading(transformed_plan, carrot_pose, velocity, xy_error, heading_error, sign_x)) if (shouldAlignToFinalHeading(transformed_plan, carrot_pose, velocity, xy_error, heading_error, sign_x))
// { {
// // Use Arc Motion controller for final heading alignment // Use Arc Motion controller for final heading alignment
// alignToFinalHeading(xy_error, heading_error, velocity, sign_x, dt, drive_cmd); alignToFinalHeading(xy_error, heading_error, velocity, sign_x, dt, drive_cmd);
// #ifdef BUILD_WITH_ROS #ifdef BUILD_WITH_ROS
// ROS_INFO("heading_err=%.3f deg, v=%.3f, w_current=%.3f, w_target=%.3f", ROS_INFO("heading_err=%.3f deg, v=%.3f, w_current=%.3f, w_target=%.3f",
// heading_error * 180.0 / M_PI, drive_cmd.x, velocity.theta, drive_cmd.theta); heading_error * 180.0 / M_PI, drive_cmd.x, velocity.theta, drive_cmd.theta);
// #endif #endif
// } }
// else else
// { {
// if(fabs(carrot_pose.pose.y) > 0.2)
// {
// lookahead_dist = sqrt(carrot_pose.pose.y *carrot_pose.pose.y + lookahead_dist * lookahead_dist);
// }
robot_nav_2d_msgs::Twist2D drive_target = drive_cmd; robot_nav_2d_msgs::Twist2D drive_target = drive_cmd;
transformed_plan = this->generateTrajectory(transformed_plan, drive_cmd, velocity, sign_x, drive_target, dt); // transformed_plan = this->generateTrajectory(transformed_plan, drive_cmd, velocity, sign_x, drive_target);
carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan); // carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan);
// Normal Pure Pursuit // Normal Pure Pursuit
this->computePurePursuit( this->computePurePursuit(
carrot_pose, carrot_pose,
@@ -567,7 +559,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
sign_x, sign_x,
dt, dt,
drive_cmd); drive_cmd);
// } }
applyDistanceSpeedScaling(compute_plan_, velocity, drive_cmd, sign_x, dt); applyDistanceSpeedScaling(compute_plan_, velocity, drive_cmd, sign_x, dt);
if (this->nav_stop_) if (this->nav_stop_)
{ {
@@ -581,7 +573,6 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
result.velocity = drive_cmd; result.velocity = drive_cmd;
return result; return result;
} }
} }
result.poses.clear(); result.poses.clear();
result.poses.reserve(transformed_plan.poses.size()); result.poses.reserve(transformed_plan.poses.size());
@@ -595,11 +586,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
} }
if(fabs(v_max == 0.0)) if(fabs(v_max == 0.0))
{
drive_cmd.x = 0.0; drive_cmd.x = 0.0;
robot::log_warning_throttle(0.2, "[%s:%d]\n v_max is 0.0", __FILE__, __LINE__);
return result;
}
result.velocity = drive_cmd; result.velocity = drive_cmd;
prevous_drive_cmd_ = drive_cmd; prevous_drive_cmd_ = drive_cmd;
return result; return result;
@@ -625,15 +612,15 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
// 3) Adjust speed using Hermite trajectory curvature + remaining distance // 3) Adjust speed using Hermite trajectory curvature + remaining distance
double v_target = adjustSpeedWithHermiteTrajectory(velocity, trajectory, drive_target.x, sign_x); double v_target = adjustSpeedWithHermiteTrajectory(velocity, trajectory, drive_target.x, sign_x);
// const double L_min = 0.1; // m, chỉnh theo nhu cầu const double L_min = 0.1; // m, chỉnh theo nhu cầu
// double scale_close = std::clamp(L / L_min, 0.0, 1.0); double scale_close = std::clamp(L / L_min, 0.0, 1.0);
// v_target *= scale_close; v_target *= scale_close;
const double y_abs = std::fabs(carrot_pose.pose.y); const double y_abs = std::fabs(carrot_pose.pose.y);
const double y_soft = 0.1; const double y_soft = 0.1;
if (y_abs > y_soft) if (y_abs > y_soft)
{ {
double scale = y_soft / y_abs; // y càng lớn => scale càng nhỏ double scale = y_soft / y_abs; // y càng lớn => scale càng nhỏ
scale = std::clamp(scale, 0.6, 1.0); // không giảm quá sâu scale = std::clamp(scale, 0.2, 1.0); // không giảm quá sâu
v_target *= scale; v_target *= scale;
robot_nav_2d_msgs::Twist2D cmd, result; robot_nav_2d_msgs::Twist2D cmd, result;
cmd.x = v_target; cmd.x = v_target;
@@ -644,8 +631,9 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
// 4) Maintain minimum approach speed // 4) Maintain minimum approach speed
if (std::fabs(v_target) < min_approach_linear_velocity) if (std::fabs(v_target) < min_approach_linear_velocity)
v_target = std::copysign(min_approach_linear_velocity, sign_x); v_target = std::copysign(min_approach_linear_velocity, sign_x);
// 5) Angular speed from curvature // 5) Angular speed from curvature
double w_target = v_target * kappa; double w_target = v_target * kappa + std::copysign(carrot_pose.pose.theta * dt, kappa);
if(journey(trajectory.poses, 0, trajectory.poses.size() - 1) <= min_journey_squared_) if(journey(trajectory.poses, 0, trajectory.poses.size() - 1) <= min_journey_squared_)
{ {
if (trajectory.poses.size() >= 2) { if (trajectory.poses.size() >= 2) {
@@ -654,20 +642,18 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
for(int i = trajectory.poses.size() - 2; i >= 0; i--) for(int i = trajectory.poses.size() - 2; i >= 0; i--)
{ {
const auto& p = trajectory.poses[i].pose; const auto& p = trajectory.poses[i].pose;
const auto& dx = p1.x - p.x ; if(std::hypot(p1.x - p.x, p1.y - p.y) >= costmap_robot_->getCostmap()->getResolution())
const auto& dy = p1.y - p.y ;
if(std::hypot(dx, dy) >= costmap_robot_->getCostmap()->getResolution())
{ {
if(fabs(dx) < 1e-6 && fabs(dy) < 1e-6) heading_ref = angles::normalize_angle(std::atan2(p1.y - p.y, p1.x - p.x));
continue;
heading_ref = std::atan2(dy, dx);
if(sign_x < 0.0) if(sign_x < 0.0)
heading_ref += std::copysign(M_PI, heading_ref) * (-1.0); {
heading_ref = angles::normalize_angle(M_PI + heading_ref);
}
break; break;
} }
} }
const double error = heading_ref; const double error = angles::normalize_angle(heading_ref);
double w_heading = 0.0; double w_heading = 0.0;
pid(error, pid(error,
near_goal_heading_integral_, near_goal_heading_integral_,
@@ -680,11 +666,11 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
// Apply acceleration limits // Apply acceleration limits
double dw_heading = std::clamp(w_heading - velocity.theta, -acc_lim_theta_ * dt, acc_lim_theta_ * dt); double dw_heading = std::clamp(w_heading - velocity.theta, -acc_lim_theta_ * dt, acc_lim_theta_ * dt);
w_target = velocity.theta + dw_heading; w_target = velocity.theta + dw_heading;
w_target = std::clamp(w_target, -fabs(drive_target.theta), fabs(drive_target.theta)); w_target = std::clamp(w_target, -0.05, 0.05);
} }
else else
{ {
w_target = std::clamp(w_target, -0.001, 0.001); w_target = 0.0;
near_goal_heading_was_active_ = false; near_goal_heading_was_active_ = false;
} }
} }
@@ -692,7 +678,7 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
{ {
near_goal_heading_was_active_ = false; near_goal_heading_was_active_ = false;
} }
w_target = std::clamp(w_target, -fabs(drive_target.theta), fabs(drive_target.theta)); // w_target = std::clamp(w_target, -fabs(drive_target.theta), fabs(drive_target.theta));
// 6) Apply acceleration limits (linear + angular) // 6) Apply acceleration limits (linear + angular)
const double dv = std::clamp(v_target - velocity.x, -acc_lim_x_ * dt, acc_lim_x_ * dt); const double dv = std::clamp(v_target - velocity.x, -acc_lim_x_ * dt, acc_lim_x_ * dt);
@@ -700,7 +686,8 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
drive_cmd.x = velocity.x + dv; drive_cmd.x = velocity.x + dv;
drive_cmd.theta = velocity.theta + dw; drive_cmd.theta = velocity.theta + dw;
Eigen::VectorXd y(2); Eigen::VectorXd y(2);
y << drive_cmd.x, drive_cmd.theta; y << drive_cmd.x, drive_cmd.theta;
@@ -718,9 +705,8 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
double v_min = min_approach_linear_velocity_; double v_min = min_approach_linear_velocity_;
drive_cmd.x = std::clamp(kf_->state()[0], -fabs(v_target), fabs(v_target)); drive_cmd.x = std::clamp(kf_->state()[0], -fabs(v_target), fabs(v_target));
drive_cmd.x = fabs(drive_cmd.x) >= v_min ? drive_cmd.x : std::copysign(v_min, sign_x); drive_cmd.x = fabs(drive_cmd.x) >= v_min ? drive_cmd.x : std::copysign(v_min, sign_x);
if (kf_filter_angular_) // if (kf_filter_angular_)
drive_cmd.theta = std::clamp(kf_->state()[3], -fabs(drive_target.theta), fabs(drive_target.theta)); // drive_cmd.theta = std::clamp(kf_->state()[3], -max_vel_theta_, max_vel_theta_);
// robot::log_info("drive_cmd.theta: %f, drive_target.theta: %f", drive_cmd.theta, drive_target.theta);
} }
void mkt_algorithm::diff::PredictiveTrajectory::applyDistanceSpeedScaling( void mkt_algorithm::diff::PredictiveTrajectory::applyDistanceSpeedScaling(
@@ -744,9 +730,8 @@ void mkt_algorithm::diff::PredictiveTrajectory::applyDistanceSpeedScaling(
double cosine_factor = 0.5 * (1.0 + std::cos(M_PI * (1.0 - r))); double cosine_factor = 0.5 * (1.0 + std::cos(M_PI * (1.0 - r)));
target_speed = max_speed * cosine_factor; target_speed = max_speed * cosine_factor;
} }
const double v_limited = sign_x > 0 ? traj_->getTwistLinear(true).x : traj_->getTwistLinear(false).x;
const double v_min = std::min(fabs(v_limited), min_speed_xy_); double reduce_speed = std::min(max_speed, min_speed_xy_);
double reduce_speed = std::min(max_speed, v_min);
if (s < S_final) if (s < S_final)
{ {
double r = std::clamp(s / S_final, 0.0, 1.0); double r = std::clamp(s / S_final, 0.0, 1.0);
@@ -779,29 +764,21 @@ bool mkt_algorithm::diff::PredictiveTrajectory::shouldRotateToPath(
// const double max_kappa = calculateMaxKappa(global_plan); // const double max_kappa = calculateMaxKappa(global_plan);
// const bool curvature = max_kappa > straight_threshold; // const bool curvature = max_kappa > straight_threshold;
double path_angle = std::atan2(carrot_pose.pose.y, carrot_pose.pose.x); double path_angle = std::atan2(carrot_pose.pose.y, carrot_pose.pose.x);
if(is_stopped && global_plan.poses.size() >= 4 && if(is_stopped && global_plan.poses.size() >= 2)
journey(global_plan.poses, 0, global_plan.poses.size() - 1) >= 0.7 * min_lookahead_dist_)
{ {
const auto& p1 = global_plan.poses[2]; const auto& p1 = global_plan.poses[1];
for(int i = 3; i < global_plan.poses.size(); i++) for(int i = 2; i < global_plan.poses.size(); i++)
{ {
const auto& p = global_plan.poses[i]; const auto& p = global_plan.poses[i];
const auto& dx = p.pose.x - p1.pose.x; if(std::hypot(p.pose.x, p.pose.y) > costmap_robot_->getCostmap()->getResolution())
const auto& dy = p.pose.y - p1.pose.y;
if(std::hypot(dx, dy) > costmap_robot_->getCostmap()->getResolution())
{ {
if(fabs(dx) < 1e-9 && fabs(dy) < 1e-9) path_angle = std::atan2(p.pose.y - p1.pose.y, p.pose.x - p1.pose.x);
continue;
path_angle = std::atan2(dy, dx);
break; break;
} }
} }
} }
// Whether we should rotate robot to rough path heading // Whether we should rotate robot to rough path heading
// if(sign_x < 0.0)
// path_angle += std::copysign(M_PI, path_angle) * (-1.0);
// angle_to_path = path_angle;
angle_to_path = sign_x < 0.0 ? angles::normalize_angle(M_PI + path_angle) : path_angle; angle_to_path = sign_x < 0.0 ? angles::normalize_angle(M_PI + path_angle) : path_angle;
double heading_linear = sqrt(velocity.x * velocity.x + velocity.y * velocity.y); double heading_linear = sqrt(velocity.x * velocity.x + velocity.y * velocity.y);
// The difference in the path orientation and the starting robot orientation (radians) to trigger a rotate in place. (default: 0.785) // The difference in the path orientation and the starting robot orientation (radians) to trigger a rotate in place. (default: 0.785)
@@ -815,13 +792,16 @@ bool mkt_algorithm::diff::PredictiveTrajectory::shouldRotateToPath(
// (is_stopped || sign(angle_to_path) * sign_x < 0 ) && fabs(angle_to_path) > heading_rotate; // (is_stopped || sign(angle_to_path) * sign_x < 0 ) && fabs(angle_to_path) > heading_rotate;
bool result = use_rotate_to_heading_ && fabs(angle_to_path) > heading_rotate; bool result = use_rotate_to_heading_ && fabs(angle_to_path) > heading_rotate;
#ifdef BUILD_WITH_ROS // #ifdef BUILD_WITH_ROS
if (result) // if (result)
ROS_WARN_THROTTLE(0.1, "angle_to_path: %f, heading_rotate: %f, is_stopped: %x %x, sign_x: %f", angle_to_path, heading_rotate, is_stopped, sign(angle_to_path) * sign_x < 0, sign_x); // ROS_WARN_THROTTLE(0.1, "angle_to_path: %f, heading_rotate: %f, is_stopped: %x %x, sign_x: %f", angle_to_path, heading_rotate, is_stopped, sign(angle_to_path) * sign_x < 0, sign_x);
#else
if (result) // else if(fabs(velocity.x) < min_speed_xy_)
robot::log_info_throttle(0.1, "angle_to_path: %f, heading_rotate: %f, is_stopped: %x %x, sign_x: %f", angle_to_path, heading_rotate, is_stopped, sign(angle_to_path) * sign_x < 0, sign_x); // {
#endif // ROS_INFO_THROTTLE(0.1, "velocity.x: %f, velocity.theta: %f, ", velocity.x, velocity.theta);
// ROS_INFO_THROTTLE(0.1, "angle_to_path: %f, heading_rotate: %f, is_stopped: %x %x, sign_x: %f", angle_to_path, heading_rotate, is_stopped, sign(angle_to_path) * sign_x < 0, sign_x);
// }
// #endif
return result; return result;
} }
@@ -903,11 +883,13 @@ bool mkt_algorithm::diff::PredictiveTrajectory::shouldAlignToFinalHeading(
for(int i = trajectory.poses.size() - 2; i >= 0; i--) for(int i = trajectory.poses.size() - 2; i >= 0; i--)
{ {
const auto& p = trajectory.poses[i].pose; const auto& p = trajectory.poses[i].pose;
const auto& dx = sign_x < 0.0 ? p1.x - p.x : p.x - p1.x; if(std::hypot(p1.x - p.x, p1.y - p.y) >= costmap_robot_->getCostmap()->getResolution())
const auto& dy = sign_x < 0.0 ? p1.y - p.y : p.y - p1.y;
if(std::hypot(dx, dy) >= costmap_robot_->getCostmap()->getResolution())
{ {
heading_error = angles::normalize_angle(std::atan2(dy, dx)); heading_error = angles::normalize_angle(std::atan2(p1.y - p.y, p1.x - p.x));
if(sign_x < 0.0)
{
heading_error = angles::normalize_angle(M_PI + heading_error);
}
break; break;
} }
} }
@@ -957,10 +939,8 @@ void mkt_algorithm::diff::PredictiveTrajectory::alignToFinalHeading(
// --- Linear velocity calculation --- // --- Linear velocity calculation ---
// Base velocity proportional to distance, with minimum for smooth motion // Base velocity proportional to distance, with minimum for smooth motion
double v_base = std::sqrt(2.0 * std::fabs(decel_lim_x_) * xy_error); double v_base = std::sqrt(2.0 * std::fabs(decel_lim_x_) * xy_error);
const double v_limited = sign_x > 0 ? traj_->getTwistLinear(true).x : traj_->getTwistLinear(false).x;
const double v_min = std::min(fabs(v_limited), min_speed_xy_);
v_base = std::max(v_base, final_heading_min_velocity_); v_base = std::max(v_base, final_heading_min_velocity_);
v_base = std::min(v_base, v_min); v_base = std::min(v_base, min_speed_xy_);
// Scale down when heading error is large (prioritize rotation) // Scale down when heading error is large (prioritize rotation)
double heading_scale = 1.0; double heading_scale = 1.0;
@@ -1032,7 +1012,7 @@ void mkt_algorithm::diff::PredictiveTrajectory::alignToFinalHeading(
cmd_vel.theta = omega_current + domega; cmd_vel.theta = omega_current + domega;
// --- Apply velocity limits --- // --- Apply velocity limits ---
cmd_vel.x = std::clamp(cmd_vel.x, -v_min, v_min); cmd_vel.x = std::clamp(cmd_vel.x, -min_speed_xy_, min_speed_xy_);
cmd_vel.theta = std::clamp(cmd_vel.theta, -max_vel_theta_, max_vel_theta_); cmd_vel.theta = std::clamp(cmd_vel.theta, -max_vel_theta_, max_vel_theta_);
// --- Safety: ensure we can stop --- // --- Safety: ensure we can stop ---
@@ -1214,11 +1194,9 @@ double mkt_algorithm::diff::PredictiveTrajectory::adjustSpeedWithHermiteTrajecto
double v_limit = std::fabs(v_target); double v_limit = std::fabs(v_target);
double journey_distance = journey(trajectory.poses, 0, trajectory.poses.size() - 1); double journey_distance = journey(trajectory.poses, 0, trajectory.poses.size() - 1);
const double v_limited = sign_x > 0 ? traj_->getTwistLinear(true).x : traj_->getTwistLinear(false).x;
const double v_min = std::min(fabs(v_limited), min_speed_xy_);
if (journey_distance < min_journey_squared_) if (journey_distance < min_journey_squared_)
{ {
v_limit = std::clamp(sqrt(2.0 * fabs(decel_lim_x_) * journey_distance), min_approach_linear_velocity_, v_min) * sign_x; v_limit = std::clamp(sqrt(2.0 * fabs(decel_lim_x_) * journey_distance), min_approach_linear_velocity_, min_speed_xy_) * sign_x;
} }
if (max_kappa > 1e-6 && max_lateral_accel_ > 1e-6) if (max_kappa > 1e-6 && max_lateral_accel_ > 1e-6)
@@ -1228,7 +1206,7 @@ double mkt_algorithm::diff::PredictiveTrajectory::adjustSpeedWithHermiteTrajecto
} }
if(trajectory.poses.size() > 2 && fabs(trajectory.poses.front().pose.theta) >= angle_threshold_) if(trajectory.poses.size() > 2 && fabs(trajectory.poses.front().pose.theta) >= angle_threshold_)
v_limit = v_min * sign_x; v_limit = min_speed_xy_ * sign_x;
if (fabs(decel_lim_x_) > 1e-6) if (fabs(decel_lim_x_) > 1e-6)
{ {
@@ -1246,8 +1224,7 @@ robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateTra
const robot_nav_2d_msgs::Twist2D &drive_target, const robot_nav_2d_msgs::Twist2D &drive_target,
const robot_nav_2d_msgs::Twist2D &velocity, const robot_nav_2d_msgs::Twist2D &velocity,
const double &sign_x, const double &sign_x,
robot_nav_2d_msgs::Twist2D &drive_cmd, robot_nav_2d_msgs::Twist2D &drive_cmd)
const double &dt)
{ {
if (path.poses.empty()) if (path.poses.empty())
{ {
@@ -1255,31 +1232,24 @@ robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateTra
drive_cmd.theta = 0.0; drive_cmd.theta = 0.0;
return robot_nav_2d_msgs::Path2D(); return robot_nav_2d_msgs::Path2D();
} }
drive_cmd.x = drive_target.x;
drive_cmd.theta = max_vel_theta_;
double max_kappa = calculateMaxKappa(path); double max_kappa = calculateMaxKappa(path);
const double straight_threshold = std::max(0.05, 2.0 * (costmap_robot_ ? costmap_robot_->getCostmap()->getResolution() : 0.05)); const double straight_threshold = std::max(0.05, 2.0 * (costmap_robot_ ? costmap_robot_->getCostmap()->getResolution() : 0.05));
// nếu đường thẳng drive_cmd.x = this->adjustSpeedWithHermiteTrajectory(velocity, path, drive_target.x, sign_x);
if (max_kappa <= straight_threshold) drive_cmd.theta = max_vel_theta_;
if (max_kappa <= straight_threshold && fabs(path.poses.back().pose.x) < min_lookahead_dist_) // nếu đường thẳng
{ {
if(fabs(path.poses.back().pose.x) < min_lookahead_dist_ * 0.8) if(fabs(path.poses.front().pose.y) <= 0.03 && fabs(path.poses.front().pose.x) < (min_lookahead_dist_ + max_path_distance_))
{ {
if(fabs(path.poses.back().pose.x) < min_journey_squared_)
drive_cmd.theta = 0.01;
return generateParallelPath(path, sign_x); return generateParallelPath(path, sign_x);
} }
return generateHermiteTrajectory(path, sign_x); return generateHermiteTrajectory(path.poses.back(), sign_x);
} }
else // nếu đường cong else // nếu đường cong
{ {
const double v_limited = sign_x > 0 ? traj_->getTwistLinear(true).x : traj_->getTwistLinear(false).x; if(fabs(drive_cmd.x) < min_speed_xy_)
const double v_min = std::min(fabs(v_limited), min_speed_xy_); drive_cmd.x = std::copysign(min_speed_xy_, sign_x);
if(fabs(drive_cmd.x) < v_min) return generateHermiteQuadraticTrajectory(path.poses.back(), sign_x);
{
drive_cmd.x = std::copysign(v_min, sign_x);
}
return generateHermiteQuadraticTrajectory(path, sign_x);
} }
} }
@@ -1309,47 +1279,40 @@ robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generatePar
dx = path.poses[i+1].pose.x - path.poses[i-1].pose.x; dx = path.poses[i+1].pose.x - path.poses[i-1].pose.x;
dy = path.poses[i+1].pose.y - path.poses[i-1].pose.y; dy = path.poses[i+1].pose.y - path.poses[i-1].pose.y;
} }
if(fabs(dx) < 1e-6 && fabs(dy) < 1e-6)
continue;
double theta = atan2(dy, dx); double theta = atan2(dy, dx);
double x_off = p.x - offset_y * sin(theta)*sign_x; double x_off = p.x - offset_y * sin(theta)*sign_x;
double y_off = p.y - offset_y * cos(theta)*sign_x; double y_off = p.y - offset_y * cos(theta)*sign_x;
parallel_path.poses[i].header = path.poses[i].header;
parallel_path.poses[i].pose.x = x_off; parallel_path.poses[i].pose.x = x_off;
parallel_path.poses[i].pose.y = y_off; parallel_path.poses[i].pose.y = y_off;
parallel_path.poses[i].pose.theta = sign_x < 0 ? angles::normalize_angle(theta + M_PI) : theta; parallel_path.poses[i].pose.theta = theta; // hoặc giữ nguyên p.theta
parallel_path.poses[i].header = path.poses[i].header;
} }
return parallel_path; return parallel_path;
} }
robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateHermiteTrajectory( robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateHermiteTrajectory(
const robot_nav_2d_msgs::Path2D &path, const double &sign_x) const robot_nav_2d_msgs::Pose2DStamped &pose, const double &sign_x)
{ {
robot_nav_2d_msgs::Path2D hermite_trajectory; robot_nav_2d_msgs::Path2D hermite_trajectory;
hermite_trajectory.poses.clear(); hermite_trajectory.poses.clear();
hermite_trajectory.header = path.header; hermite_trajectory.header.stamp = pose.header.stamp;
hermite_trajectory.header.frame_id = pose.header.frame_id;
if (path.poses.empty()) const double x = pose.pose.x;
return hermite_trajectory; const double y = pose.pose.y;
const double theta = pose.pose.theta;
const auto &goal = path.poses.back();
if (hermite_trajectory.header.frame_id.empty())
hermite_trajectory.header.frame_id = goal.header.frame_id;
if (hermite_trajectory.header.stamp.isZero())
hermite_trajectory.header.stamp = goal.header.stamp;
const double x = goal.pose.x;
const double y = goal.pose.y;
double theta = goal.pose.theta;
const double L = std::hypot(x, y); const double L = std::hypot(x, y);
if (L < 1e-6) { if (L < 1e-6) {
robot_nav_2d_msgs::Pose2DStamped pose_stamped; robot_nav_2d_msgs::Pose2DStamped pose_stamped;
pose_stamped.pose.x = x; pose_stamped.pose.x = 0.0;
pose_stamped.pose.y = y; pose_stamped.pose.y = 0.0;
pose_stamped.pose.theta = theta; pose_stamped.pose.theta = 0.0;
pose_stamped.header.stamp = hermite_trajectory.header.stamp; pose_stamped.header.stamp = pose.header.stamp;
pose_stamped.header.frame_id = hermite_trajectory.header.frame_id; pose_stamped.header.frame_id = pose.header.frame_id;
hermite_trajectory.poses.push_back(pose_stamped); hermite_trajectory.poses.push_back(pose_stamped);
return hermite_trajectory; return hermite_trajectory;
} }
@@ -1383,39 +1346,30 @@ robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateHer
double dx = dh10 * Lnegative + dh01 * x + dh11 * Lnegative * std::cos(theta); double dx = dh10 * Lnegative + dh01 * x + dh11 * Lnegative * std::cos(theta);
double dy = dh01 * y + dh11 * Lnegative * std::sin(theta); double dy = dh01 * y + dh11 * Lnegative * std::sin(theta);
if(fabs(dx) < 1e-6 && fabs(dy) < 1e-6)
continue;
double heading = std::atan2(dy, dx); double heading = std::atan2(dy, dx);
robot_nav_2d_msgs::Pose2DStamped pose_out; robot_nav_2d_msgs::Pose2DStamped pose;
pose_out.pose.x = px; pose.pose.x = px;
pose_out.pose.y = py; pose.pose.y = py;
pose_out.pose.theta = sign_x < 0 ? angles::normalize_angle(heading + M_PI) : heading; pose.pose.theta = sign_x < 0 ? angles::normalize_angle(heading + M_PI) : heading;
pose_out.header.stamp = hermite_trajectory.header.stamp; pose.header.stamp = hermite_trajectory.header.stamp;
pose_out.header.frame_id = hermite_trajectory.header.frame_id; pose.header.frame_id = hermite_trajectory.header.frame_id;
hermite_trajectory.poses.push_back(pose_out); hermite_trajectory.poses.push_back(pose);
} }
return hermite_trajectory; return hermite_trajectory;
} }
robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateHermiteQuadraticTrajectory( robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateHermiteQuadraticTrajectory(
const robot_nav_2d_msgs::Path2D &path, const double &sign_x) const robot_nav_2d_msgs::Pose2DStamped &pose, const double &sign_x)
{ {
robot_nav_2d_msgs::Path2D trajectory; robot_nav_2d_msgs::Path2D trajectory;
trajectory.poses.clear(); trajectory.poses.clear();
trajectory.header = path.header; trajectory.header.stamp = pose.header.stamp;
if (path.poses.empty()) trajectory.header.frame_id = pose.header.frame_id;
return trajectory;
const auto &goal = path.poses.back(); const double x = pose.pose.x;
if (trajectory.header.frame_id.empty()) const double y = pose.pose.y;
trajectory.header.frame_id = goal.header.frame_id; const double theta = sign_x < 0 ? angles::normalize_angle(pose.pose.theta + M_PI) : pose.pose.theta;
if (trajectory.header.stamp.isZero())
trajectory.header.stamp = goal.header.stamp;
const double x = goal.pose.x;
const double y = goal.pose.y;
const double theta = sign_x < 0 ? angles::normalize_angle(goal.pose.theta + M_PI) : goal.pose.theta;
const double L = std::hypot(x, y); const double L = std::hypot(x, y);
if (L < 1e-6) if (L < 1e-6)
{ {
@@ -1455,8 +1409,6 @@ robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateHer
double dx = 2.0 * ax * t + bx; double dx = 2.0 * ax * t + bx;
double dy = 2.0 * ay * t + by; double dy = 2.0 * ay * t + by;
if(fabs(dx) < 1e-6 && fabs(dy) < 1e-6)
continue;
double heading = std::atan2(dy, dx); double heading = std::atan2(dy, dx);
robot_nav_2d_msgs::Pose2DStamped pose_out; robot_nav_2d_msgs::Pose2DStamped pose_out;

View File

@@ -70,8 +70,9 @@ bool mkt_plugins::GoalChecker::isGoalReached(const robot_nav_2d_msgs::Pose2DStam
double tolerance = fabs(cos(theta)) >= fabs(sin(theta)) ? x : y; double tolerance = fabs(cos(theta)) >= fabs(sin(theta)) ? x : y;
if(fabs(tolerance) <= xy_goal_tolerance_) if(fabs(tolerance) <= xy_goal_tolerance_)
{ {
robot::log_info_at(__FILE__, __LINE__, "%.3f %.3f %.3f %.3f %.3f", fabs(cos(theta)), fabs(sin(theta)),xy_tolerance, xy_goal_tolerance_, yaw_goal_tolerance_); robot::log_info_at(__FILE__, __LINE__, "%x %x", fabs(tolerance) <= xy_goal_tolerance_, tolerance * old_xy_goal_tolerance_ < 0);
robot::log_info_at(__FILE__, __LINE__, "Goal checker 1 ok %.3f %.3f %.3f %.3f %.3f ", tolerance, old_xy_goal_tolerance_, x, y, theta); robot::log_info_at(__FILE__, __LINE__, "%f %f %f %f", fabs(cos(theta)), fabs(sin(theta)), xy_goal_tolerance_, yaw_goal_tolerance_);
robot::log_info_at(__FILE__, __LINE__, "Goal checker 1 ok %f %f %f %f %f ", tolerance, old_xy_goal_tolerance_, x, y, theta);
return true; return true;
} }
} }

View File

@@ -255,7 +255,7 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::reset()
parent_.setParam(algorithm_nav_name, original_papams_); parent_.setParam(algorithm_nav_name, original_papams_);
robot::NodeHandle nh_algorithm = robot::NodeHandle(parent_, algorithm_nav_name); robot::NodeHandle nh_algorithm = robot::NodeHandle(parent_, algorithm_nav_name);
nh_algorithm.setParam("allow_rotate", false); // nh_algorithm.setParam("allow_rotate", false);
} }
void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity) void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity)
@@ -453,7 +453,8 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::isGoalReached(const robot_nav_
} }
} }
if (ret_nav_ && !ret_angle_ && !dock_ok) // if (ret_nav_ && !ret_angle_ && !dock_ok)
if (ret_nav_ && !ret_angle_)
{ {
double delta_orient = double delta_orient =
fabs(angles::normalize_angle(local_goal.pose.theta - local_pose.pose.theta)); fabs(angles::normalize_angle(local_goal.pose.theta - local_pose.pose.theta));

View File

@@ -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()) {
@@ -344,7 +343,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);
} }

View File

@@ -146,7 +146,7 @@ namespace robot_nav_core
* @brief Gets the current global plan * @brief Gets the current global plan
* @param path The global plan * @param path The global plan
*/ */
virtual void getGlobalPlan(std::vector<robot_geometry_msgs::PoseStamped> &path) = 0; virtual void getGlobalPlan(std::vector<robot_geometry_msgs::PoseStamped> &path) {return;}
/** /**
* @brief Constructs the local planner * @brief Constructs the local planner

View File

@@ -103,7 +103,7 @@ namespace robot_nav_core2
* @brief Gets the current global plan * @brief Gets the current global plan
* @param path The global plan * @param path The global plan
*/ */
virtual void getGlobalPlan(robot_nav_2d_msgs::Path2D &path) = 0; virtual void getGlobalPlan(robot_nav_2d_msgs::Path2D &path) {return;}
/** /**
* @brief Compute the best command given the current pose, velocity and goal * @brief Compute the best command given the current pose, velocity and goal

View File

@@ -1424,6 +1424,7 @@ bool move_base::MoveBase::dockTo(const robot_protocol_msgs::Order &msg,
lock.unlock(); lock.unlock();
return false; return false;
} }
as_->processGoal(action_goal); as_->processGoal(action_goal);
} }
catch (const std::exception &e) catch (const std::exception &e)