Skip to content

Commit 29faba5

Browse files
authored
refactor(lane_change): add const to lane change functions (#6175)
Signed-off-by: Fumiya Watanabe <rej55.g@gmail.com>
1 parent 0a057e1 commit 29faba5

File tree

3 files changed

+9
-9
lines changed

3 files changed

+9
-9
lines changed

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ class NormalLaneChange : public LaneChangeBase
5555

5656
BehaviorModuleOutput generateOutput() override;
5757

58-
void extendOutputDrivableArea(BehaviorModuleOutput & output) override;
58+
void extendOutputDrivableArea(BehaviorModuleOutput & output) const override;
5959

6060
void insertStopPoint(const lanelet::ConstLanelets & lanelets, PathWithLaneId & path) override;
6161

@@ -65,7 +65,7 @@ class NormalLaneChange : public LaneChangeBase
6565

6666
void resetParameters() override;
6767

68-
TurnSignalInfo updateOutputTurnSignal() override;
68+
TurnSignalInfo updateOutputTurnSignal() const override;
6969

7070
bool calcAbortPath() override;
7171

@@ -141,7 +141,7 @@ class NormalLaneChange : public LaneChangeBase
141141
const utils::path_safety_checker::RSSparams rss_params, const bool is_stuck,
142142
const bool check_safety = true) const override;
143143

144-
TurnSignalInfo calcTurnSignalInfo() override;
144+
TurnSignalInfo calcTurnSignalInfo() const override;
145145

146146
bool isValidPath(const PathWithLaneId & path) const override;
147147

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -66,15 +66,15 @@ class LaneChangeBase
6666

6767
virtual BehaviorModuleOutput generateOutput() = 0;
6868

69-
virtual void extendOutputDrivableArea(BehaviorModuleOutput & output) = 0;
69+
virtual void extendOutputDrivableArea(BehaviorModuleOutput & output) const = 0;
7070

7171
virtual PathWithLaneId getReferencePath() const = 0;
7272

7373
virtual std::optional<PathWithLaneId> extendPath() = 0;
7474

7575
virtual void resetParameters() = 0;
7676

77-
virtual TurnSignalInfo updateOutputTurnSignal() = 0;
77+
virtual TurnSignalInfo updateOutputTurnSignal() const = 0;
7878

7979
virtual bool hasFinishedLaneChange() const = 0;
8080

@@ -225,7 +225,7 @@ class LaneChangeBase
225225
LaneChangePaths * candidate_paths, const utils::path_safety_checker::RSSparams rss_params,
226226
const bool is_stuck, const bool check_safety) const = 0;
227227

228-
virtual TurnSignalInfo calcTurnSignalInfo() = 0;
228+
virtual TurnSignalInfo calcTurnSignalInfo() const = 0;
229229

230230
virtual bool isValidPath(const PathWithLaneId & path) const = 0;
231231

planning/behavior_path_lane_change_module/src/scene.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,7 @@ BehaviorModuleOutput NormalLaneChange::generateOutput()
183183
return output;
184184
}
185185

186-
void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output)
186+
void NormalLaneChange::extendOutputDrivableArea(BehaviorModuleOutput & output) const
187187
{
188188
const auto & dp = planner_data_->drivable_area_expansion_parameters;
189189

@@ -431,7 +431,7 @@ void NormalLaneChange::resetParameters()
431431
RCLCPP_DEBUG(logger_, "reset all flags and debug information.");
432432
}
433433

434-
TurnSignalInfo NormalLaneChange::updateOutputTurnSignal()
434+
TurnSignalInfo NormalLaneChange::updateOutputTurnSignal() const
435435
{
436436
TurnSignalInfo turn_signal_info = calcTurnSignalInfo();
437437
const auto [turn_signal_command, distance_to_vehicle_front] = utils::getPathTurnSignal(
@@ -1447,7 +1447,7 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
14471447
return safety_status;
14481448
}
14491449

1450-
TurnSignalInfo NormalLaneChange::calcTurnSignalInfo()
1450+
TurnSignalInfo NormalLaneChange::calcTurnSignalInfo() const
14511451
{
14521452
const auto get_blinker_pose = [](const PathWithLaneId & path, const double length) {
14531453
double accumulated_length = 0.0;

0 commit comments

Comments
 (0)