Skip to content

Commit

Permalink
refactor(behavior_velocity_crosswalk_module): use std::optional inste…
Browse files Browse the repository at this point in the history
…ad of boost::optional

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 committed Jul 18, 2023
1 parent faf6ed6 commit 6922164
Show file tree
Hide file tree
Showing 6 changed files with 42 additions and 39 deletions.
5 changes: 3 additions & 2 deletions planning/behavior_velocity_crosswalk_module/src/manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@

#include <functional>
#include <memory>
#include <optional>
#include <set>
#include <vector>

Expand All @@ -52,7 +53,7 @@ class CrosswalkModuleManager : public SceneModuleManagerInterfaceWithRTC
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)> getModuleExpiredFunction(
const PathWithLaneId & path) override;

boost::optional<bool> opt_use_regulatory_element_{boost::none};
std::optional<bool> opt_use_regulatory_element_{std::nullopt};
};

class WalkwayModuleManager : public SceneModuleManagerInterface
Expand All @@ -70,7 +71,7 @@ class WalkwayModuleManager : public SceneModuleManagerInterface
std::function<bool(const std::shared_ptr<SceneModuleInterface> &)> getModuleExpiredFunction(
const PathWithLaneId & path) override;

boost::optional<bool> opt_use_regulatory_element_{boost::none};
std::optional<bool> opt_use_regulatory_element_{std::nullopt};
};

class CrosswalkModulePlugin : public PluginWrapper<CrosswalkModuleManager>
Expand Down
37 changes: 18 additions & 19 deletions planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,8 +253,7 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
}

// NOTE: The stop point will be the returned point with the margin.
boost::optional<std::pair<geometry_msgs::msg::Point, double>>
CrosswalkModule::getStopPointWithMargin(
std::optional<std::pair<geometry_msgs::msg::Point, double>> CrosswalkModule::getStopPointWithMargin(
const PathWithLaneId & ego_path,
const std::vector<geometry_msgs::msg::Point> & path_intersects) const
{
Expand All @@ -279,11 +278,11 @@ CrosswalkModule::getStopPointWithMargin(
return {};
}

boost::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
std::optional<StopFactor> CrosswalkModule::checkStopForCrosswalkUsers(
const PathWithLaneId & ego_path, const PathWithLaneId & sparse_resample_path,
const boost::optional<std::pair<geometry_msgs::msg::Point, double>> & p_stop_line,
const std::optional<std::pair<geometry_msgs::msg::Point, double>> & p_stop_line,
const std::vector<geometry_msgs::msg::Point> & path_intersects,
const boost::optional<geometry_msgs::msg::Pose> & default_stop_pose)
const std::optional<geometry_msgs::msg::Pose> & default_stop_pose)
{
const auto & ego_pos = planner_data_->current_odometry->pose.position;
const auto & objects_ptr = planner_data_->predicted_objects;
Expand Down Expand Up @@ -480,8 +479,8 @@ std::pair<double, double> CrosswalkModule::clampAttentionRangeByNeighborCrosswal

sortCrosswalksByDistance(ego_path, ego_pos, crosswalks);

boost::optional<lanelet::ConstLanelet> prev_crosswalk{boost::none};
boost::optional<lanelet::ConstLanelet> next_crosswalk{boost::none};
std::optional<lanelet::ConstLanelet> prev_crosswalk{std::nullopt};
std::optional<lanelet::ConstLanelet> next_crosswalk{std::nullopt};

if (!crosswalks.empty()) {
for (size_t i = 0; i < crosswalks.size() - 1; ++i) {
Expand Down Expand Up @@ -748,10 +747,10 @@ Polygon2d CrosswalkModule::getAttentionArea(
return attention_area;
}

boost::optional<StopFactor> CrosswalkModule::checkStopForStuckedVehicles(
std::optional<StopFactor> CrosswalkModule::checkStopForStuckedVehicles(
const PathWithLaneId & ego_path, const std::vector<PredictedObject> & objects,
const std::vector<geometry_msgs::msg::Point> & path_intersects,
const boost::optional<geometry_msgs::msg::Pose> & stop_pose) const
const std::optional<geometry_msgs::msg::Pose> & stop_pose) const
{
if (path_intersects.size() < 2 || !stop_pose) {
return {};
Expand Down Expand Up @@ -789,14 +788,14 @@ boost::optional<StopFactor> CrosswalkModule::checkStopForStuckedVehicles(
return {};
}

boost::optional<StopFactor> CrosswalkModule::getNearestStopFactor(
std::optional<StopFactor> CrosswalkModule::getNearestStopFactor(
const PathWithLaneId & ego_path,
const boost::optional<StopFactor> & stop_factor_for_crosswalk_users,
const boost::optional<StopFactor> & stop_factor_for_stucked_vehicles)
const std::optional<StopFactor> & stop_factor_for_crosswalk_users,
const std::optional<StopFactor> & stop_factor_for_stucked_vehicles)
{
const auto get_distance_to_stop = [&](const auto stop_factor) -> boost::optional<double> {
const auto get_distance_to_stop = [&](const auto stop_factor) -> std::optional<double> {
const auto & ego_pos = planner_data_->current_odometry->pose.position;
if (!stop_factor) return boost::none;
if (!stop_factor) return std::nullopt;
return calcSignedArcLength(ego_path.points, ego_pos, stop_factor->stop_pose.position);
};
const auto dist_to_stop_for_crosswalk_users =
Expand Down Expand Up @@ -967,7 +966,7 @@ geometry_msgs::msg::Polygon CrosswalkModule::createVehiclePolygon(
}

void CrosswalkModule::planGo(
PathWithLaneId & ego_path, const boost::optional<StopFactor> & stop_factor)
PathWithLaneId & ego_path, const std::optional<StopFactor> & stop_factor)
{
if (!stop_factor) {
setDistance(std::numeric_limits<double>::lowest());
Expand All @@ -988,13 +987,13 @@ void CrosswalkModule::planGo(
}

void CrosswalkModule::planStop(
PathWithLaneId & ego_path, const boost::optional<StopFactor> & nearest_stop_factor,
const boost::optional<geometry_msgs::msg::Pose> & default_stop_pose, StopReason * stop_reason)
PathWithLaneId & ego_path, const std::optional<StopFactor> & nearest_stop_factor,
const std::optional<geometry_msgs::msg::Pose> & default_stop_pose, StopReason * stop_reason)
{
const auto stop_factor = [&]() -> boost::optional<StopFactor> {
const auto stop_factor = [&]() -> std::optional<StopFactor> {
if (nearest_stop_factor) return *nearest_stop_factor;
if (default_stop_pose) return createStopFactor(*default_stop_pose);
return boost::none;
return std::nullopt;
}();

if (!stop_factor) {
Expand Down
29 changes: 15 additions & 14 deletions planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include <pcl_conversions/pcl_conversions.h>

#include <memory>
#include <optional>
#include <string>
#include <unordered_map>
#include <utility>
Expand Down Expand Up @@ -98,7 +99,7 @@ class CrosswalkModule : public SceneModuleInterface
// NOTE: FULLY_STOPPED means stopped object which can be ignored.
enum class State { STOPPED = 0, FULLY_STOPPED, OTHER };
State state{State::OTHER};
boost::optional<rclcpp::Time> time_to_start_stopped{boost::none};
std::optional<rclcpp::Time> time_to_start_stopped{std::nullopt};

void updateState(
const rclcpp::Time & now, const double obj_vel, const bool is_ego_yielding,
Expand All @@ -123,7 +124,7 @@ class CrosswalkModule : public SceneModuleInterface
state = State::STOPPED;
}
} else {
time_to_start_stopped = boost::none;
time_to_start_stopped = std::nullopt;
state = State::OTHER;
}
}
Expand Down Expand Up @@ -182,35 +183,35 @@ class CrosswalkModule : public SceneModuleInterface
void applySafetySlowDownSpeed(
PathWithLaneId & output, const std::vector<geometry_msgs::msg::Point> & path_intersects);

boost::optional<std::pair<geometry_msgs::msg::Point, double>> getStopPointWithMargin(
std::optional<std::pair<geometry_msgs::msg::Point, double>> getStopPointWithMargin(
const PathWithLaneId & ego_path,
const std::vector<geometry_msgs::msg::Point> & path_intersects) const;

boost::optional<StopFactor> checkStopForCrosswalkUsers(
std::optional<StopFactor> checkStopForCrosswalkUsers(
const PathWithLaneId & ego_path, const PathWithLaneId & sparse_resample_path,
const boost::optional<std::pair<geometry_msgs::msg::Point, double>> & p_stop_line,
const std::optional<std::pair<geometry_msgs::msg::Point, double>> & p_stop_line,
const std::vector<geometry_msgs::msg::Point> & path_intersects,
const boost::optional<geometry_msgs::msg::Pose> & default_stop_pose);
const std::optional<geometry_msgs::msg::Pose> & default_stop_pose);

boost::optional<StopFactor> checkStopForStuckedVehicles(
std::optional<StopFactor> checkStopForStuckedVehicles(
const PathWithLaneId & ego_path, const std::vector<PredictedObject> & objects,
const std::vector<geometry_msgs::msg::Point> & path_intersects,
const boost::optional<geometry_msgs::msg::Pose> & stop_pose) const;
const std::optional<geometry_msgs::msg::Pose> & stop_pose) const;

std::vector<CollisionPoint> getCollisionPoints(
const PathWithLaneId & ego_path, const PredictedObject & object,
const Polygon2d & attention_area, const std::pair<double, double> & crosswalk_attention_range);

boost::optional<StopFactor> getNearestStopFactor(
std::optional<StopFactor> getNearestStopFactor(
const PathWithLaneId & ego_path,
const boost::optional<StopFactor> & stop_factor_for_crosswalk_users,
const boost::optional<StopFactor> & stop_factor_for_stucked_vehicles);
const std::optional<StopFactor> & stop_factor_for_crosswalk_users,
const std::optional<StopFactor> & stop_factor_for_stucked_vehicles);

void planGo(PathWithLaneId & ego_path, const boost::optional<StopFactor> & stop_factor);
void planGo(PathWithLaneId & ego_path, const std::optional<StopFactor> & stop_factor);

void planStop(
PathWithLaneId & ego_path, const boost::optional<StopFactor> & nearest_stop_factor,
const boost::optional<geometry_msgs::msg::Pose> & default_stop_pose, StopReason * stop_reason);
PathWithLaneId & ego_path, const std::optional<StopFactor> & nearest_stop_factor,
const std::optional<geometry_msgs::msg::Pose> & default_stop_pose, StopReason * stop_reason);

// minor functions
std::pair<double, double> getAttentionRange(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ WalkwayModule::WalkwayModule(
}
}

boost::optional<std::pair<double, geometry_msgs::msg::Point>> WalkwayModule::getStopLine(
std::optional<std::pair<double, geometry_msgs::msg::Point>> WalkwayModule::getStopLine(
const PathWithLaneId & ego_path, bool & exist_stopline_in_map,
const std::vector<geometry_msgs::msg::Point> & path_intersects) const
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <lanelet2_routing/RoutingGraphContainer.h>

#include <memory>
#include <optional>
#include <utility>
#include <vector>

Expand Down Expand Up @@ -57,7 +58,7 @@ class WalkwayModule : public SceneModuleInterface
private:
const int64_t module_id_;

[[nodiscard]] boost::optional<std::pair<double, geometry_msgs::msg::Point>> getStopLine(
[[nodiscard]] std::optional<std::pair<double, geometry_msgs::msg::Point>> getStopLine(
const PathWithLaneId & ego_path, bool & exist_stopline_in_map,
const std::vector<geometry_msgs::msg::Point> & path_intersects) const;

Expand Down
5 changes: 3 additions & 2 deletions planning/behavior_velocity_crosswalk_module/src/util.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@

#include <limits>
#include <memory>
#include <optional>
#include <string>
#include <utility>
#include <vector>
Expand Down Expand Up @@ -68,8 +69,8 @@ struct DebugData
geometry_msgs::msg::Pose first_stop_pose;
geometry_msgs::msg::Point nearest_collision_point;

boost::optional<geometry_msgs::msg::Point> range_near_point{boost::none};
boost::optional<geometry_msgs::msg::Point> range_far_point{boost::none};
std::optional<geometry_msgs::msg::Point> range_near_point{std::nullopt};
std::optional<geometry_msgs::msg::Point> range_far_point{std::nullopt};

std::vector<std::pair<CollisionPoint, CollisionState>> collision_points;

Expand Down

0 comments on commit 6922164

Please sign in to comment.