Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore(pure_pursuit): fix typo #4403

Merged
merged 1 commit into from
Jul 27, 2023
Merged
Show file tree
Hide file tree
Changes from all 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: 5 additions & 5 deletions control/pure_pursuit/include/pure_pursuit/pure_pursuit.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,18 +47,18 @@ namespace pure_pursuit
class PurePursuit
{
public:
PurePursuit() : lookahead_distance_(0.0), clst_thr_dist_(3.0), clst_thr_ang_(M_PI / 4) {}
PurePursuit() : lookahead_distance_(0.0), closest_thr_dist_(3.0), closest_thr_ang_(M_PI / 4) {}
~PurePursuit() = default;

rclcpp::Logger logger = rclcpp::get_logger("pure_pursuit");
// setter
void setCurrentPose(const geometry_msgs::msg::Pose & msg);
void setWaypoints(const std::vector<geometry_msgs::msg::Pose> & msg);
void setLookaheadDistance(double ld) { lookahead_distance_ = ld; }
void setClosestThreshold(double clst_thr_dist, double clst_thr_ang)
void setClosestThreshold(double closest_thr_dist, double closest_thr_ang)
{
clst_thr_dist_ = clst_thr_dist;
clst_thr_ang_ = clst_thr_ang;
closest_thr_dist_ = closest_thr_dist;
closest_thr_ang_ = closest_thr_ang;
}

// getter
Expand All @@ -74,7 +74,7 @@ class PurePursuit
geometry_msgs::msg::Point loc_next_tgt_;

// variables got from outside
double lookahead_distance_, clst_thr_dist_, clst_thr_ang_;
double lookahead_distance_, closest_thr_dist_, closest_thr_ang_;
std::shared_ptr<std::vector<geometry_msgs::msg::Pose>> curr_wps_ptr_;
std::shared_ptr<geometry_msgs::msg::Pose> curr_pose_ptr_;

Expand Down
11 changes: 6 additions & 5 deletions control/pure_pursuit/src/pure_pursuit_core/pure_pursuit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,16 +55,17 @@ std::pair<bool, double> PurePursuit::run()
return std::make_pair(false, std::numeric_limits<double>::quiet_NaN());
}

auto clst_pair = planning_utils::findClosestIdxWithDistAngThr(
*curr_wps_ptr_, *curr_pose_ptr_, clst_thr_dist_, clst_thr_ang_);
auto closest_pair = planning_utils::findClosestIdxWithDistAngThr(
*curr_wps_ptr_, *curr_pose_ptr_, closest_thr_dist_, closest_thr_ang_);

if (!clst_pair.first) {
if (!closest_pair.first) {
RCLCPP_WARN(
logger, "cannot find, curr_bool: %d, clst_idx: %d", clst_pair.first, clst_pair.second);
logger, "cannot find, curr_bool: %d, closest_idx: %d", closest_pair.first,
closest_pair.second);
return std::make_pair(false, std::numeric_limits<double>::quiet_NaN());
}

int32_t next_wp_idx = findNextPointIdx(clst_pair.second);
int32_t next_wp_idx = findNextPointIdx(closest_pair.second);
if (next_wp_idx == -1) {
RCLCPP_WARN(logger, "lost next waypoint");
return std::make_pair(false, std::numeric_limits<double>::quiet_NaN());
Expand Down