Compare commits
1 Commits
6ff54e4154
...
3.0
| Author | SHA1 | Date | |
|---|---|---|---|
| 7baa7000b8 |
@@ -398,7 +398,6 @@ robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXDockingLocalPlanner::S
|
||||
else if (!ret_nav_)
|
||||
{
|
||||
traj = nav_algorithm_->calculator(pose, velocity);
|
||||
|
||||
if (!dkpl_.empty() && dkpl_.front()->initialized_ && dkpl_.front()->is_detected_ && !dkpl_.front()->is_goal_reached_)
|
||||
{
|
||||
if (dkpl_.front()->docking_nav_ && !dkpl_.front()->docking_planner_)
|
||||
@@ -406,9 +405,17 @@ robot_nav_2d_msgs::Twist2DStamped pnkx_local_planner::PNKXDockingLocalPlanner::S
|
||||
traj = dkpl_.front()->docking_nav_->calculator(pose, velocity);
|
||||
}
|
||||
}
|
||||
local_plan_.header.stamp = robot::Time::now();
|
||||
robot_nav_msgs::Path path = robot_nav_2d_utils::poses2DToPath(traj.poses, costmap_robot_->getBaseFrameID(), robot::Time::now());
|
||||
local_plan_ = robot_nav_2d_utils::pathToPath(path);
|
||||
}
|
||||
else
|
||||
{
|
||||
traj = rotate_algorithm_->calculator(pose, velocity);
|
||||
local_plan_.header.stamp = robot::Time::now();
|
||||
robot_nav_msgs::Path path = robot_nav_2d_utils::poses2DToPath(traj.poses, costmap_robot_->getBaseFrameID(), robot::Time::now());
|
||||
local_plan_ = robot_nav_2d_utils::pathToPath(path);
|
||||
}
|
||||
|
||||
cmd_vel.velocity = traj.velocity;
|
||||
return cmd_vel;
|
||||
|
||||
Reference in New Issue
Block a user