Compare commits

..

17 Commits

25 changed files with 444 additions and 211 deletions

1
.gitignore vendored
View File

@@ -422,3 +422,4 @@ build
install
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
cd ../pnkx_nav_catkin_ws
rm -rf build devel
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"
catkin_make
source devel/setup.bash
```

View File

@@ -356,7 +356,8 @@ export PNKX_NAV_CORE_CONFIG_DIR=/path/to/config
# Chỉ định workspace directory
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
```

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

View File

@@ -19,17 +19,33 @@ virtual_walls_map:
lethal_cost_threshold: 100
obstacles:
observation_sources: f_scan_marking f_scan_clearing b_scan_marking b_scan_clearing
f_scan_marking:
topic: /f_scan
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
data_type: LaserScan
clearing: false
marking: true
inf_is_valid: true
min_obstacle_height: 0.0
max_obstacle_height: 0.25
f_scan_clearing:
topic: /f_scan
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
data_type: LaserScan
clearing: true
marking: false
@@ -54,3 +70,4 @@ obstacles:
max_obstacle_height: 0.25

View File

@@ -4,7 +4,7 @@ global_costmap:
global_frame: map
update_frequency: 1.0
publish_frequency: 1.0
raytrace_range: 2.0
raytrace_range: 3.5
resolution: 0.05
z_resolution: 0.2
rolling_window: false

View File

@@ -5,7 +5,7 @@ local_costmap:
update_frequency: 6.0
publish_frequency: 6.0
rolling_window: true
raytrace_range: 2.0
raytrace_range: 3.5
resolution: 0.05
z_resolution: 0.15
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: ""}
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]]
delay: 1.5 # Cấm sửa không là không chạy được
timeout: 60

View File

@@ -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_distance: 0.5
### recovery behaviors
recovery_behavior_enabled: false
recovery_behavior_enabled: true
recovery_behaviors: [
{name: aggressive_reset, type: ClearCostmapRecovery},
{name: conservative_reset, type: ClearCostmapRecovery},

View File

@@ -1,4 +1,4 @@
yaw_goal_tolerance: 0.02
yaw_goal_tolerance: 0.03
xy_goal_tolerance: 0.02
min_approach_linear_velocity: 0.05
@@ -48,17 +48,17 @@ LimitedAccelGenerator:
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
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
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_theta: 1.5
decel_lim_x: -3.0
decel_lim_x: -1.5
decel_lim_y: -0.0
decel_lim_theta: -2.0
decel_lim_theta: -1.5
# Whether to split the path into segments or not
split_path: true
@@ -74,8 +74,8 @@ LimitedAccelGenerator:
MKTAlgorithmDiffPredictiveTrajectory:
library_path: libmkt_algorithm_diff
xy_local_goal_tolerance: 0.05
angle_threshold: 0.6
xy_local_goal_tolerance: 0.02
angle_threshold: 0.47
index_samples: 60
follow_step_path: true
@@ -95,7 +95,7 @@ MKTAlgorithmDiffPredictiveTrajectory:
min_lookahead_dist: 0.6 # The minimum lookahead distance (m) threshold. (default: 0.3)
max_lookahead_dist: 2.0 # The maximum lookahead distance (m) threshold. (default: 0.9)
lookahead_time: 1.9 # The time (s) to project the velocity by, a.k.a. lookahead gain. (default: 1.5)
min_journey_squared: 0.35 # Minimum squared journey to consider for goal (default: 0.2)
min_journey_squared: 0.2 # Minimum squared journey to consider for goal (default: 0.2)
max_journey_squared: 0.5 # Maximum squared journey to consider for goal (default: 0.2)
max_lateral_accel: 0.9 # Max lateral accel for speed reduction on curves (m/s^2)
@@ -119,7 +119,7 @@ MKTAlgorithmDiffPredictiveTrajectory:
MKTAlgorithmDiffGoStraight:
library_path: libmkt_algorithm_diff
xy_local_goal_tolerance: 0.05
xy_local_goal_tolerance: 0.02
angle_threshold: 0.8
index_samples: 60
follow_step_path: true
@@ -156,7 +156,7 @@ MKTAlgorithmDiffGoStraight:
MKTAlgorithmDiffRotateToGoal:
library_path: libmkt_algorithm_diff
xy_local_goal_tolerance: 0.05
xy_local_goal_tolerance: 0.02
angle_threshold: 0.47
index_samples: 60
follow_step_path: true

View File

@@ -569,16 +569,10 @@ extern "C" bool navigation_set_twist_linear(NavigationHandle handle,
return false;
robot_geometry_msgs::Vector3 linear;
linear.x = 0.1;
linear.x = linear_x;
linear.y = linear_y;
linear.z = linear_z;
bool result = 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;
return nav_ptr->setTwistLinear(linear);
}
catch (...)
{

View File

@@ -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 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;
if (fabs(tolerance) <= xy_local_goal_tolerance_)
{
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;
@@ -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 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;
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;
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;
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);
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.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.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.y = sub_pose_stamped.pose.orientation.y;
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;
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);
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.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.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.y = sub_goal_stamped.pose.orientation.y;
sub_goal_stamped_ros.pose.orientation.z = sub_goal_stamped.pose.orientation.z;

View File

@@ -117,7 +117,9 @@ namespace mkt_algorithm
* @return lookahead point
*/
std::vector<robot_nav_2d_msgs::Pose2DStamped>::iterator
getLookAheadPoint(const robot_nav_2d_msgs::Twist2D &velocity, const double &lookahead_dist, robot_nav_2d_msgs::Path2D global_plan);
getLookAheadPoint(const robot_nav_2d_msgs::Twist2D &velocity,
const double &lookahead_dist,
robot_nav_2d_msgs::Path2D& global_plan);
/**
* @brief Prune global plan
@@ -181,7 +183,7 @@ namespace mkt_algorithm
*/
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::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

View File

@@ -131,19 +131,19 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::GoStraight::calculator(
auto carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transformed_plan);
robot_geometry_msgs::PoseStamped carrot_pose_stamped = robot_nav_2d_utils::pose2DToPoseStamped(carrot_pose);
// // === Final Heading Alignment Check ===
// double xy_error = 0.0, heading_error = 0.0;
// if (shouldAlignToFinalHeading(transformed_plan, carrot_pose, velocity, xy_error, heading_error, sign_x))
// {
// // Use Arc Motion controller for final heading alignment
// alignToFinalHeading(xy_error, heading_error, velocity, sign_x, dt, drive_cmd);
// #ifdef BUILD_WITH_ROS
// 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);
// #endif
// }
// else
// {
// === Final Heading Alignment Check ===
double xy_error = 0.0, heading_error = 0.0;
if (shouldAlignToFinalHeading(transformed_plan, carrot_pose, velocity, xy_error, heading_error, sign_x))
{
// Use Arc Motion controller for final heading alignment
alignToFinalHeading(xy_error, heading_error, velocity, sign_x, dt, drive_cmd);
#ifdef BUILD_WITH_ROS
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);
#endif
}
else
{
// robot::log_info_at(__FILE__, __LINE__, "journey : %f lookahead_dist : %f",
// journey(transformed_plan.poses, 0, transformed_plan.poses.size() - 1), lookahead_dist);
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);
}
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);
// Normal Pure Pursuit
@@ -164,7 +164,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::GoStraight::calculator(
sign_x,
dt,
drive_cmd);
// }
}
applyDistanceSpeedScaling(compute_plan_, velocity, drive_cmd, sign_x, dt);
if (this->nav_stop_)

View File

@@ -279,6 +279,7 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
const robot_nav_2d_msgs::Pose2DStamped &goal, const robot_nav_2d_msgs::Path2D &global_plan,
double &x_direction, double &y_direction, double &theta_direction)
{
// robot::log_error("DEBUG STEP 2.0");
if (!initialized_)
{
robot::log_error("[%s:%d]\n This planner has not been initialized, please call initialize() before using this planner", __FILE__, __LINE__);
@@ -288,7 +289,7 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
{
last_actuator_update_ = robot::Time::now();
}
// robot::log_error("DEBUG STEP 3.0");
std::vector<robot_geometry_msgs::Point> footprint = costmap_robot_ ? costmap_robot_->getRobotFootprint() : std::vector<robot_geometry_msgs::Point>();
if (footprint.size() > 1)
{
@@ -311,14 +312,14 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
this->min_path_distance_ = min_length > 0.1 ? min_length : 0.1;
this->max_path_distance_ = max_length > 0.1 ? max_length : 0.1;
}
// robot::log_error("DEBUG STEP 4.0");
if (global_plan.poses.empty() || (unsigned int)global_plan.poses.size() < 2)
{
robot::log_error("[%s:%d]\n The Local plan is empty or less than 1 points %d", __FILE__, __LINE__, (unsigned int)global_plan.poses.size());
return false;
}
this->getParams();
// robot::log_error("DEBUG STEP 5.0");
frame_id_path_ = global_plan.header.frame_id;
goal_ = goal;
global_plan_ = global_plan;
@@ -329,14 +330,14 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
robot::log_error("[%s:%d]\n pruneGlobalPlan Failed", __FILE__, __LINE__);
return false;
}
// robot::log_error("DEBUG STEP 6.0");
double S = std::numeric_limits<double>::infinity();
S = std::max(costmap_robot_->getCostmap()->getSizeInCellsX() * costmap_robot_->getCostmap()->getResolution() / 2.0,
costmap_robot_->getCostmap()->getSizeInCellsY() * costmap_robot_->getCostmap()->getResolution() / 2.0);
const double min_S = min_lookahead_dist_ * 1.5 + max_path_distance_, max_S = max_lookahead_dist_ * 1.5 + max_path_distance_;
S = std::clamp(S * fabs(velocity.x) * lookahead_time_, min_S, max_S);
compute_plan_.poses.clear();
// robot::log_error("DEBUG STEP 7.0");
if ((unsigned int)global_plan_.poses.size() == 2)
{
double dx = global_plan_.poses.back().pose.x - global_plan_.poses.front().pose.x;
@@ -360,6 +361,7 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
return false;
}
}
// robot::log_error("DEBUG STEP 8.0");
double lookahead_dist = this->getLookAheadDistance(velocity);
transform_plan_.poses.clear();
@@ -368,7 +370,7 @@ 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__);
return false;
}
// robot::log_error("DEBUG STEP 9.0");
const auto carrot_pose = *getLookAheadPoint(velocity, lookahead_dist, transform_plan_);
if(fabs(carrot_pose.pose.y) > 0.2)
{
@@ -379,14 +381,15 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
return false;
}
}
// robot::log_error("DEBUG STEP 10.0");
x_direction = x_direction_;
y_direction = y_direction_ = 0;
theta_direction = theta_direction_;
// robot::log_error("DEBUG STATUS : %x, %x", (unsigned int)(compute_plan_.poses.size() > 1), journey(compute_plan_.poses, 0, compute_plan_.poses.size() - 1) >= costmap_robot_->getCostmap()->getResolution());
if ((unsigned int)(compute_plan_.poses.size() > 1) &&
journey(compute_plan_.poses, 0, compute_plan_.poses.size() - 1) >= costmap_robot_->getCostmap()->getResolution())
{
// robot::log_error("DEBUG STEP 10.1");
const robot_geometry_msgs::Pose2D p2 = compute_plan_.poses.back().pose;
int index;
for (index = (unsigned int)(compute_plan_.poses.size() - 1); index > 0; index--)
@@ -405,50 +408,54 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
}
}
else if(compute_plan_.poses.size() == 1)
else
{
// robot::log_error("DEBUG STEP 11.1");
try
{
// auto carrot_pose_it = getLookAheadPoint(velocity, lookahead_dist, transform_plan_);
// auto prev_carrot_pose_it = transform_plan_.poses.begin();
// double distance_it = 0;
// for (auto it = carrot_pose_it - 1; it != transform_plan_.poses.begin(); --it)
// {
// double dx = it->pose.x - carrot_pose_it->pose.x;
// double dy = it->pose.y - carrot_pose_it->pose.y;
// distance_it += std::hypot(dx, dy);
// if (distance_it > costmap_robot_->getCostmap()->getResolution())
// {
// prev_carrot_pose_it = it;
// break;
// }
// }
// 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(robot_geometry_msgs::Pose2D());
auto carrot_pose_it = getLookAheadPoint(velocity, lookahead_dist, transform_plan_);
// robot::log_error("DEBUG STEP 11.2");
auto prev_carrot_pose_it = transform_plan_.poses.begin();
// robot::log_error("DEBUG STEP 11.2.1 carrot_pose_it: %d", (int)std::distance(transform_plan_.poses.begin(), carrot_pose_it));
double distance_it = 0;
// robot_geometry_msgs::Pose back = robot_nav_2d_utils::pose2DToPose((*(carrot_pose_it)).pose);
auto it = carrot_pose_it == transform_plan_.poses.begin() ? transform_plan_.poses.end() : carrot_pose_it - 1;
for ( ; it != transform_plan_.poses.begin(); --it)
{
double dx = it->pose.x - carrot_pose_it->pose.x;
double dy = it->pose.y - carrot_pose_it->pose.y;
distance_it += std::hypot(dx, dy);
if (distance_it > costmap_robot_->getCostmap()->getResolution())
{
prev_carrot_pose_it = it;
break;
}
}
// robot::log_error("DEBUG STEP 11.3");
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(robot_geometry_msgs::Pose2D());
robot_geometry_msgs::Pose back = robot_nav_2d_utils::pose2DToPose((*(carrot_pose_it)).pose);
// robot::log_error("DEBUG STEP 11.4");
// teb_local_planner::PoseSE2 start_pose(front);
// teb_local_planner::PoseSE2 goal_pose(back);
// const double dir_path = (goal_pose.position() - start_pose.position()).dot(start_pose.orientationUnitVec());
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));
const double dir_path = 0.0;
if (fabs(dir_path) > M_PI / 6 || x_direction < 1e-9)
x_direction = dir_path > 0 ? FORWARD : BACKWARD;
// robot::log_error("DEBUG STEP 11.5");
}
catch (std::exception &e)
{
robot::log_warning_throttle(0.2, "[%s:%d]\n getLookAheadPoint throw an exception: %s", __FILE__, __LINE__, e.what());
x_direction = x_direction_;
robot::log_error("[%s:%d]\n getLookAheadPoint throw an exception: %s", __FILE__, __LINE__, e.what());
return false;
}
}
// robot::log_error("DEBUG STEP 11.0");
x_direction_ = x_direction;
y_direction_ = y_direction;
theta_direction_ = theta_direction;
@@ -482,8 +489,8 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
twist = traj_->nextTwist();
}
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 = sqrt(twist.x * twist.x);
// 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_;
if (transformed_plan.poses.empty())
@@ -520,11 +527,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
const double distance_allow_rotate = min_journey_squared_;
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;
robot_geometry_msgs::Pose2D back_pose = transformed_plan.poses.back().pose;
allow_rotate |= fabs(atan2(back_pose.y, back_pose.x) - back_pose.theta) > M_PI / 6.0;
allow_rotate &= (fabs(transformed_plan.poses.front().pose.y) <= 0.5);
allow_rotate &= std::hypot(compute_plan_.poses.front().pose.x - pose.pose.x, compute_plan_.poses.front().pose.y - pose.pose.y) <= 0.1;
double angle_to_heading;
if (allow_rotate && shouldRotateToPath(transformed_plan, carrot_pose, velocity, angle_to_heading, sign_x))
{
@@ -554,7 +557,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
// else
// {
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);
// Normal Pure Pursuit
@@ -581,7 +584,6 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
result.velocity = drive_cmd;
return result;
}
}
result.poses.clear();
result.poses.reserve(transformed_plan.poses.size());
@@ -595,11 +597,7 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
}
if(fabs(v_max == 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;
prevous_drive_cmd_ = drive_cmd;
return result;
@@ -625,15 +623,15 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
// 3) Adjust speed using Hermite trajectory curvature + remaining distance
double v_target = adjustSpeedWithHermiteTrajectory(velocity, trajectory, drive_target.x, sign_x);
// 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);
// v_target *= scale_close;
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);
v_target *= scale_close;
const double y_abs = std::fabs(carrot_pose.pose.y);
const double y_soft = 0.1;
if (y_abs > y_soft)
{
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;
robot_nav_2d_msgs::Twist2D cmd, result;
cmd.x = v_target;
@@ -644,6 +642,9 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
// 4) Maintain minimum approach speed
if (std::fabs(v_target) < min_approach_linear_velocity)
v_target = std::copysign(min_approach_linear_velocity, sign_x);
std::stringstream ss;
// 5) Angular speed from curvature
double w_target = v_target * kappa;
if(journey(trajectory.poses, 0, trajectory.poses.size() - 1) <= min_journey_squared_)
@@ -661,6 +662,7 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
if(fabs(dx) < 1e-6 && fabs(dy) < 1e-6)
continue;
heading_ref = std::atan2(dy, dx);
ss << "error " << heading_ref << " ";
if(sign_x < 0.0)
heading_ref += std::copysign(M_PI, heading_ref) * (-1.0);
break;
@@ -668,6 +670,7 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
}
const double error = heading_ref;
ss << error << " ";
double w_heading = 0.0;
pid(error,
near_goal_heading_integral_,
@@ -679,8 +682,8 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
w_heading);
// Apply acceleration limits
double dw_heading = std::clamp(w_heading - velocity.theta, -acc_lim_theta_ * dt, acc_lim_theta_ * dt);
ss << "dw_heading " << dw_heading << " ";
w_target = velocity.theta + dw_heading;
w_target = std::clamp(w_target, -fabs(drive_target.theta), fabs(drive_target.theta));
}
else
{
@@ -692,6 +695,7 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
{
near_goal_heading_was_active_ = false;
}
w_target = std::clamp(w_target, -fabs(drive_target.theta), fabs(drive_target.theta));
// 6) Apply acceleration limits (linear + angular)
@@ -719,8 +723,8 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
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);
if (kf_filter_angular_)
drive_cmd.theta = std::clamp(kf_->state()[3], -fabs(drive_target.theta), fabs(drive_target.theta));
// robot::log_info("drive_cmd.theta: %f, drive_target.theta: %f", drive_cmd.theta, drive_target.theta);
drive_cmd.theta = std::clamp(kf_->state()[3], -max_vel_theta_, max_vel_theta_);
// robot::log_info("%s", ss.str().c_str());
}
void mkt_algorithm::diff::PredictiveTrajectory::applyDistanceSpeedScaling(
@@ -744,9 +748,8 @@ void mkt_algorithm::diff::PredictiveTrajectory::applyDistanceSpeedScaling(
double cosine_factor = 0.5 * (1.0 + std::cos(M_PI * (1.0 - r)));
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, v_min);
double reduce_speed = std::min(max_speed, min_speed_xy_);
if (s < S_final)
{
double r = std::clamp(s / S_final, 0.0, 1.0);
@@ -779,16 +782,15 @@ bool mkt_algorithm::diff::PredictiveTrajectory::shouldRotateToPath(
// const double max_kappa = calculateMaxKappa(global_plan);
// const bool curvature = max_kappa > straight_threshold;
double path_angle = std::atan2(carrot_pose.pose.y, carrot_pose.pose.x);
if(is_stopped && global_plan.poses.size() >= 4 &&
journey(global_plan.poses, 0, global_plan.poses.size() - 1) >= 0.7 * min_lookahead_dist_)
if(is_stopped && global_plan.poses.size() >= 2)
{
const auto& p1 = global_plan.poses[2];
for(int i = 3; i < global_plan.poses.size(); i++)
const auto& p1 = global_plan.poses[1];
for(int i = 2; i < global_plan.poses.size(); i++)
{
const auto& p = global_plan.poses[i];
const auto& dx = p.pose.x - p1.pose.x;
const auto& dy = p.pose.y - p1.pose.y;
if(std::hypot(dx, dy) > costmap_robot_->getCostmap()->getResolution())
if(std::hypot(p.pose.x, p.pose.y) > costmap_robot_->getCostmap()->getResolution())
{
if(fabs(dx) < 1e-9 && fabs(dy) < 1e-9)
continue;
@@ -799,10 +801,9 @@ bool mkt_algorithm::diff::PredictiveTrajectory::shouldRotateToPath(
}
// 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;
if(sign_x < 0.0)
path_angle += std::copysign(M_PI, path_angle) * (-1.0);
angle_to_path = path_angle;
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)
double heading_rotate = rotate_to_heading_min_angle_;
@@ -818,9 +819,12 @@ bool mkt_algorithm::diff::PredictiveTrajectory::shouldRotateToPath(
#ifdef BUILD_WITH_ROS
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);
#else
if (result)
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);
// else if(fabs(velocity.x) < min_speed_xy_)
// {
// 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;
}
@@ -957,10 +961,8 @@ void mkt_algorithm::diff::PredictiveTrajectory::alignToFinalHeading(
// --- Linear velocity calculation ---
// Base velocity proportional to distance, with minimum for smooth motion
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::min(v_base, v_min);
v_base = std::min(v_base, min_speed_xy_);
// Scale down when heading error is large (prioritize rotation)
double heading_scale = 1.0;
@@ -1032,7 +1034,7 @@ void mkt_algorithm::diff::PredictiveTrajectory::alignToFinalHeading(
cmd_vel.theta = omega_current + domega;
// --- 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_);
// --- Safety: ensure we can stop ---
@@ -1084,7 +1086,8 @@ double mkt_algorithm::diff::PredictiveTrajectory::getLookAheadDistance(const rob
}
std::vector<robot_nav_2d_msgs::Pose2DStamped>::iterator
mkt_algorithm::diff::PredictiveTrajectory::getLookAheadPoint(const robot_nav_2d_msgs::Twist2D &velocity, const double &lookahead_dist, robot_nav_2d_msgs::Path2D global_plan)
mkt_algorithm::diff::PredictiveTrajectory::getLookAheadPoint(const robot_nav_2d_msgs::Twist2D &velocity,
const double &lookahead_dist, robot_nav_2d_msgs::Path2D& global_plan)
{
if (global_plan.poses.empty())
throw robot_nav_core2::PlannerTFException("The global plan passed to the local planner is empty.");
@@ -1121,9 +1124,104 @@ mkt_algorithm::diff::PredictiveTrajectory::getLookAheadPoint(const robot_nav_2d_
if (goal_pose_it == global_plan.poses.end())
goal_pose_it = std::prev(global_plan.poses.end());
// --- Final safety check ---
if (goal_pose_it < global_plan.poses.begin() || goal_pose_it >= global_plan.poses.end())
{
// fallback cuối cùng
goal_pose_it = std::prev(global_plan.poses.end());
}
return goal_pose_it;
}
// std::vector<robot_nav_2d_msgs::Pose2DStamped>::iterator
// mkt_algorithm::diff::PredictiveTrajectory::getLookAheadPoint(
// const robot_nav_2d_msgs::Twist2D &velocity,
// const double &lookahead_dist,
// robot_nav_2d_msgs::Path2D &global_plan)
// {
// auto &poses = global_plan.poses;
// // --- Guard ---
// if (poses.empty())
// throw robot_nav_core2::PlannerTFException("The global plan is empty.");
// if (poses.size() == 1)
// return poses.begin();
// if (poses.size() == 2)
// return std::prev(poses.end());
// // --- Init ---
// size_t goal_index = poses.size() - 1;
// const auto &p0 = poses[0].pose;
// const auto &p1 = poses[1].pose;
// double start_angle = atan2(p1.y - p0.y, p1.x - p0.x);
// double turn_threshold = M_PI_2 * 0.6;
// // --- Detect turn ---
// for (size_t i = 1; i < poses.size(); ++i)
// {
// const auto &a = poses[i - 1].pose;
// const auto &b = poses[i].pose;
// double current_angle = atan2(b.y - a.y, b.x - a.x);
// double delta = angles::normalize_angle(current_angle - start_angle);
// goal_index = i;
// if (fabs(delta) >= turn_threshold)
// break;
// }
// // --- Clamp goal_index ---
// if (goal_index >= poses.size())
// goal_index = poses.size() - 1;
// // --- Safe search range ---
// auto search_begin = poses.begin();
// // ❗ IMPORTANT: +1 để iterator hợp lệ
// auto search_end = poses.begin() + goal_index + 1;
// if (search_end > poses.end())
// search_end = poses.end();
// // --- Find lookahead ---
// double accumulated_dist = 0.0;
// auto goal_pose_it = search_begin;
// for (auto it = search_begin + 1; it != search_end; ++it)
// {
// double dx = it->pose.x - std::prev(it)->pose.x;
// double dy = it->pose.y - std::prev(it)->pose.y;
// accumulated_dist += std::hypot(dx, dy);
// if (accumulated_dist >= lookahead_dist)
// {
// goal_pose_it = it;
// break;
// }
// }
// // --- Fallback an toàn ---
// if (goal_pose_it == search_begin)
// {
// goal_pose_it = std::prev(search_end); // safe vì search_end > search_begin
// }
// // --- Final safety check ---
// if (goal_pose_it < poses.begin() || goal_pose_it >= poses.end())
// {
// // fallback cuối cùng
// return std::prev(poses.end());
// }
// return goal_pose_it;
// }
bool mkt_algorithm::diff::PredictiveTrajectory::pruneGlobalPlan(TFListenerPtr tf, const robot_nav_2d_msgs::Pose2DStamped &pose, robot_nav_2d_msgs::Path2D &global_plan, double dist_behind_robot)
{
if (global_plan.poses.empty())
@@ -1214,11 +1312,9 @@ double mkt_algorithm::diff::PredictiveTrajectory::adjustSpeedWithHermiteTrajecto
double v_limit = std::fabs(v_target);
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_)
{
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)
@@ -1228,7 +1324,7 @@ double mkt_algorithm::diff::PredictiveTrajectory::adjustSpeedWithHermiteTrajecto
}
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)
{
@@ -1246,8 +1342,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 &velocity,
const double &sign_x,
robot_nav_2d_msgs::Twist2D &drive_cmd,
const double &dt)
robot_nav_2d_msgs::Twist2D &drive_cmd)
{
if (path.poses.empty())
{
@@ -1255,30 +1350,23 @@ robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateTra
drive_cmd.theta = 0.0;
return robot_nav_2d_msgs::Path2D();
}
drive_cmd.x = drive_target.x;
drive_cmd.theta = max_vel_theta_;
double max_kappa = calculateMaxKappa(path);
const double straight_threshold = std::max(0.05, 2.0 * (costmap_robot_ ? costmap_robot_->getCostmap()->getResolution() : 0.05));
// nếu đường thẳng
if (max_kappa <= straight_threshold)
drive_cmd.x = this->adjustSpeedWithHermiteTrajectory(velocity, path, drive_target.x, sign_x);
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.back().pose.x) < min_lookahead_dist_ )
{
if(fabs(path.poses.back().pose.x) < min_journey_squared_)
drive_cmd.theta = 0.01;
return generateParallelPath(path, sign_x);
}
return generateHermiteTrajectory(path, sign_x);
}
else // nếu đường cong
{
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(fabs(drive_cmd.x) < v_min)
{
drive_cmd.x = std::copysign(v_min, sign_x);
}
if(fabs(drive_cmd.x) < min_speed_xy_)
drive_cmd.x = std::copysign(min_speed_xy_, sign_x);
return generateHermiteQuadraticTrajectory(path, sign_x);
}
}
@@ -1323,6 +1411,8 @@ robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generatePar
return parallel_path;
}
robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateHermiteTrajectory(
const robot_nav_2d_msgs::Path2D &path, const double &sign_x)
{

View File

@@ -190,9 +190,14 @@ namespace two_points_planner
}
else
{
robot_geometry_msgs::PoseStamped pose = start;
pose.pose.position.x += resolution * cos(theta);
pose.pose.position.y += resolution * sin(theta);
auto goal_2d = robot_nav_2d_utils::poseStampedToPose2D(goal); // hoặc start.theta
robot_geometry_msgs::PoseStamped pose = goal;
pose.pose.position.x += resolution * std::cos(goal_2d.pose.theta);
pose.pose.position.y += resolution * std::sin(goal_2d.pose.theta);
plan.push_back(pose);
pose = goal;
pose.pose.position.x -= resolution * std::cos(goal_2d.pose.theta);
pose.pose.position.y -= resolution * std::sin(goal_2d.pose.theta);
plan.push_back(pose);
plan.push_back(goal);
return true;

View File

@@ -31,6 +31,8 @@ namespace pnkx_local_planner
void initialize(robot::NodeHandle &parent, const std::string &name,
TFListenerPtr tf, robot_costmap_2d::Costmap2DROBOT *costmap_robot) override;
void setPlan(const robot_nav_2d_msgs::Path2D &path) override;
/**
* @brief robot_nav_core2 computeVelocityCommands - calculates the best command given the current pose and velocity
*

View File

@@ -240,6 +240,12 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::getParams(robot::NodeHandle &n
}
}
void pnkx_local_planner::PNKXDockingLocalPlanner::setPlan(const robot_nav_2d_msgs::Path2D &path)
{
this->reset();
pnkx_local_planner::PNKXLocalPlanner::setPlan(path);
}
void pnkx_local_planner::PNKXDockingLocalPlanner::reset()
{
robot::log_info_at(__FILE__, __LINE__, "New Docking Goal Received.");
@@ -255,11 +261,12 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::reset()
parent_.setParam(algorithm_nav_name, original_papams_);
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)
{
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 1.0");
this->getParams(planner_nh_);
if (update_costmap_before_planning_)
{
@@ -273,11 +280,12 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msg
if (!costmap_robot_->isCurrent())
throw robot_nav_core2::CostmapDataLagException("Costmap2DROBOT is out of date somehow.");
}
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 2.0");
// Update time stamp of goal pose
// goal_pose_.header.stamp = pose.header.stamp;
robot_nav_2d_msgs::Pose2DStamped local_start_pose = this->transformPoseToLocal(pose),
local_goal_pose = this->transformPoseToLocal(goal_pose_);
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 3.0");
if (start_docking_)
{
local_goal_pose = goal_pose_;
@@ -285,6 +293,14 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msg
try
{
// robot::log_error("local_start_pose (%f, %f, %f)", local_start_pose.pose.x, local_start_pose.pose.y, local_start_pose.pose.theta);
// robot::log_error("local_goal_pose (%f, %f, %f)", local_goal_pose.pose.x, local_goal_pose.pose.y, local_goal_pose.pose.theta);
// for(size_t i = 0; i < global_plan_.poses.size(); i++)
// {
// robot::log_error("global_plan_ [%zu] (%f, %f, %f)", i, global_plan_.poses[i].pose.x, global_plan_.poses[i].pose.y, global_plan_.poses[i].pose.theta);
// }
// robot::log_error("costmap_robot_->getGlobalFrameID(): %s", costmap_robot_->getGlobalFrameID().c_str());
if (!pnkx_local_planner::transformGlobalPlan(tf_, global_plan_, local_start_pose, costmap_robot_, costmap_robot_->getGlobalFrameID(), 2.0, transformed_global_plan_))
robot::log_warning_at(__FILE__, __LINE__, "Transform global plan is failed");
}
@@ -294,53 +310,60 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msg
}
double x_direction, y_direction, theta_direction;
if (!ret_nav_)
if (!ret_nav_ && !dkpl_.empty())
{
if (!nav_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_global_plan_, x_direction, y_direction, theta_direction))
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 4.0");
if(nav_algorithm_)
{
robot::log_warning_at(__FILE__, __LINE__, "Algorithm \"%s\" failed to prepare", nav_algorithm_->getName().c_str());
throw robot_nav_core2::LocalPlannerException("Algorithm failed to prepare");
}
// else
// ROS_INFO_THROTTLE(0.2, "chieu %f %f %f", x_direction, y_direction, theta_direction);
if (!dkpl_.empty() && dkpl_.front()->initialized_ && dkpl_.front()->is_detected_ && !dkpl_.front()->is_goal_reached_)
{
this->lock();
robot_geometry_msgs::Vector3 linear = dkpl_.front()->linear_;
traj_generator_->setTwistLinear(linear);
linear.x *= (-1);
traj_generator_->setTwistLinear(linear);
traj_generator_->setTwistAngular(dkpl_.front()->angular_);
std::string algorithm_nav_name;
planner_nh_.param("algorithm_nav_name", algorithm_nav_name, std::string("pnkx_local_planner::PTA"));
robot::NodeHandle nh_algorithm = robot::NodeHandle(parent_, algorithm_nav_name);
nh_algorithm.setParam("allow_rotate", dkpl_.front()->allow_rotate_);
nh_algorithm.setParam("min_lookahead_dist", dkpl_.front()->min_lookahead_dist_);
nh_algorithm.setParam("max_lookahead_dist", dkpl_.front()->max_lookahead_dist_);
nh_algorithm.setParam("lookahead_time", dkpl_.front()->lookahead_time_);
nh_algorithm.setParam("angle_threshold", dkpl_.front()->angle_threshold_);
parent_.setParam("xy_goal_tolerance", dkpl_.front()->xy_goal_tolerance_);
parent_.setParam("yaw_goal_tolerance", dkpl_.front()->yaw_goal_tolerance_);
if (dkpl_.front()->docking_nav_ && !dkpl_.front()->docking_planner_)
if (!nav_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_global_plan_, x_direction, y_direction, theta_direction))
{
robot::log_warning_at(__FILE__, __LINE__, "Algorithm \"%s\" failed to prepare", nav_algorithm_->getName().c_str());
throw robot_nav_core2::LocalPlannerException("Algorithm failed to prepare");
}
// else
// ROS_INFO_THROTTLE(0.2, "chieu %f %f %f", x_direction, y_direction, theta_direction);
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 5.0");
if (!dkpl_.empty() && dkpl_.front()->initialized_ && dkpl_.front()->is_detected_ && !dkpl_.front()->is_goal_reached_)
{
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 6.0");
this->lock();
robot_geometry_msgs::Vector3 linear = dkpl_.front()->linear_;
traj_generator_->setTwistLinear(linear);
linear.x *= (-1);
traj_generator_->setTwistLinear(linear);
traj_generator_->setTwistAngular(dkpl_.front()->angular_);
if (dkpl_.front()->following_)
std::string algorithm_nav_name;
planner_nh_.param("algorithm_nav_name", algorithm_nav_name, std::string("pnkx_local_planner::PTA"));
robot::NodeHandle nh_algorithm = robot::NodeHandle(parent_, algorithm_nav_name);
nh_algorithm.setParam("allow_rotate", dkpl_.front()->allow_rotate_);
nh_algorithm.setParam("min_lookahead_dist", dkpl_.front()->min_lookahead_dist_);
nh_algorithm.setParam("max_lookahead_dist", dkpl_.front()->max_lookahead_dist_);
nh_algorithm.setParam("lookahead_time", dkpl_.front()->lookahead_time_);
nh_algorithm.setParam("angle_threshold", dkpl_.front()->angle_threshold_);
parent_.setParam("xy_goal_tolerance", dkpl_.front()->xy_goal_tolerance_);
parent_.setParam("yaw_goal_tolerance", dkpl_.front()->yaw_goal_tolerance_);
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 7.0");
if (dkpl_.front()->docking_nav_ && !dkpl_.front()->docking_planner_)
{
robot_nav_2d_msgs::Pose2DStamped follow_pose;
if (dkpl_.front()->geLocalGoal(local_goal_pose))
if (dkpl_.front()->following_)
{
local_goal_pose = follow_pose;
robot_nav_2d_msgs::Pose2DStamped follow_pose;
if (dkpl_.front()->geLocalGoal(local_goal_pose))
{
local_goal_pose = follow_pose;
}
}
if (!dkpl_.front()->docking_nav_->prepare(local_start_pose, velocity, local_goal_pose, transformed_global_plan_, x_direction, y_direction, theta_direction))
{
throw robot_nav_core2::LocalPlannerException("Algorithm failed to prepare");
robot::log_warning_at(__FILE__, __LINE__, "Algorithm \"%s\" failed to prepare", nav_algorithm_->getName().c_str());
}
}
if (!dkpl_.front()->docking_nav_->prepare(local_start_pose, velocity, local_goal_pose, transformed_global_plan_, x_direction, y_direction, theta_direction))
{
throw robot_nav_core2::LocalPlannerException("Algorithm failed to prepare");
robot::log_warning_at(__FILE__, __LINE__, "Algorithm \"%s\" failed to prepare", nav_algorithm_->getName().c_str());
}
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 8.0");
}
}
}
@@ -365,14 +388,26 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msg
robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXDockingLocalPlanner::computeVelocityCommands(const robot_nav_2d_msgs::Pose2DStamped &pose,
const robot_nav_2d_msgs::Twist2D &velocity)
{
// boost::recursive_mutex::scoped_lock l(configuration_mutex_);
// // boost::recursive_mutex::scoped_lock l(configuration_mutex_);
// for(size_t i = 0; i < global_plan_.poses.size(); i++)
// {
// robot::log_error("computeVelocityCommands global_plan_ [%d] (%f, %f, %f)", i, global_plan_.poses[i].pose.x, global_plan_.poses[i].pose.y, global_plan_.poses[i].pose.theta);
// }
robot_nav_2d_msgs::Twist2DStamped cmd_vel;
cmd_vel.header.stamp = robot::Time::now();
cmd_vel.velocity.x = 0.0;
cmd_vel.velocity.y = 0.0;
cmd_vel.velocity.theta = 0.0;
try
{
if (global_plan_.poses.empty())
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 1.0");
if ( global_plan_.poses.empty())
return cmd_vel;
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 1.11");
this->prepare(pose, velocity);
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 2");
cmd_vel = this->ScoreAlgorithm(pose, velocity);
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 3");
return cmd_vel;
}
catch (const robot_nav_core2::PlannerException &e)
@@ -419,6 +454,11 @@ robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXDockingLocalPlanner::S
bool pnkx_local_planner::PNKXDockingLocalPlanner::isGoalReached(const robot_nav_2d_msgs::Pose2DStamped &pose, const robot_nav_2d_msgs::Twist2D &velocity)
{
// if(global_plan_.poses.size() <= 2)
// {
// robot::log_error("DEBUG GOAL");
// return true;
// }
if (goal_pose_.header.frame_id == "")
{
robot::log_warning_at(__FILE__, __LINE__, "Cannot check if the goal is reached without the goal being set!");
@@ -453,7 +493,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 =
fabs(angles::normalize_angle(local_goal.pose.theta - local_pose.pose.theta));
@@ -510,6 +551,7 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::dockingHanlde(const robot_nav_
dkpl_.front()->getLocalPath(local_pose, local_goal, path);
this->setPlan(robot_nav_2d_utils::pathToPath(path));
this->setGoalPose(local_goal);
robot::log_debug(__FILE__, __LINE__, "DEBUG 1 size path: %d", (int)path.poses.size());
}
}
catch (const std::exception &e)
@@ -534,6 +576,7 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::dockingHanlde(const robot_nav_
path.poses.push_back(local_goal);
this->setPlan(path);
this->setGoalPose(local_goal);
robot::log_debug(__FILE__, __LINE__, "DEBUG 2 size path: %d", (int)path.poses.size());
}
}
catch (const std::exception &e)
@@ -542,6 +585,7 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::dockingHanlde(const robot_nav_
}
}
}
}
else
{

View File

@@ -66,7 +66,6 @@ std::string PluginLoaderHelper::findLibraryPath(const std::string& symbol_name)
}
// Try to read from NodeHandle
std::string library_path;
robot::log_info_at(__FILE__, __LINE__, "%s", symbol_name.c_str());
if (nh_.hasParam(param_path)) {
nh_.getParam(param_path, library_path, std::string(""));
if (!library_path.empty()) {
@@ -344,7 +343,7 @@ std::string PluginLoaderHelper::getBuildDirectory()
std::string PluginLoaderHelper::getWorkspacePath()
{
// 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)) {
return std::string(workspace_path);
}

View File

@@ -146,7 +146,7 @@ namespace robot_nav_core
* @brief Gets the current 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

View File

@@ -103,7 +103,7 @@ namespace robot_nav_core2
* @brief Gets the current 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

View File

@@ -976,6 +976,7 @@ bool move_base::MoveBase::moveTo( const robot_geometry_msgs::PoseStamped &goal,
robot::log_info("[MoveBase::moveTo] Processing goal through action server...");
as_->processGoal(action_goal);
robot::log_info("[MoveBase::moveTo] Goal processed successfully by action server");
}
catch (const std::exception &e)
@@ -1116,7 +1117,6 @@ bool move_base::MoveBase::moveTo(const robot_protocol_msgs::Order &msg,
lock.unlock();
return false;
}
as_->processGoal(action_goal);
}
catch (const std::exception &e)
@@ -2495,6 +2495,7 @@ void move_base::MoveBase::executeCb(const robot_move_base_msgs::MoveBaseGoalCons
// the real work on pursuing a goal is done here
bool done = executeCycle(goal);
// robot::log_debug("[MoveBase] Completed an execution cycle: ̀done=%s", done ? "true" : "false");
// if we're done, then we'll return from execute
if (done)
return;
@@ -2714,7 +2715,7 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal)
controller_plan_ = latest_plan_;
latest_plan_ = temp_plan;
lock.unlock();
robot::log_debug("pointers swapped!");
robot::log_debug("pointers swapped!: %d", controller_plan_->size());
if (!tc_->setPlan(*controller_plan_))
{
@@ -2735,6 +2736,7 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal)
// as_->setAborted(robot_move_base_msgs::MoveBaseResult(), "Failed to pass global plan to the controller.");
return true;
}
// robot::log_debug("pointers swapped2!");
// make sure to reset recovery_index_ since we were able to find a valid plan
if (recovery_trigger_ == PLANNING_R)
@@ -2746,6 +2748,9 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal)
if (cancel_ctr_ && tc_)
{
robot_geometry_msgs::Vector3 linear;
linear.x = 0.0;
linear.y = 0.0;
linear.z = 0.0;
// ROS_INFO_THROTTLE(1.0,"MoveTo is Canling ....");
tc_->setTwistLinear(linear);
try
@@ -2915,10 +2920,12 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal)
{
boost::unique_lock<robot_costmap_2d::Costmap2D::mutex_t> lock(*(controller_costmap_robot_->getCostmap()->getMutex()));
// robot::log_error("paused_: %s", paused_ ? "true" : "false");
if (!paused_)
{
if (tc_->computeVelocityCommands(odometry_.twist.twist, cmd_vel))
{
// robot::log_debug("Got a valid velocity command from the local planner start!");
robot_nav_msgs::Path path;
tc_->getPlan(path.poses);
if (!path.poses.empty())
@@ -2944,6 +2951,7 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal)
}
if (recovery_trigger_ == CONTROLLING_R)
recovery_index_ = 0;
// robot::log_debug("Got a valid velocity command from the local planner end!");
}
else
{