Skip to content
Merged
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 8 additions & 2 deletions nav2_docking/opennav_docking/src/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,10 @@ bool Controller::isTrajectoryCollisionFree(
}

// Generate path
for (double t = 0; t < projection_time_; t += simulation_time_step_) {
double distance = std::numeric_limits<double>::max();
unsigned int max_iter = static_cast<unsigned int>(ceil(projection_time_ / simulation_time_step_));

do{
// Apply velocities to calculate next pose
next_pose.pose = control_law_->calculateNextPose(
simulation_time_step_, target_pose, next_pose.pose, backward);
Expand Down Expand Up @@ -177,7 +180,10 @@ bool Controller::isTrajectoryCollisionFree(
trajectory_pub_->publish(trajectory);
return false;
}
}

// Check if we reach the goal
distance = nav2_util::geometry_utils::euclidean_distance(target_pose, next_pose.pose);
}while(distance > 1e-2 && trajectory.poses.size() < max_iter);

trajectory_pub_->publish(trajectory);

Expand Down
Loading