Skip to content

Commit

Permalink
refactor(mission_planner): use lower case (autowarefoundation#4079)
Browse files Browse the repository at this point in the history
Signed-off-by: yutaka <purewater0901@gmail.com>
  • Loading branch information
purewater0901 authored Jun 26, 2023
1 parent 52099a5 commit 3e12df8
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
14 changes: 7 additions & 7 deletions planning/mission_planner/src/mission_planner/mission_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -391,7 +391,7 @@ void MissionPlanner::on_set_mrm_route(
// check route safety
// step1. if in mrm state, check with mrm route
if (mrm_route_) {
if (checkRerouteSafety(*mrm_route_, new_route)) {
if (check_reroute_safety(*mrm_route_, new_route)) {
// success to reroute
change_mrm_route(new_route);
res->status.success = true;
Expand All @@ -413,7 +413,7 @@ void MissionPlanner::on_set_mrm_route(
}

// step2. if not in mrm state, check with normal route
if (checkRerouteSafety(*normal_route_, new_route)) {
if (check_reroute_safety(*normal_route_, new_route)) {
// success to reroute
change_mrm_route(new_route);
res->status.success = true;
Expand Down Expand Up @@ -455,7 +455,7 @@ void MissionPlanner::on_clear_mrm_route(
}

// check route safety
if (checkRerouteSafety(*mrm_route_, *normal_route_)) {
if (check_reroute_safety(*mrm_route_, *normal_route_)) {
clear_mrm_route();
change_route(*normal_route_);
change_state(RouteState::Message::SET);
Expand All @@ -470,7 +470,7 @@ void MissionPlanner::on_clear_mrm_route(
normal_route_->allow_modification);

// check new route safety
if (new_route.segments.empty() || !checkRerouteSafety(*mrm_route_, new_route)) {
if (new_route.segments.empty() || !check_reroute_safety(*mrm_route_, new_route)) {
// failed to create a new route
RCLCPP_ERROR_THROTTLE(get_logger(), *get_clock(), 5000, "Reroute with normal goal failed.");
change_mrm_route(*mrm_route_);
Expand Down Expand Up @@ -591,7 +591,7 @@ void MissionPlanner::on_change_route(
}

// check route safety
if (checkRerouteSafety(*normal_route_, new_route)) {
if (check_reroute_safety(*normal_route_, new_route)) {
// success to reroute
change_route(new_route);
res->status.success = true;
Expand Down Expand Up @@ -649,7 +649,7 @@ void MissionPlanner::on_change_route_points(
}

// check route safety
if (checkRerouteSafety(*normal_route_, new_route)) {
if (check_reroute_safety(*normal_route_, new_route)) {
// success to reroute
change_route(new_route);
res->status.success = true;
Expand All @@ -664,7 +664,7 @@ void MissionPlanner::on_change_route_points(
}
}

bool MissionPlanner::checkRerouteSafety(
bool MissionPlanner::check_reroute_safety(
const LaneletRoute & original_route, const LaneletRoute & target_route)
{
if (original_route.segments.empty() || target_route.segments.empty() || !map_ptr_ || !odometry_) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ class MissionPlanner : public rclcpp::Node

double reroute_time_threshold_{10.0};
double minimum_reroute_length_{30.0};
bool checkRerouteSafety(const LaneletRoute & original_route, const LaneletRoute & target_route);
bool check_reroute_safety(const LaneletRoute & original_route, const LaneletRoute & target_route);

std::shared_ptr<LaneletRoute> normal_route_{nullptr};
std::shared_ptr<LaneletRoute> mrm_route_{nullptr};
Expand Down

0 comments on commit 3e12df8

Please sign in to comment.