Skip to content

Commit 2fa8f5f

Browse files
committed
rename kHungarian to snake_case
1 parent 958bce8 commit 2fa8f5f

File tree

6 files changed

+25
-25
lines changed

6 files changed

+25
-25
lines changed

simulation/behavior_tree_plugin/include/behavior_tree_plugin/vehicle/follow_lane_sequence/follow_front_entity_action.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -42,9 +42,9 @@ class FollowFrontEntityAction : public entity_behavior::VehicleActionNode
4242

4343
private:
4444
std::optional<double> distance_to_front_entity_;
45-
static constexpr double kWaypointInterval = 1.0;
46-
static constexpr double kFrontEntityMargin = 5.0;
47-
static constexpr double kSpeedStep = 2.0;
45+
static constexpr double waypoint_interval = 1.0;
46+
static constexpr double front_entity_margin = 5.0;
47+
static constexpr double speed_step = 2.0;
4848
};
4949
} // namespace follow_lane_sequence
5050
} // namespace vehicle

simulation/behavior_tree_plugin/include/behavior_tree_plugin/vehicle/follow_lane_sequence/follow_lane_action.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -43,11 +43,11 @@ class FollowLaneAction : public entity_behavior::VehicleActionNode
4343

4444
private:
4545
std::optional<traffic_simulator::LaneletPose> target_lanelet_pose_;
46-
static constexpr double kWaypointInterval = 1.0;
47-
static constexpr double kFrontEntityStopMargin = 5.0;
48-
static constexpr double kBoundingBoxHalfFactor = 0.5;
49-
static constexpr double kStopLineMargin = 5.0;
50-
static constexpr double kConflictingEntityMargin = 3.0;
46+
static constexpr double waypoint_interval = 1.0;
47+
static constexpr double front_entity_stop_margin = 5.0;
48+
static constexpr double bounding_box_half_factor = 0.5;
49+
static constexpr double stop_line_margin = 5.0;
50+
static constexpr double conflicting_entity_margin = 3.0;
5151
};
5252
} // namespace follow_lane_sequence
5353
} // namespace vehicle

simulation/behavior_tree_plugin/include/behavior_tree_plugin/vehicle/follow_lane_sequence/stop_at_stop_line_action.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -43,11 +43,11 @@ class StopAtStopLineAction : public entity_behavior::VehicleActionNode
4343

4444
private:
4545
std::optional<double> distance_to_stopline_;
46-
static constexpr double kWaypointInterval = 1.0;
47-
static constexpr double kBoundingBoxHalfFactor = 0.5;
48-
static constexpr double kStopMargin = 1.0;
49-
static constexpr double kFrontStoplineMargin = 5.0;
50-
static constexpr double kVelocityEpsilon = 0.001;
46+
static constexpr double waypoint_interval = 1.0;
47+
static constexpr double bounding_box_half_factor = 0.5;
48+
static constexpr double stop_margin = 1.0;
49+
static constexpr double front_stopline_margin = 5.0;
50+
static constexpr double velocity_epsilon = 0.001;
5151
};
5252
} // namespace follow_lane_sequence
5353
} // namespace vehicle

simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/follow_front_entity_action.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ const traffic_simulator_msgs::msg::WaypointsArray FollowFrontEntityAction::calcu
6060
double horizon = getHorizon();
6161
const auto lanelet_pose = canonicalized_entity_status_->getLaneletPose();
6262
waypoints.waypoints = reference_trajectory->getTrajectory(
63-
lanelet_pose.s, lanelet_pose.s + horizon, kWaypointInterval, lanelet_pose.offset);
63+
lanelet_pose.s, lanelet_pose.s + horizon, waypoint_interval, lanelet_pose.offset);
6464
trajectory = std::make_unique<math::geometry::CatmullRomSubspline>(
6565
reference_trajectory, lanelet_pose.s, lanelet_pose.s + horizon);
6666
return waypoints;
@@ -127,17 +127,17 @@ BT::NodeStatus FollowFrontEntityAction::tick()
127127
if (
128128
distance_to_front_entity_.value() >=
129129
(calculateStopDistance(behavior_parameter_.dynamic_constraints) +
130-
vehicle_parameters.bounding_box.dimensions.x + kFrontEntityMargin)) {
130+
vehicle_parameters.bounding_box.dimensions.x + front_entity_margin)) {
131131
setCanonicalizedEntityStatus(
132-
calculateUpdatedEntityStatus(front_entity_linear_velocity + kSpeedStep));
132+
calculateUpdatedEntityStatus(front_entity_linear_velocity + speed_step));
133133
setOutput("waypoints", waypoints);
134134
setOutput("obstacle", calculateObstacle(waypoints));
135135
return BT::NodeStatus::RUNNING;
136136
} else if (
137137
distance_to_front_entity_.value() <=
138138
calculateStopDistance(behavior_parameter_.dynamic_constraints)) {
139139
setCanonicalizedEntityStatus(
140-
calculateUpdatedEntityStatus(front_entity_linear_velocity - kSpeedStep));
140+
calculateUpdatedEntityStatus(front_entity_linear_velocity - speed_step));
141141
setOutput("waypoints", waypoints);
142142
setOutput("obstacle", calculateObstacle(waypoints));
143143
return BT::NodeStatus::RUNNING;

simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/follow_lane_action.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ const traffic_simulator_msgs::msg::WaypointsArray FollowLaneAction::calculateWay
4646
traffic_simulator_msgs::msg::WaypointsArray waypoints;
4747
const auto lanelet_pose = canonicalized_entity_status_->getLaneletPose();
4848
waypoints.waypoints = reference_trajectory->getTrajectory(
49-
lanelet_pose.s, lanelet_pose.s + getHorizon(), kWaypointInterval, lanelet_pose.offset);
49+
lanelet_pose.s, lanelet_pose.s + getHorizon(), waypoint_interval, lanelet_pose.offset);
5050
trajectory = std::make_unique<math::geometry::CatmullRomSubspline>(
5151
reference_trajectory, lanelet_pose.s, lanelet_pose.s + getHorizon());
5252
return waypoints;
@@ -97,7 +97,7 @@ BT::NodeStatus FollowLaneAction::tick()
9797
if (
9898
distance_to_front_entity.value() <=
9999
calculateStopDistance(behavior_parameter_.dynamic_constraints) +
100-
vehicle_parameters.bounding_box.dimensions.x + kFrontEntityStopMargin) {
100+
vehicle_parameters.bounding_box.dimensions.x + front_entity_stop_margin) {
101101
return BT::NodeStatus::FAILURE;
102102
}
103103
}
@@ -116,14 +116,14 @@ BT::NodeStatus FollowLaneAction::tick()
116116
if (
117117
distance_to_stopline.value() <=
118118
calculateStopDistance(behavior_parameter_.dynamic_constraints) +
119-
vehicle_parameters.bounding_box.dimensions.x * kBoundingBoxHalfFactor + kStopLineMargin) {
119+
vehicle_parameters.bounding_box.dimensions.x * bounding_box_half_factor + stop_line_margin) {
120120
return BT::NodeStatus::FAILURE;
121121
}
122122
}
123123
if (distance_to_conflicting_entity) {
124124
if (
125125
distance_to_conflicting_entity.value() <
126-
(vehicle_parameters.bounding_box.dimensions.x + kConflictingEntityMargin +
126+
(vehicle_parameters.bounding_box.dimensions.x + conflicting_entity_margin +
127127
calculateStopDistance(behavior_parameter_.dynamic_constraints))) {
128128
return BT::NodeStatus::FAILURE;
129129
}

simulation/behavior_tree_plugin/src/vehicle/follow_lane_sequence/stop_at_stop_line_action.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ const traffic_simulator_msgs::msg::WaypointsArray StopAtStopLineAction::calculat
5757
double horizon = getHorizon();
5858
const auto lanelet_pose = canonicalized_entity_status_->getLaneletPose();
5959
waypoints.waypoints = reference_trajectory->getTrajectory(
60-
lanelet_pose.s, lanelet_pose.s + horizon, kWaypointInterval, lanelet_pose.offset);
60+
lanelet_pose.s, lanelet_pose.s + horizon, waypoint_interval, lanelet_pose.offset);
6161
trajectory = std::make_unique<math::geometry::CatmullRomSubspline>(
6262
reference_trajectory, lanelet_pose.s, lanelet_pose.s + horizon);
6363
return waypoints;
@@ -76,7 +76,7 @@ std::optional<double> StopAtStopLineAction::calculateTargetSpeed(double current_
7676
*/
7777
double rest_distance =
7878
distance_to_stopline_.value() -
79-
(vehicle_parameters.bounding_box.dimensions.x * kBoundingBoxHalfFactor + kStopMargin);
79+
(vehicle_parameters.bounding_box.dimensions.x * bounding_box_half_factor + stop_margin);
8080
if (rest_distance < calculateStopDistance(behavior_parameter_.dynamic_constraints)) {
8181
return 0;
8282
}
@@ -125,11 +125,11 @@ BT::NodeStatus StopAtStopLineAction::tick()
125125
}
126126
}
127127

128-
if (std::fabs(canonicalized_entity_status_->getTwist().linear.x) < kVelocityEpsilon) {
128+
if (std::fabs(canonicalized_entity_status_->getTwist().linear.x) < velocity_epsilon) {
129129
if (distance_to_stopline_) {
130130
if (
131131
distance_to_stopline_.value() <=
132-
vehicle_parameters.bounding_box.dimensions.x + kFrontStoplineMargin) {
132+
vehicle_parameters.bounding_box.dimensions.x + front_stopline_margin) {
133133
if (!target_speed_) {
134134
target_speed_ = hdmap_utils_->getSpeedLimit(route_lanelets_);
135135
}

0 commit comments

Comments
 (0)