Compare commits

..

18 Commits

Author SHA1 Message Date
ece9154a84 update bug crash miss docking 2026-04-24 06:48:26 +00:00
08d597304e update 2026-03-30 07:55:41 +00:00
ff8ecf6126 update 2026-03-27 02:36:29 +00:00
ed8e364ab4 Merge remote-tracking branch 'origin/3.0' into awc-devel 2026-03-26 11:56:53 +00:00
58d925f2be fix 2026-03-26 14:42:26 +07:00
ba503eca85 fix giam toc 2026-03-25 10:33:01 +00:00
3944447b4d update docking 2026-03-25 09:09:58 +00:00
ea41848a4a fix gentrajectory 2026-03-25 15:35:15 +07:00
69823442f9 update 2026-03-24 15:26:00 +07:00
6b4d630d09 fix speed 2026-03-24 08:16:56 +00:00
37c7707582 Merge remote-tracking branch 'origin/3.0' into awc-devel 2026-03-24 08:06:47 +00:00
5375a5ea84 update 2026-03-24 08:05:05 +00:00
f69c3eac9f Merge remote-tracking branch 'origin/3.0' into awc-devel 2026-03-23 11:05:41 +00:00
483ca24418 fix 2026-03-23 17:55:50 +07:00
b4fee6c417 Merge remote-tracking branch 'origin/3.0' into awc-devel 2026-03-23 08:16:18 +00:00
c1e00fe76d fix bug 2026-03-23 15:06:57 +07:00
472cc4d02c fix 2026-03-23 14:36:59 +07:00
36ce68abf1 update 2026-03-23 14:27:24 +07:00
15 changed files with 379 additions and 196 deletions

View File

@@ -31,8 +31,8 @@ HybridLocalPlanner:
# GoalTolerance # GoalTolerance
xy_goal_tolerance: 0.1 xy_goal_tolerance: 0.05
yaw_goal_tolerance: 0.07 yaw_goal_tolerance: 0.05
# Optimization # Optimization

View File

@@ -9,14 +9,14 @@ trolley:
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.0 timeout: 60.0
vel_x: 0.25 vel_x: 0.2
vel_theta: 0.3 vel_theta: 0.3
yaw_goal_tolerance: 0.015 yaw_goal_tolerance: 0.015
xy_goal_tolerance: 0.015 xy_goal_tolerance: 0.015
min_lookahead_dist: 0.4 min_lookahead_dist: 0.4
max_lookahead_dist: 1.0 max_lookahead_dist: 1.0
lookahead_time: 1.5 lookahead_time: 1.5
angle_threshold: 0.16 angle_threshold: 0.4
qrcode: qrcode:
maker_goal_frame: qr_trolley maker_goal_frame: qr_trolley
@@ -30,7 +30,7 @@ trolley:
min_lookahead_dist: 0.4 min_lookahead_dist: 0.4
max_lookahead_dist: 1.0 max_lookahead_dist: 1.0
lookahead_time: 1.5 lookahead_time: 1.5
angle_threshold: 0.16 angle_threshold: 0.4
charger: charger:
plugins: plugins:
@@ -41,13 +41,13 @@ 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
vel_x: 0.1 vel_x: 0.15
yaw_goal_tolerance: 0.015 yaw_goal_tolerance: 0.015
xy_goal_tolerance: 0.015 xy_goal_tolerance: 0.015
min_lookahead_dist: 0.4 min_lookahead_dist: 0.4
max_lookahead_dist: 1.0 max_lookahead_dist: 1.0
lookahead_time: 1.5 lookahead_time: 1.5
angle_threshold: 0.16 angle_threshold: 0.4
dock_station: dock_station:
plugins: plugins:
@@ -102,7 +102,7 @@ undock_station:
min_lookahead_dist: 0.4 min_lookahead_dist: 0.4
max_lookahead_dist: 1.0 max_lookahead_dist: 1.0
lookahead_time: 1.5 lookahead_time: 1.5
angle_threshold: 0.16 angle_threshold: 0.4
qrcode: qrcode:
maker_goal_frame: qr_trolley maker_goal_frame: qr_trolley
@@ -116,7 +116,7 @@ undock_station:
min_lookahead_dist: 0.4 min_lookahead_dist: 0.4
max_lookahead_dist: 1.0 max_lookahead_dist: 1.0
lookahead_time: 1.5 lookahead_time: 1.5
angle_threshold: 0.16 angle_threshold: 0.4
undock_station_2: undock_station_2:
plugins: plugins:
@@ -135,7 +135,7 @@ undock_station_2:
min_lookahead_dist: 0.4 min_lookahead_dist: 0.4
max_lookahead_dist: 1.0 max_lookahead_dist: 1.0
lookahead_time: 1.5 lookahead_time: 1.5
angle_threshold: 0.16 angle_threshold: 0.4
qrcode: qrcode:
maker_goal_frame: qr_trolley maker_goal_frame: qr_trolley
@@ -149,4 +149,4 @@ undock_station_2:
min_lookahead_dist: 0.4 min_lookahead_dist: 0.4
max_lookahead_dist: 1.0 max_lookahead_dist: 1.0
lookahead_time: 1.5 lookahead_time: 1.5
angle_threshold: 0.16 angle_threshold: 0.4

View File

@@ -48,7 +48,7 @@ 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
@@ -106,8 +106,8 @@ MKTAlgorithmDiffPredictiveTrajectory:
angular_decel_zone: 0.1 angular_decel_zone: 0.1
# stoped # stoped
rot_stopped_velocity: 0.05 rot_stopped_velocity: 0.03
trans_stopped_velocity: 0.06 trans_stopped_velocity: 0.03
use_final_heading_alignment: true use_final_heading_alignment: true
final_heading_xy_tolerance: 0.1 final_heading_xy_tolerance: 0.1
@@ -143,8 +143,8 @@ MKTAlgorithmDiffGoStraight:
angular_decel_zone: 0.1 angular_decel_zone: 0.1
# stoped # stoped
rot_stopped_velocity: 0.05 rot_stopped_velocity: 0.03
trans_stopped_velocity: 0.06 trans_stopped_velocity: 0.03
use_final_heading_alignment: true use_final_heading_alignment: true
final_heading_xy_tolerance: 0.1 final_heading_xy_tolerance: 0.1
@@ -180,8 +180,8 @@ MKTAlgorithmDiffRotateToGoal:
angular_decel_zone: 0.1 angular_decel_zone: 0.1
# stoped # stoped
rot_stopped_velocity: 0.05 rot_stopped_velocity: 0.03
trans_stopped_velocity: 0.06 trans_stopped_velocity: 0.03
use_final_heading_alignment: true use_final_heading_alignment: true
final_heading_xy_tolerance: 0.1 final_heading_xy_tolerance: 0.1

View File

@@ -117,7 +117,9 @@ namespace mkt_algorithm
* @return lookahead point * @return lookahead point
*/ */
std::vector<robot_nav_2d_msgs::Pose2DStamped>::iterator 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 * @brief Prune global plan
@@ -194,11 +196,11 @@ namespace mkt_algorithm
/** /**
* @brief Generate Hermite trajectory * @brief Generate Hermite trajectory
* @param pose * @param path
* @param sign_x * @param sign_x
* @return trajectory * @return trajectory
*/ */
robot_nav_2d_msgs::Path2D generateHermiteTrajectory(const robot_nav_2d_msgs::Pose2DStamped &pose, const double &sign_x); robot_nav_2d_msgs::Path2D generateHermiteTrajectory(const robot_nav_2d_msgs::Path2D &path, const double &sign_x);
/** /**
* @brief Generate Hermite quadratic trajectory * @brief Generate Hermite quadratic trajectory
@@ -206,7 +208,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::Pose2DStamped &pose, const double &sign_x); robot_nav_2d_msgs::Path2D generateHermiteQuadraticTrajectory(const robot_nav_2d_msgs::Path2D &path, const double &sign_x);
/** /**
* @brief Should rotate to path * @brief Should rotate to path

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, const robot_nav_2d_msgs::Pose2DStamped &goal, const robot_nav_2d_msgs::Path2D &global_plan,
double &x_direction, double &y_direction, double &theta_direction) double &x_direction, double &y_direction, double &theta_direction)
{ {
// robot::log_error("DEBUG STEP 2.0");
if (!initialized_) if (!initialized_)
{ {
robot::log_error("[%s:%d]\n This planner has not been initialized, please call initialize() before using this planner", __FILE__, __LINE__); 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(); 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>(); std::vector<robot_geometry_msgs::Point> footprint = costmap_robot_ ? costmap_robot_->getRobotFootprint() : std::vector<robot_geometry_msgs::Point>();
if (footprint.size() > 1) 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->min_path_distance_ = min_length > 0.1 ? min_length : 0.1;
this->max_path_distance_ = max_length > 0.1 ? max_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) 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()); 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; return false;
} }
this->getParams(); this->getParams();
// robot::log_error("DEBUG STEP 5.0");
frame_id_path_ = global_plan.header.frame_id; frame_id_path_ = global_plan.header.frame_id;
goal_ = goal; goal_ = goal;
global_plan_ = global_plan; 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__); robot::log_error("[%s:%d]\n pruneGlobalPlan Failed", __FILE__, __LINE__);
return false; return false;
} }
// robot::log_error("DEBUG STEP 6.0");
double S = std::numeric_limits<double>::infinity(); double S = std::numeric_limits<double>::infinity();
S = std::max(costmap_robot_->getCostmap()->getSizeInCellsX() * costmap_robot_->getCostmap()->getResolution() / 2.0, S = std::max(costmap_robot_->getCostmap()->getSizeInCellsX() * costmap_robot_->getCostmap()->getResolution() / 2.0,
costmap_robot_->getCostmap()->getSizeInCellsY() * 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_; 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); S = std::clamp(S * fabs(velocity.x) * lookahead_time_, min_S, max_S);
compute_plan_.poses.clear(); compute_plan_.poses.clear();
// robot::log_error("DEBUG STEP 7.0");
if ((unsigned int)global_plan_.poses.size() == 2) if ((unsigned int)global_plan_.poses.size() == 2)
{ {
double dx = global_plan_.poses.back().pose.x - global_plan_.poses.front().pose.x; 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; return false;
} }
} }
// robot::log_error("DEBUG STEP 8.0");
double lookahead_dist = this->getLookAheadDistance(velocity); double lookahead_dist = this->getLookAheadDistance(velocity);
transform_plan_.poses.clear(); transform_plan_.poses.clear();
@@ -368,6 +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__); robot::log_warning("[%s:%d]\n Could not transform the global plan to the frame of the controller", __FILE__, __LINE__);
return false; return false;
} }
// robot::log_error("DEBUG STEP 9.0");
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)
{ {
@@ -378,14 +381,15 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
return false; return false;
} }
} }
// robot::log_error("DEBUG STEP 10.0");
x_direction = x_direction_; x_direction = x_direction_;
y_direction = y_direction_ = 0; y_direction = y_direction_ = 0;
theta_direction = theta_direction_; 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) && if ((unsigned int)(compute_plan_.poses.size() > 1) &&
journey(compute_plan_.poses, 0, compute_plan_.poses.size() - 1) >= costmap_robot_->getCostmap()->getResolution()) 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; const robot_geometry_msgs::Pose2D p2 = compute_plan_.poses.back().pose;
int index; int index;
for (index = (unsigned int)(compute_plan_.poses.size() - 1); index > 0; index--) for (index = (unsigned int)(compute_plan_.poses.size() - 1); index > 0; index--)
@@ -406,12 +410,19 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
} }
else else
{ {
// robot::log_error("DEBUG STEP 11.1");
try try
{ {
auto carrot_pose_it = getLookAheadPoint(velocity, lookahead_dist, transform_plan_); 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(); 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; double distance_it = 0;
for (auto it = carrot_pose_it - 1; it != transform_plan_.poses.begin(); --it)
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 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;
@@ -422,19 +433,21 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
break; 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_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);
// robot::log_error("DEBUG STEP 11.4");
// 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; const double dir_path = 0.0;
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;
// robot::log_error("DEBUG STEP 11.5");
} }
catch (std::exception &e) catch (std::exception &e)
{ {
@@ -442,7 +455,7 @@ bool mkt_algorithm::diff::PredictiveTrajectory::prepare(const robot_nav_2d_msgs:
return false; return false;
} }
} }
// robot::log_error("DEBUG STEP 11.0");
x_direction_ = x_direction; x_direction_ = x_direction;
y_direction_ = y_direction; y_direction_ = y_direction;
theta_direction_ = theta_direction; theta_direction_ = theta_direction;
@@ -476,7 +489,9 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
twist = traj_->nextTwist(); twist = traj_->nextTwist();
} }
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())
{ {
@@ -512,7 +527,7 @@ 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;
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; 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))
{ {
@@ -528,24 +543,20 @@ 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) robot_nav_2d_msgs::Twist2D drive_target = drive_cmd;
// {
// 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); 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);
@@ -559,7 +570,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_)
{ {
@@ -585,6 +596,8 @@ mkt_msgs::Trajectory2D mkt_algorithm::diff::PredictiveTrajectory::calculator(
break; break;
} }
if(fabs(v_max == 0.0))
drive_cmd.x = 0.0;
result.velocity = drive_cmd; result.velocity = drive_cmd;
prevous_drive_cmd_ = drive_cmd; prevous_drive_cmd_ = drive_cmd;
return result; return result;
@@ -630,8 +643,10 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
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);
std::stringstream ss;
// 5) Angular speed from curvature // 5) Angular speed from curvature
double w_target = v_target * kappa + std::copysign(carrot_pose.pose.theta * dt, kappa); double w_target = v_target * 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) {
@@ -640,18 +655,22 @@ 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;
if(std::hypot(p1.x - p.x, p1.y - p.y) >= costmap_robot_->getCostmap()->getResolution()) const auto& dx = p1.x - p.x ;
const auto& dy = p1.y - p.y ;
if(std::hypot(dx, dy) >= costmap_robot_->getCostmap()->getResolution())
{ {
heading_ref = angles::normalize_angle(std::atan2(p1.y - p.y, p1.x - p.x)); 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) 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 = angles::normalize_angle(heading_ref); const double error = heading_ref;
ss << error << " ";
double w_heading = 0.0; double w_heading = 0.0;
pid(error, pid(error,
near_goal_heading_integral_, near_goal_heading_integral_,
@@ -663,11 +682,12 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
w_heading); w_heading);
// 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);
ss << "dw_heading " << dw_heading << " ";
w_target = velocity.theta + dw_heading; w_target = velocity.theta + dw_heading;
} }
else else
{ {
w_target = 0.0; w_target = std::clamp(w_target, -0.001, 0.001);
near_goal_heading_was_active_ = false; near_goal_heading_was_active_ = false;
} }
} }
@@ -675,6 +695,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)
@@ -684,7 +705,6 @@ 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;
@@ -704,6 +724,7 @@ void mkt_algorithm::diff::PredictiveTrajectory::computePurePursuit(
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], -max_vel_theta_, max_vel_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( void mkt_algorithm::diff::PredictiveTrajectory::applyDistanceSpeedScaling(
@@ -767,16 +788,22 @@ bool mkt_algorithm::diff::PredictiveTrajectory::shouldRotateToPath(
for(int i = 2; 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;
const auto& dy = p.pose.y - p1.pose.y;
if(std::hypot(p.pose.x, p.pose.y) > costmap_robot_->getCostmap()->getResolution()) if(std::hypot(p.pose.x, p.pose.y) > costmap_robot_->getCostmap()->getResolution())
{ {
path_angle = std::atan2(p.pose.y - p1.pose.y, p.pose.x - p1.pose.x); if(fabs(dx) < 1e-9 && fabs(dy) < 1e-9)
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
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); 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)
double heading_rotate = rotate_to_heading_min_angle_; double heading_rotate = rotate_to_heading_min_angle_;
@@ -789,16 +816,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(fabs(velocity.x) < min_speed_xy_) // 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, "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); // 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 #endif
return result; return result;
} }
@@ -880,13 +907,11 @@ 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;
if(std::hypot(p1.x - p.x, p1.y - p.y) >= costmap_robot_->getCostmap()->getResolution()) const auto& dx = sign_x < 0.0 ? p1.x - p.x : p.x - p1.x;
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(p1.y - p.y, p1.x - p.x)); heading_error = angles::normalize_angle(std::atan2(dy, dx));
if(sign_x < 0.0)
{
heading_error = angles::normalize_angle(M_PI + heading_error);
}
break; break;
} }
} }
@@ -1061,7 +1086,8 @@ double mkt_algorithm::diff::PredictiveTrajectory::getLookAheadDistance(const rob
} }
std::vector<robot_nav_2d_msgs::Pose2DStamped>::iterator 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()) if (global_plan.poses.empty())
throw robot_nav_core2::PlannerTFException("The global plan passed to the local planner is empty."); throw robot_nav_core2::PlannerTFException("The global plan passed to the local planner is empty.");
@@ -1098,9 +1124,104 @@ mkt_algorithm::diff::PredictiveTrajectory::getLookAheadPoint(const robot_nav_2d_
if (goal_pose_it == global_plan.poses.end()) if (goal_pose_it == global_plan.poses.end())
goal_pose_it = std::prev(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; 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) 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()) if (global_plan.poses.empty())
@@ -1236,17 +1357,17 @@ robot_nav_2d_msgs::Path2D mkt_algorithm::diff::PredictiveTrajectory::generateTra
if (max_kappa <= straight_threshold && fabs(path.poses.back().pose.x) < min_lookahead_dist_) // nếu đường thẳng if (max_kappa <= straight_threshold && fabs(path.poses.back().pose.x) < min_lookahead_dist_) // nếu đường thẳng
{ {
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.front().pose.y) <= 0.03 && fabs(path.poses.back().pose.x) < min_lookahead_dist_ )
{ {
return generateParallelPath(path, sign_x); return generateParallelPath(path, sign_x);
} }
return generateHermiteTrajectory(path.poses.back(), sign_x); return generateHermiteTrajectory(path, sign_x);
} }
else // nếu đường cong else // nếu đường cong
{ {
if(fabs(drive_cmd.x) < min_speed_xy_) if(fabs(drive_cmd.x) < min_speed_xy_)
drive_cmd.x = std::copysign(min_speed_xy_, sign_x); drive_cmd.x = std::copysign(min_speed_xy_, sign_x);
return generateHermiteQuadraticTrajectory(path.poses.back(), sign_x); return generateHermiteQuadraticTrajectory(path, sign_x);
} }
} }
@@ -1276,40 +1397,49 @@ 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 = theta; // hoặc giữ nguyên p.theta parallel_path.poses[i].pose.theta = sign_x < 0 ? angles::normalize_angle(theta + M_PI) : 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::Pose2DStamped &pose, const double &sign_x) const robot_nav_2d_msgs::Path2D &path, 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.stamp = pose.header.stamp; hermite_trajectory.header = path.header;
hermite_trajectory.header.frame_id = pose.header.frame_id;
const double x = pose.pose.x; if (path.poses.empty())
const double y = pose.pose.y; return hermite_trajectory;
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 = 0.0; pose_stamped.pose.x = x;
pose_stamped.pose.y = 0.0; pose_stamped.pose.y = y;
pose_stamped.pose.theta = 0.0; pose_stamped.pose.theta = theta;
pose_stamped.header.stamp = pose.header.stamp; pose_stamped.header.stamp = hermite_trajectory.header.stamp;
pose_stamped.header.frame_id = pose.header.frame_id; pose_stamped.header.frame_id = hermite_trajectory.header.frame_id;
hermite_trajectory.poses.push_back(pose_stamped); hermite_trajectory.poses.push_back(pose_stamped);
return hermite_trajectory; return hermite_trajectory;
} }
@@ -1343,30 +1473,39 @@ 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; robot_nav_2d_msgs::Pose2DStamped pose_out;
pose.pose.x = px; pose_out.pose.x = px;
pose.pose.y = py; pose_out.pose.y = py;
pose.pose.theta = sign_x < 0 ? angles::normalize_angle(heading + M_PI) : heading; pose_out.pose.theta = sign_x < 0 ? angles::normalize_angle(heading + M_PI) : heading;
pose.header.stamp = hermite_trajectory.header.stamp; pose_out.header.stamp = hermite_trajectory.header.stamp;
pose.header.frame_id = hermite_trajectory.header.frame_id; pose_out.header.frame_id = hermite_trajectory.header.frame_id;
hermite_trajectory.poses.push_back(pose); hermite_trajectory.poses.push_back(pose_out);
} }
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::Pose2DStamped &pose, const double &sign_x) const robot_nav_2d_msgs::Path2D &path, const double &sign_x)
{ {
robot_nav_2d_msgs::Path2D trajectory; robot_nav_2d_msgs::Path2D trajectory;
trajectory.poses.clear(); trajectory.poses.clear();
trajectory.header.stamp = pose.header.stamp; trajectory.header = path.header;
trajectory.header.frame_id = pose.header.frame_id; if (path.poses.empty())
return trajectory;
const double x = pose.pose.x; const auto &goal = path.poses.back();
const double y = pose.pose.y; if (trajectory.header.frame_id.empty())
const double theta = sign_x < 0 ? angles::normalize_angle(pose.pose.theta + M_PI) : pose.pose.theta; trajectory.header.frame_id = goal.header.frame_id;
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)
{ {
@@ -1406,6 +1545,8 @@ 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,9 +70,8 @@ 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__, "%x %x", fabs(tolerance) <= xy_goal_tolerance_, tolerance * old_xy_goal_tolerance_ < 0); 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__, "%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 %.3f %.3f %.3f %.3f %.3f ", tolerance, old_xy_goal_tolerance_, x, y, theta);
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

@@ -176,6 +176,8 @@ namespace two_points_planner
const double dy = goal.pose.position.y - start.pose.position.y; const double dy = goal.pose.position.y - start.pose.position.y;
const double distance = std::sqrt(dx * dx + dy * dy); const double distance = std::sqrt(dx * dx + dy * dy);
double theta; double theta;
// Lấy độ phân giải của costmap
double resolution = costmap_robot_->getCostmap()->getResolution();
if(fabs(dx) > 1e-9 || fabs(dy) > 1e-9) if(fabs(dx) > 1e-9 || fabs(dy) > 1e-9)
{ {
@@ -188,17 +190,18 @@ namespace two_points_planner
} }
else else
{ {
robot_geometry_msgs::PoseStamped pose = start; auto goal_2d = robot_nav_2d_utils::poseStampedToPose2D(goal); // hoặc start.theta
pose.pose.position.x += 0.01 * cos(theta); robot_geometry_msgs::PoseStamped pose = goal;
pose.pose.position.y += 0.01 * sin(theta); 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(pose);
plan.push_back(goal); plan.push_back(goal);
return true; return true;
} }
// Lấy độ phân giải của costmap
double resolution = costmap_robot_->getCostmap()->getResolution();
// Tính số điểm cần chia // Tính số điểm cần chia
int num_points = std::ceil(distance / resolution); int num_points = std::ceil(distance / resolution);

View File

@@ -31,6 +31,8 @@ namespace pnkx_local_planner
void initialize(robot::NodeHandle &parent, const std::string &name, void initialize(robot::NodeHandle &parent, const std::string &name,
TFListenerPtr tf, robot_costmap_2d::Costmap2DROBOT *costmap_robot) override; 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 * @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() void pnkx_local_planner::PNKXDockingLocalPlanner::reset()
{ {
robot::log_info_at(__FILE__, __LINE__, "New Docking Goal Received."); robot::log_info_at(__FILE__, __LINE__, "New Docking Goal Received.");
@@ -250,21 +256,17 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::reset()
if(rotate_algorithm_) rotate_algorithm_->reset(); if(rotate_algorithm_) rotate_algorithm_->reset();
ret_nav_ = ret_angle_ = false; ret_nav_ = ret_angle_ = false;
robot::log_info_at(__FILE__, __LINE__, "Debug");
parent_.printParams();
std::string algorithm_nav_name; std::string algorithm_nav_name;
planner_nh_.param("algorithm_nav_name", algorithm_nav_name, std::string("pnkx_local_planner::PTA")); planner_nh_.param("algorithm_nav_name", algorithm_nav_name, std::string("pnkx_local_planner::PTA"));
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);
robot::log_info_at(__FILE__, __LINE__, "Debug ở đây");
parent_.printParams();
} }
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)
{ {
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 1.0");
this->getParams(planner_nh_); this->getParams(planner_nh_);
if (update_costmap_before_planning_) if (update_costmap_before_planning_)
{ {
@@ -278,11 +280,12 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msg
if (!costmap_robot_->isCurrent()) if (!costmap_robot_->isCurrent())
throw robot_nav_core2::CostmapDataLagException("Costmap2DROBOT is out of date somehow."); 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 // Update time stamp of goal pose
// goal_pose_.header.stamp = pose.header.stamp; // goal_pose_.header.stamp = pose.header.stamp;
robot_nav_2d_msgs::Pose2DStamped local_start_pose = this->transformPoseToLocal(pose), robot_nav_2d_msgs::Pose2DStamped local_start_pose = this->transformPoseToLocal(pose),
local_goal_pose = this->transformPoseToLocal(goal_pose_); local_goal_pose = this->transformPoseToLocal(goal_pose_);
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 3.0");
if (start_docking_) if (start_docking_)
{ {
local_goal_pose = goal_pose_; local_goal_pose = goal_pose_;
@@ -290,6 +293,14 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msg
try 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_)) 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"); robot::log_warning_at(__FILE__, __LINE__, "Transform global plan is failed");
} }
@@ -299,7 +310,10 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msg
} }
double x_direction, y_direction, theta_direction; double x_direction, y_direction, theta_direction;
if (!ret_nav_) if (!ret_nav_ && !dkpl_.empty())
{
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 4.0");
if(nav_algorithm_)
{ {
if (!nav_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_global_plan_, x_direction, y_direction, theta_direction)) if (!nav_algorithm_->prepare(local_start_pose, velocity, local_goal_pose, transformed_global_plan_, x_direction, y_direction, theta_direction))
{ {
@@ -308,9 +322,10 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msg
} }
// else // else
// ROS_INFO_THROTTLE(0.2, "chieu %f %f %f", x_direction, y_direction, theta_direction); // 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_) 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(); this->lock();
robot_geometry_msgs::Vector3 linear = dkpl_.front()->linear_; robot_geometry_msgs::Vector3 linear = dkpl_.front()->linear_;
traj_generator_->setTwistLinear(linear); traj_generator_->setTwistLinear(linear);
@@ -329,7 +344,7 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msg
parent_.setParam("xy_goal_tolerance", dkpl_.front()->xy_goal_tolerance_); parent_.setParam("xy_goal_tolerance", dkpl_.front()->xy_goal_tolerance_);
parent_.setParam("yaw_goal_tolerance", dkpl_.front()->yaw_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_) if (dkpl_.front()->docking_nav_ && !dkpl_.front()->docking_planner_)
{ {
@@ -347,6 +362,9 @@ void pnkx_local_planner::PNKXDockingLocalPlanner::prepare(const robot_nav_2d_msg
robot::log_warning_at(__FILE__, __LINE__, "Algorithm \"%s\" failed to prepare", nav_algorithm_->getName().c_str()); 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");
}
} }
} }
else else
@@ -370,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, robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXDockingLocalPlanner::computeVelocityCommands(const robot_nav_2d_msgs::Pose2DStamped &pose,
const robot_nav_2d_msgs::Twist2D &velocity) 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; 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 try
{ {
if (global_plan_.poses.empty()) // robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 1.0");
if ( global_plan_.poses.empty())
return cmd_vel; return cmd_vel;
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 1.11");
this->prepare(pose, velocity); this->prepare(pose, velocity);
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 2");
cmd_vel = this->ScoreAlgorithm(pose, velocity); cmd_vel = this->ScoreAlgorithm(pose, velocity);
// robot::log_debug_at(__FILE__, __LINE__, "DEBUG STEP 3");
return cmd_vel; return cmd_vel;
} }
catch (const robot_nav_core2::PlannerException &e) catch (const robot_nav_core2::PlannerException &e)
@@ -424,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) 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 == "") if (goal_pose_.header.frame_id == "")
{ {
robot::log_warning_at(__FILE__, __LINE__, "Cannot check if the goal is reached without the goal being set!"); robot::log_warning_at(__FILE__, __LINE__, "Cannot check if the goal is reached without the goal being set!");
@@ -455,11 +490,11 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::isGoalReached(const robot_nav_
{ {
robot::log_info_at(__FILE__, __LINE__, "local_pose %f %f %f", local_pose.pose.x, local_pose.pose.y, local_pose.pose.theta); robot::log_info_at(__FILE__, __LINE__, "local_pose %f %f %f", local_pose.pose.x, local_pose.pose.y, local_pose.pose.theta);
robot::log_info_at(__FILE__, __LINE__, "local_goal %f %f %f", local_goal.pose.x, local_goal.pose.y, local_goal.pose.theta); robot::log_info_at(__FILE__, __LINE__, "local_goal %f %f %f", local_goal.pose.x, local_goal.pose.y, local_goal.pose.theta);
robot::log_info_at(__FILE__, __LINE__, "goal_pose_ %f %f %f", goal_pose_.pose.x, goal_pose_.pose.y, goal_pose_.pose.theta);
} }
} }
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));
@@ -516,6 +551,7 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::dockingHanlde(const robot_nav_
dkpl_.front()->getLocalPath(local_pose, local_goal, path); dkpl_.front()->getLocalPath(local_pose, local_goal, path);
this->setPlan(robot_nav_2d_utils::pathToPath(path)); this->setPlan(robot_nav_2d_utils::pathToPath(path));
this->setGoalPose(local_goal); this->setGoalPose(local_goal);
robot::log_debug(__FILE__, __LINE__, "DEBUG 1 size path: %d", (int)path.poses.size());
} }
} }
catch (const std::exception &e) catch (const std::exception &e)
@@ -540,6 +576,7 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::dockingHanlde(const robot_nav_
path.poses.push_back(local_goal); path.poses.push_back(local_goal);
this->setPlan(path); this->setPlan(path);
this->setGoalPose(local_goal); this->setGoalPose(local_goal);
robot::log_debug(__FILE__, __LINE__, "DEBUG 2 size path: %d", (int)path.poses.size());
} }
} }
catch (const std::exception &e) catch (const std::exception &e)
@@ -548,6 +585,7 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::dockingHanlde(const robot_nav_
} }
} }
} }
} }
else else
{ {
@@ -801,7 +839,8 @@ bool pnkx_local_planner::PNKXDockingLocalPlanner::DockingPlanner::getLocalPath(
robot_geometry_msgs::PoseStamped start = robot_nav_2d_utils::pose2DToPoseStamped(local_pose); robot_geometry_msgs::PoseStamped start = robot_nav_2d_utils::pose2DToPoseStamped(local_pose);
robot_geometry_msgs::PoseStamped goal = robot_nav_2d_utils::pose2DToPoseStamped(local_goal); robot_geometry_msgs::PoseStamped goal = robot_nav_2d_utils::pose2DToPoseStamped(local_goal);
std::vector<robot_geometry_msgs::PoseStamped> docking_plan; std::vector<robot_geometry_msgs::PoseStamped> docking_plan;
robot::log_info_at(__FILE__, __LINE__, "start %s %f %f", start.header.frame_id.c_str(), start.pose.position.x, start.pose.position.y);
robot::log_info_at(__FILE__, __LINE__, "goal %s %f %f", goal.header.frame_id.c_str(), goal.pose.position.x, goal.pose.position.y);
if (!docking_planner_->makePlan(start, goal, docking_plan)) if (!docking_planner_->makePlan(start, goal, docking_plan))
{ {
throw robot_nav_core2::LocalPlannerException("Making plan from goal maker is failed"); throw robot_nav_core2::LocalPlannerException("Making plan from goal maker is failed");

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

@@ -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..."); robot::log_info("[MoveBase::moveTo] Processing goal through action server...");
as_->processGoal(action_goal); as_->processGoal(action_goal);
robot::log_info("[MoveBase::moveTo] Goal processed successfully by action server"); robot::log_info("[MoveBase::moveTo] Goal processed successfully by action server");
} }
catch (const std::exception &e) catch (const std::exception &e)
@@ -1116,7 +1117,6 @@ bool move_base::MoveBase::moveTo(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)
@@ -1424,7 +1424,6 @@ 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)
@@ -2496,6 +2495,7 @@ void move_base::MoveBase::executeCb(const robot_move_base_msgs::MoveBaseGoalCons
// the real work on pursuing a goal is done here // the real work on pursuing a goal is done here
bool done = executeCycle(goal); 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 we're done, then we'll return from execute
if (done) if (done)
return; return;
@@ -2715,7 +2715,7 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal)
controller_plan_ = latest_plan_; controller_plan_ = latest_plan_;
latest_plan_ = temp_plan; latest_plan_ = temp_plan;
lock.unlock(); lock.unlock();
robot::log_debug("pointers swapped!"); robot::log_debug("pointers swapped!: %d", controller_plan_->size());
if (!tc_->setPlan(*controller_plan_)) if (!tc_->setPlan(*controller_plan_))
{ {
@@ -2736,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."); // as_->setAborted(robot_move_base_msgs::MoveBaseResult(), "Failed to pass global plan to the controller.");
return true; return true;
} }
// robot::log_debug("pointers swapped2!");
// make sure to reset recovery_index_ since we were able to find a valid plan // make sure to reset recovery_index_ since we were able to find a valid plan
if (recovery_trigger_ == PLANNING_R) if (recovery_trigger_ == PLANNING_R)
@@ -2747,6 +2748,9 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal)
if (cancel_ctr_ && tc_) if (cancel_ctr_ && tc_)
{ {
robot_geometry_msgs::Vector3 linear; 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 ...."); // ROS_INFO_THROTTLE(1.0,"MoveTo is Canling ....");
tc_->setTwistLinear(linear); tc_->setTwistLinear(linear);
try try
@@ -2916,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())); 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 (!paused_)
{ {
if (tc_->computeVelocityCommands(odometry_.twist.twist, cmd_vel)) 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; robot_nav_msgs::Path path;
tc_->getPlan(path.poses); tc_->getPlan(path.poses);
if (!path.poses.empty()) if (!path.poses.empty())
@@ -2945,6 +2951,7 @@ bool move_base::MoveBase::executeCycle(robot_geometry_msgs::PoseStamped &goal)
} }
if (recovery_trigger_ == CONTROLLING_R) if (recovery_trigger_ == CONTROLLING_R)
recovery_index_ = 0; recovery_index_ = 0;
// robot::log_debug("Got a valid velocity command from the local planner end!");
} }
else else
{ {
@@ -3144,15 +3151,6 @@ robot_geometry_msgs::PoseStamped move_base::MoveBase::goalToGlobalFrame(const ro
} }
std::string global_frame = planner_costmap_robot_->getGlobalFrameID(); std::string global_frame = planner_costmap_robot_->getGlobalFrameID();
// robot_geometry_msgs::PoseStamped goal_pose, global_pose;
// goal_pose = goal_pose_msg;
// goal_pose.header.stamp = robot::Time(); // latest available
// try
// {
// tf3::TransformStampedMsg transform = tf_->lookupTransform(global_frame, goal_pose.header.frame_id, tf3::Time());
// tf3::doTransform(goal_pose, global_pose, transform);
// }
robot_geometry_msgs::PoseStamped global_pose; robot_geometry_msgs::PoseStamped global_pose;
tf3::toMsg(tf3::Transform::getIdentity(), global_pose.pose); tf3::toMsg(tf3::Transform::getIdentity(), global_pose.pose);
robot_geometry_msgs::PoseStamped goal_pose; robot_geometry_msgs::PoseStamped goal_pose;
@@ -3218,17 +3216,16 @@ robot::move_base_core::PlannerDataOutput move_base::MoveBase::getGlobalData()
{ {
robot_nav_msgs::Path path; robot_nav_msgs::Path path;
tc_->getGlobalPlan(path.poses); tc_->getGlobalPlan(path.poses);
if (!path.poses.empty()) robot_nav_msgs::Path global_path;
global_path.header.stamp = robot::Time::now();
global_path.header.frame_id = planner_costmap_robot_->getGlobalFrameID();
for(auto &p : path.poses)
{ {
path.header.stamp = path.poses[0].header.stamp; robot_geometry_msgs::PoseStamped pose = goalToGlobalFrame(p);
path.header.frame_id = path.poses[0].header.frame_id; pose.header.stamp = robot::Time::now();
global_path.poses.push_back(goalToGlobalFrame(pose));
} }
else global_data_.plan = robot_nav_2d_utils::pathToPath(global_path);
{
path.header.stamp = robot::Time::now();
path.header.frame_id = planner_costmap_robot_->getGlobalFrameID();
}
global_data_.plan = robot_nav_2d_utils::pathToPath(path);
} }
ConvertData convert_data(planner_costmap_robot_, planner_costmap_robot_->getGlobalFrameID(), true); ConvertData convert_data(planner_costmap_robot_, planner_costmap_robot_->getGlobalFrameID(), true);
convert_data.updateCostmap(global_data_.costmap, global_data_.costmap_update, global_data_.is_costmap_updated); convert_data.updateCostmap(global_data_.costmap, global_data_.costmap_update, global_data_.is_costmap_updated);