Skip to content

Commit f5bfa67

Browse files
authored
Merge pull request #1606 from tier4/refactor/behavior-tree-2
Refactor/behavior tree 2
2 parents 427debb + c842d1a commit f5bfa67

File tree

10 files changed

+49
-71
lines changed

10 files changed

+49
-71
lines changed

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

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

4343
private:
4444
std::optional<double> distance_to_front_entity_;
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;
4548
};
4649
} // namespace follow_lane_sequence
4750
} // namespace vehicle

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

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

4444
private:
4545
std::optional<traffic_simulator::LaneletPose> target_lanelet_pose_;
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;
4651
};
4752
} // namespace follow_lane_sequence
4853
} // namespace vehicle

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,6 @@ class StopAtCrossingEntityAction : public entity_behavior::VehicleActionNode
4343

4444
private:
4545
std::optional<double> distance_to_stop_target_;
46-
bool in_stop_sequence_;
4746
};
4847
} // namespace follow_lane_sequence
4948
} // namespace vehicle

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

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,12 @@ class StopAtStopLineAction : public entity_behavior::VehicleActionNode
4242
const traffic_simulator_msgs::msg::WaypointsArray & waypoints) override;
4343

4444
private:
45-
bool stopped_;
4645
std::optional<double> distance_to_stopline_;
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;
4751
};
4852
} // namespace follow_lane_sequence
4953
} // namespace vehicle

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

Lines changed: 6 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, 1.0, 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,15 +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 + 5)) {
131-
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(front_entity_linear_velocity + 2));
130+
vehicle_parameters.bounding_box.dimensions.x + front_entity_margin)) {
131+
setCanonicalizedEntityStatus(
132+
calculateUpdatedEntityStatus(front_entity_linear_velocity + speed_step));
132133
setOutput("waypoints", waypoints);
133134
setOutput("obstacle", calculateObstacle(waypoints));
134135
return BT::NodeStatus::RUNNING;
135136
} else if (
136137
distance_to_front_entity_.value() <=
137138
calculateStopDistance(behavior_parameter_.dynamic_constraints)) {
138-
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(front_entity_linear_velocity - 2));
139+
setCanonicalizedEntityStatus(
140+
calculateUpdatedEntityStatus(front_entity_linear_velocity - speed_step));
139141
setOutput("waypoints", waypoints);
140142
setOutput("obstacle", calculateObstacle(waypoints));
141143
return BT::NodeStatus::RUNNING;

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

Lines changed: 5 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(), 1.0, 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 + 5) {
100+
vehicle_parameters.bounding_box.dimensions.x + front_entity_stop_margin) {
101101
return BT::NodeStatus::FAILURE;
102102
}
103103
}
@@ -116,14 +116,15 @@ BT::NodeStatus FollowLaneAction::tick()
116116
if (
117117
distance_to_stopline.value() <=
118118
calculateStopDistance(behavior_parameter_.dynamic_constraints) +
119-
vehicle_parameters.bounding_box.dimensions.x * 0.5 + 5) {
119+
vehicle_parameters.bounding_box.dimensions.x * bounding_box_half_factor +
120+
stop_line_margin) {
120121
return BT::NodeStatus::FAILURE;
121122
}
122123
}
123124
if (distance_to_conflicting_entity) {
124125
if (
125126
distance_to_conflicting_entity.value() <
126-
(vehicle_parameters.bounding_box.dimensions.x + 3 +
127+
(vehicle_parameters.bounding_box.dimensions.x + conflicting_entity_margin +
127128
calculateStopDistance(behavior_parameter_.dynamic_constraints))) {
128129
return BT::NodeStatus::FAILURE;
129130
}

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

Lines changed: 5 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,6 @@ StopAtCrossingEntityAction::StopAtCrossingEntityAction(
3131
const std::string & name, const BT::NodeConfiguration & config)
3232
: entity_behavior::VehicleActionNode(name, config)
3333
{
34-
in_stop_sequence_ = false;
3534
}
3635

3736
const std::optional<traffic_simulator_msgs::msg::Obstacle>
@@ -89,19 +88,15 @@ BT::NodeStatus StopAtCrossingEntityAction::tick()
8988
if (
9089
request_ != traffic_simulator::behavior::Request::NONE &&
9190
request_ != traffic_simulator::behavior::Request::FOLLOW_LANE) {
92-
in_stop_sequence_ = false;
9391
return BT::NodeStatus::FAILURE;
9492
}
9593
if (!canonicalized_entity_status_->isInLanelet()) {
96-
in_stop_sequence_ = false;
9794
return BT::NodeStatus::FAILURE;
9895
}
9996
if (!behavior_parameter_.see_around) {
100-
in_stop_sequence_ = false;
10197
return BT::NodeStatus::FAILURE;
10298
}
10399
if (getRightOfWayEntities(route_lanelets_).size() != 0) {
104-
in_stop_sequence_ = false;
105100
return BT::NodeStatus::FAILURE;
106101
}
107102
const auto waypoints = calculateWaypoints();
@@ -111,39 +106,26 @@ BT::NodeStatus StopAtCrossingEntityAction::tick()
111106
if (trajectory == nullptr) {
112107
return BT::NodeStatus::FAILURE;
113108
}
114-
distance_to_stop_target_ = getDistanceToConflictingEntity(route_lanelets_, *trajectory);
109+
std::optional<double> target_linear_speed;
115110
auto distance_to_stopline =
116111
traffic_simulator::distance::distanceToStopLine(route_lanelets_, *trajectory);
117112
const auto distance_to_front_entity = getDistanceToFrontEntity(*trajectory);
118-
if (!distance_to_stop_target_) {
119-
in_stop_sequence_ = false;
113+
distance_to_stop_target_ = getDistanceToConflictingEntity(route_lanelets_, *trajectory);
114+
if (distance_to_stop_target_) {
115+
target_linear_speed = calculateTargetSpeed(canonicalized_entity_status_->getTwist().linear.x);
116+
} else {
120117
return BT::NodeStatus::FAILURE;
121118
}
122119
if (distance_to_front_entity) {
123120
if (distance_to_front_entity.value() <= distance_to_stop_target_.value()) {
124-
in_stop_sequence_ = false;
125121
return BT::NodeStatus::FAILURE;
126122
}
127123
}
128124
if (distance_to_stopline) {
129125
if (distance_to_stopline.value() <= distance_to_stop_target_.value()) {
130-
in_stop_sequence_ = false;
131126
return BT::NodeStatus::FAILURE;
132127
}
133128
}
134-
std::optional<double> target_linear_speed;
135-
if (distance_to_stop_target_) {
136-
target_linear_speed = calculateTargetSpeed(canonicalized_entity_status_->getTwist().linear.x);
137-
} else {
138-
target_linear_speed = std::nullopt;
139-
}
140-
if (!distance_to_stop_target_) {
141-
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(0));
142-
setOutput("waypoints", waypoints);
143-
setOutput("obstacle", calculateObstacle(waypoints));
144-
in_stop_sequence_ = false;
145-
return BT::NodeStatus::SUCCESS;
146-
}
147129
if (target_speed_) {
148130
if (target_speed_.value() > target_linear_speed.value()) {
149131
target_speed_ = target_linear_speed.value();
@@ -154,7 +136,6 @@ BT::NodeStatus StopAtCrossingEntityAction::tick()
154136
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed_.value()));
155137
setOutput("waypoints", waypoints);
156138
setOutput("obstacle", calculateObstacle(waypoints));
157-
in_stop_sequence_ = true;
158139
return BT::NodeStatus::RUNNING;
159140
}
160141
} // namespace follow_lane_sequence

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

Lines changed: 17 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,6 @@ StopAtStopLineAction::StopAtStopLineAction(
3030
const std::string & name, const BT::NodeConfiguration & config)
3131
: entity_behavior::VehicleActionNode(name, config)
3232
{
33-
stopped_ = false;
3433
}
3534

3635
const std::optional<traffic_simulator_msgs::msg::Obstacle> StopAtStopLineAction::calculateObstacle(
@@ -53,15 +52,12 @@ const std::optional<traffic_simulator_msgs::msg::Obstacle> StopAtStopLineAction:
5352

5453
const traffic_simulator_msgs::msg::WaypointsArray StopAtStopLineAction::calculateWaypoints()
5554
{
56-
if (!canonicalized_entity_status_->isInLanelet()) {
57-
THROW_SIMULATION_ERROR("failed to assign lane");
58-
}
5955
if (canonicalized_entity_status_->getTwist().linear.x >= 0) {
6056
traffic_simulator_msgs::msg::WaypointsArray waypoints;
6157
double horizon = getHorizon();
6258
const auto lanelet_pose = canonicalized_entity_status_->getLaneletPose();
6359
waypoints.waypoints = reference_trajectory->getTrajectory(
64-
lanelet_pose.s, lanelet_pose.s + horizon, 1.0, lanelet_pose.offset);
60+
lanelet_pose.s, lanelet_pose.s + horizon, waypoint_interval, lanelet_pose.offset);
6561
trajectory = std::make_unique<math::geometry::CatmullRomSubspline>(
6662
reference_trajectory, lanelet_pose.s, lanelet_pose.s + horizon);
6763
return waypoints;
@@ -79,7 +75,8 @@ std::optional<double> StopAtStopLineAction::calculateTargetSpeed(double current_
7975
* @brief hard coded parameter!! 1.0 is a stop margin
8076
*/
8177
double rest_distance =
82-
distance_to_stopline_.value() - (vehicle_parameters.bounding_box.dimensions.x * 0.5 + 1.0);
78+
distance_to_stopline_.value() -
79+
(vehicle_parameters.bounding_box.dimensions.x * bounding_box_half_factor + stop_margin);
8380
if (rest_distance < calculateStopDistance(behavior_parameter_.dynamic_constraints)) {
8481
return 0;
8582
}
@@ -92,7 +89,6 @@ BT::NodeStatus StopAtStopLineAction::tick()
9289
if (
9390
request_ != traffic_simulator::behavior::Request::NONE &&
9491
request_ != traffic_simulator::behavior::Request::FOLLOW_LANE) {
95-
stopped_ = false;
9692
return BT::NodeStatus::FAILURE;
9793
}
9894
if (!behavior_parameter_.see_around) {
@@ -101,6 +97,9 @@ BT::NodeStatus StopAtStopLineAction::tick()
10197
if (getRightOfWayEntities(route_lanelets_).size() != 0) {
10298
return BT::NodeStatus::FAILURE;
10399
}
100+
if (!canonicalized_entity_status_->isInLanelet()) {
101+
return BT::NodeStatus::FAILURE;
102+
}
104103
const auto waypoints = calculateWaypoints();
105104
if (waypoints.waypoints.empty()) {
106105
return BT::NodeStatus::FAILURE;
@@ -113,49 +112,37 @@ BT::NodeStatus StopAtStopLineAction::tick()
113112
const auto distance_to_stop_target = getDistanceToConflictingEntity(route_lanelets_, *trajectory);
114113
const auto distance_to_front_entity = getDistanceToFrontEntity(*trajectory);
115114
if (!distance_to_stopline_) {
116-
stopped_ = false;
117115
return BT::NodeStatus::FAILURE;
118116
}
119117
if (distance_to_front_entity) {
120118
if (distance_to_front_entity.value() <= distance_to_stopline_.value()) {
121-
stopped_ = false;
122119
return BT::NodeStatus::FAILURE;
123120
}
124121
}
125122
if (distance_to_stop_target) {
126123
if (distance_to_stop_target.value() <= distance_to_stopline_.value()) {
127-
stopped_ = false;
128124
return BT::NodeStatus::FAILURE;
129125
}
130126
}
131127

132-
if (std::fabs(canonicalized_entity_status_->getTwist().linear.x) < 0.001) {
128+
if (std::fabs(canonicalized_entity_status_->getTwist().linear.x) < velocity_epsilon) {
133129
if (distance_to_stopline_) {
134-
if (distance_to_stopline_.value() <= vehicle_parameters.bounding_box.dimensions.x + 5) {
135-
stopped_ = true;
130+
if (
131+
distance_to_stopline_.value() <=
132+
vehicle_parameters.bounding_box.dimensions.x + front_stopline_margin) {
133+
if (!target_speed_) {
134+
target_speed_ = hdmap_utils_->getSpeedLimit(route_lanelets_);
135+
}
136+
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed_.value()));
137+
setOutput("waypoints", waypoints);
138+
setOutput("obstacle", calculateObstacle(waypoints));
139+
return BT::NodeStatus::RUNNING;
136140
}
137141
}
138142
}
139-
if (stopped_) {
140-
if (!target_speed_) {
141-
target_speed_ = hdmap_utils_->getSpeedLimit(route_lanelets_);
142-
}
143-
if (!distance_to_stopline_) {
144-
stopped_ = false;
145-
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed_.value()));
146-
setOutput("waypoints", waypoints);
147-
setOutput("obstacle", calculateObstacle(waypoints));
148-
return BT::NodeStatus::SUCCESS;
149-
}
150-
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed_.value()));
151-
setOutput("waypoints", waypoints);
152-
setOutput("obstacle", calculateObstacle(waypoints));
153-
return BT::NodeStatus::RUNNING;
154-
}
155143
auto target_linear_speed =
156144
calculateTargetSpeed(canonicalized_entity_status_->getTwist().linear.x);
157145
if (!target_linear_speed) {
158-
stopped_ = false;
159146
return BT::NodeStatus::FAILURE;
160147
}
161148
if (target_speed_) {
@@ -166,7 +153,6 @@ BT::NodeStatus StopAtStopLineAction::tick()
166153
target_speed_ = target_linear_speed.value();
167154
}
168155
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed_.value()));
169-
stopped_ = false;
170156
setOutput("waypoints", waypoints);
171157
setOutput("obstacle", calculateObstacle(waypoints));
172158
return BT::NodeStatus::RUNNING;

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

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -118,12 +118,6 @@ BT::NodeStatus StopAtTrafficLightAction::tick()
118118
} else {
119119
return BT::NodeStatus::FAILURE;
120120
}
121-
if (!distance_to_stop_target_) {
122-
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(0));
123-
setOutput("waypoints", waypoints);
124-
setOutput("obstacle", calculateObstacle(waypoints));
125-
return BT::NodeStatus::SUCCESS;
126-
}
127121
if (target_speed_) {
128122
if (target_speed_.value() > target_linear_speed.value()) {
129123
target_speed_ = target_linear_speed.value();

simulation/behavior_tree_plugin/src/vehicle/lane_change_action.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -171,6 +171,9 @@ BT::NodeStatus LaneChangeAction::tick()
171171
lane_change_velocity_ = curve_->getLength() / lane_change_parameters_->constraint.value;
172172
break;
173173
}
174+
if (target_speed_) {
175+
lane_change_velocity_ = std::clamp(lane_change_velocity_, 0.0, target_speed_.value());
176+
}
174177
} else {
175178
return BT::NodeStatus::FAILURE;
176179
}

0 commit comments

Comments
 (0)