Skip to content

Commit

Permalink
fix(behavior_velocity_planner): fix clang-tidy warning in crosswalk m…
Browse files Browse the repository at this point in the history
…odule (#1556)

* fix(behavior_velocity_planner): fix clang-tidy warning in crosswalk module

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

* fix(behavior_velocity_planner): fix clang-tidy warning in crosswalk module

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota authored Aug 15, 2022
1 parent 4296138 commit cc699cc
Show file tree
Hide file tree
Showing 7 changed files with 34 additions and 40 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class CrosswalkModuleManager : public SceneModuleManagerInterfaceWithRTC
const char * getModuleName() override { return "crosswalk"; }

private:
CrosswalkModule::PlannerParam crosswalk_planner_param_;
CrosswalkModule::PlannerParam crosswalk_planner_param_{};

void launchNewModules(const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override;

Expand All @@ -54,7 +54,7 @@ class WalkwayModuleManager : public SceneModuleManagerInterface
const char * getModuleName() override { return "walkway"; }

private:
WalkwayModule::PlannerParam walkway_planner_param_;
WalkwayModule::PlannerParam walkway_planner_param_{};

void launchNewModules(const autoware_auto_planning_msgs::msg::PathWithLaneId & path) override;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,9 +94,8 @@ class CrosswalkModule : public SceneModuleInterface
};

CrosswalkModule(
const int64_t module_id, const lanelet::ConstLanelet & crosswalk,
const PlannerParam & planner_param, const rclcpp::Logger logger,
const rclcpp::Clock::SharedPtr clock);
const int64_t module_id, lanelet::ConstLanelet crosswalk, const PlannerParam & planner_param,
const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock);

bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override;

Expand Down Expand Up @@ -142,17 +141,17 @@ class CrosswalkModule : public SceneModuleInterface

bool isRedSignalForPedestrians() const;

bool isVehicle(const PredictedObject & object) const;
static bool isVehicle(const PredictedObject & object);

bool isTargetType(const PredictedObject & object) const;

bool isTargetExternalInputStatus(const int target_status) const;

geometry_msgs::msg::Polygon createObjectPolygon(
const double width_m, const double length_m) const;
static geometry_msgs::msg::Polygon createObjectPolygon(
const double width_m, const double length_m);

geometry_msgs::msg::Polygon createVehiclePolygon(
const vehicle_info_util::VehicleInfo & vehicle_info) const;
static geometry_msgs::msg::Polygon createVehiclePolygon(
const vehicle_info_util::VehicleInfo & vehicle_info);

lanelet::ConstLanelet crosswalk_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@ using tier4_planning_msgs::msg::StopReason;

class WalkwayModule : public SceneModuleInterface
{
public:
public:
struct PlannerParam
{
Expand All @@ -48,9 +47,8 @@ class WalkwayModule : public SceneModuleInterface
double external_input_timeout;
};
WalkwayModule(
const int64_t module_id, const lanelet::ConstLanelet & walkway,
const PlannerParam & planner_param, const rclcpp::Logger logger,
const rclcpp::Clock::SharedPtr clock);
const int64_t module_id, lanelet::ConstLanelet walkway, const PlannerParam & planner_param,
const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock);

bool modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason) override;

Expand All @@ -60,7 +58,7 @@ class WalkwayModule : public SceneModuleInterface
private:
int64_t module_id_;

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

void insertStopPoint(const geometry_msgs::msg::Point & stop_point, PathWithLaneId & output);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@ enum class CollisionPointState { YIELD, EGO_PASS_FIRST, EGO_PASS_LATER, IGNORE }
struct CollisionPoint
{
geometry_msgs::msg::Point collision_point{};
double time_to_collision;
double time_to_vehicle;
double time_to_collision{};
double time_to_vehicle{};
CollisionPointState state{CollisionPointState::EGO_PASS_FIRST};
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,12 +32,9 @@ using motion_utils::calcArcLength;
using motion_utils::calcLateralOffset;
using motion_utils::calcLongitudinalOffsetPoint;
using motion_utils::calcLongitudinalOffsetPose;
using motion_utils::calcLongitudinalOffsetToSegment;
using motion_utils::calcSignedArcLength;
using motion_utils::findNearestIndex;
using motion_utils::findNearestSegmentIndex;
using motion_utils::insertTargetPoint;
using tier4_autoware_utils::calcDistance2d;
using tier4_autoware_utils::createPoint;
using tier4_autoware_utils::getPoint;
using tier4_autoware_utils::getPose;
Expand Down Expand Up @@ -133,12 +130,13 @@ void sortCrosswalksByDistance(
} // namespace

CrosswalkModule::CrosswalkModule(
const int64_t module_id, const lanelet::ConstLanelet & crosswalk,
const PlannerParam & planner_param, const rclcpp::Logger logger,
const rclcpp::Clock::SharedPtr clock)
: SceneModuleInterface(module_id, logger, clock), module_id_(module_id), crosswalk_(crosswalk)
const int64_t module_id, lanelet::ConstLanelet crosswalk, const PlannerParam & planner_param,
const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock)
: SceneModuleInterface(module_id, logger, clock),
module_id_(module_id),
crosswalk_(std::move(crosswalk)),
planner_param_(planner_param)
{
planner_param_ = planner_param;
}

bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_reason)
Expand Down Expand Up @@ -726,13 +724,13 @@ CollisionPointState CrosswalkModule::getCollisionPointState(
{
if (ttc + planner_param_.ego_pass_first_margin < ttv) {
return CollisionPointState::EGO_PASS_FIRST;
} else if (ttv + planner_param_.ego_pass_later_margin < ttc) {
}

if (ttv + planner_param_.ego_pass_later_margin < ttc) {
return CollisionPointState::EGO_PASS_LATER;
} else {
return CollisionPointState::YIELD;
}

return CollisionPointState::IGNORE;
return CollisionPointState::YIELD;
}

bool CrosswalkModule::isStuckVehicle(
Expand Down Expand Up @@ -801,7 +799,7 @@ bool CrosswalkModule::isRedSignalForPedestrians() const
return false;
}

bool CrosswalkModule::isVehicle(const PredictedObject & object) const
bool CrosswalkModule::isVehicle(const PredictedObject & object)
{
if (object.classification.empty()) {
return false;
Expand Down Expand Up @@ -875,7 +873,7 @@ bool CrosswalkModule::isTargetExternalInputStatus(const int target_status) const
}

geometry_msgs::msg::Polygon CrosswalkModule::createObjectPolygon(
const double width_m, const double length_m) const
const double width_m, const double length_m)
{
geometry_msgs::msg::Polygon polygon{};

Expand All @@ -888,7 +886,7 @@ geometry_msgs::msg::Polygon CrosswalkModule::createObjectPolygon(
}

geometry_msgs::msg::Polygon CrosswalkModule::createVehiclePolygon(
const vehicle_info_util::VehicleInfo & vehicle_info) const
const vehicle_info_util::VehicleInfo & vehicle_info)
{
const auto & i = vehicle_info;
const auto & front_m = i.max_longitudinal_offset_m;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,15 +32,14 @@ using tier4_autoware_utils::createPoint;
using tier4_autoware_utils::getPose;

WalkwayModule::WalkwayModule(
const int64_t module_id, const lanelet::ConstLanelet & walkway,
const PlannerParam & planner_param, const rclcpp::Logger logger,
const rclcpp::Clock::SharedPtr clock)
const int64_t module_id, lanelet::ConstLanelet walkway, const PlannerParam & planner_param,
const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock)
: SceneModuleInterface(module_id, logger, clock),
module_id_(module_id),
walkway_(walkway),
state_(State::APPROACH)
walkway_(std::move(walkway)),
state_(State::APPROACH),
planner_param_(planner_param)
{
planner_param_ = planner_param;
}

boost::optional<std::pair<double, geometry_msgs::msg::Point>> WalkwayModule::getStopLine(
Expand Down Expand Up @@ -139,8 +138,9 @@ bool WalkwayModule::modifyPathVelocity(PathWithLaneId * path, StopReason * stop_
}

return true;
}

} else if (state_ == State::STOP) {
if (state_ == State::STOP) {
if (planner_data_->isVehicleStopped()) {
state_ = State::SURPASSED;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@ using Point = bg::model::d2::point_xy<double>;
using Polygon = bg::model::polygon<Point>;
using Line = bg::model::linestring<Point>;
using motion_utils::calcSignedArcLength;
using motion_utils::findNearestSegmentIndex;
using tier4_autoware_utils::createPoint;

std::vector<Point> getPolygonIntersects(
Expand Down

0 comments on commit cc699cc

Please sign in to comment.