Skip to content

Commit

Permalink
Remove useless variable (#49)
Browse files Browse the repository at this point in the history
  • Loading branch information
ToshikiNakamura0412 authored Aug 17, 2024
1 parent 56555d2 commit d05cc95
Showing 1 changed file with 1 addition and 2 deletions.
3 changes: 1 addition & 2 deletions src/point_follow_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -497,14 +497,13 @@ void PointFollowPlanner::planning(
std::vector<State> &best_traj, std::vector<std::vector<State>> &trajectories, const Eigen::Vector3d &goal)
{
const Window dynamic_window = calc_dynamic_window(current_velocity_);
geometry_msgs::Twist cmd_vel;

if (fabs(previous_velocity_.linear.x) < velocity_th_for_stop_behind_obj_ && is_behind_obj_)
{
ROS_WARN_THROTTLE(1.0, "##########################");
ROS_WARN_THROTTLE(1.0, "### stop behind object ###");
ROS_WARN_THROTTLE(1.0, "##########################");
generate_trajectory(best_traj, cmd_vel.linear.x, cmd_vel.angular.z);
generate_trajectory(best_traj, 0.0, 0.0);
trajectories.push_back(best_traj);
}
else if (fabs(dynamic_window.max_velocity_ - dynamic_window.min_velocity_) < DBL_EPSILON)
Expand Down

0 comments on commit d05cc95

Please sign in to comment.