Skip to content

Refactor/behavior tree 2 #1606

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 12 commits into from
May 27, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,9 @@ class FollowFrontEntityAction : public entity_behavior::VehicleActionNode

private:
std::optional<double> distance_to_front_entity_;
static constexpr double waypoint_interval = 1.0;
static constexpr double front_entity_margin = 5.0;
static constexpr double speed_step = 2.0;
};
} // namespace follow_lane_sequence
} // namespace vehicle
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,11 @@ class FollowLaneAction : public entity_behavior::VehicleActionNode

private:
std::optional<traffic_simulator::LaneletPose> target_lanelet_pose_;
static constexpr double waypoint_interval = 1.0;
static constexpr double front_entity_stop_margin = 5.0;
static constexpr double bounding_box_half_factor = 0.5;
static constexpr double stop_line_margin = 5.0;
static constexpr double conflicting_entity_margin = 3.0;
};
} // namespace follow_lane_sequence
} // namespace vehicle
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@ class StopAtCrossingEntityAction : public entity_behavior::VehicleActionNode

private:
std::optional<double> distance_to_stop_target_;
bool in_stop_sequence_;
};
} // namespace follow_lane_sequence
} // namespace vehicle
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,12 @@ class StopAtStopLineAction : public entity_behavior::VehicleActionNode
const traffic_simulator_msgs::msg::WaypointsArray & waypoints) override;

private:
bool stopped_;
std::optional<double> distance_to_stopline_;
static constexpr double waypoint_interval = 1.0;
static constexpr double bounding_box_half_factor = 0.5;
static constexpr double stop_margin = 1.0;
static constexpr double front_stopline_margin = 5.0;
static constexpr double velocity_epsilon = 0.001;
};
} // namespace follow_lane_sequence
} // namespace vehicle
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ const traffic_simulator_msgs::msg::WaypointsArray FollowFrontEntityAction::calcu
double horizon = getHorizon();
const auto lanelet_pose = canonicalized_entity_status_->getLaneletPose();
waypoints.waypoints = reference_trajectory->getTrajectory(
lanelet_pose.s, lanelet_pose.s + horizon, 1.0, lanelet_pose.offset);
lanelet_pose.s, lanelet_pose.s + horizon, waypoint_interval, lanelet_pose.offset);
trajectory = std::make_unique<math::geometry::CatmullRomSubspline>(
reference_trajectory, lanelet_pose.s, lanelet_pose.s + horizon);
return waypoints;
Expand Down Expand Up @@ -127,15 +127,17 @@ BT::NodeStatus FollowFrontEntityAction::tick()
if (
distance_to_front_entity_.value() >=
(calculateStopDistance(behavior_parameter_.dynamic_constraints) +
vehicle_parameters.bounding_box.dimensions.x + 5)) {
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(front_entity_linear_velocity + 2));
vehicle_parameters.bounding_box.dimensions.x + front_entity_margin)) {
setCanonicalizedEntityStatus(
calculateUpdatedEntityStatus(front_entity_linear_velocity + speed_step));
setOutput("waypoints", waypoints);
setOutput("obstacle", calculateObstacle(waypoints));
return BT::NodeStatus::RUNNING;
} else if (
distance_to_front_entity_.value() <=
calculateStopDistance(behavior_parameter_.dynamic_constraints)) {
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(front_entity_linear_velocity - 2));
setCanonicalizedEntityStatus(
calculateUpdatedEntityStatus(front_entity_linear_velocity - speed_step));
setOutput("waypoints", waypoints);
setOutput("obstacle", calculateObstacle(waypoints));
return BT::NodeStatus::RUNNING;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ const traffic_simulator_msgs::msg::WaypointsArray FollowLaneAction::calculateWay
traffic_simulator_msgs::msg::WaypointsArray waypoints;
const auto lanelet_pose = canonicalized_entity_status_->getLaneletPose();
waypoints.waypoints = reference_trajectory->getTrajectory(
lanelet_pose.s, lanelet_pose.s + getHorizon(), 1.0, lanelet_pose.offset);
lanelet_pose.s, lanelet_pose.s + getHorizon(), waypoint_interval, lanelet_pose.offset);
trajectory = std::make_unique<math::geometry::CatmullRomSubspline>(
reference_trajectory, lanelet_pose.s, lanelet_pose.s + getHorizon());
return waypoints;
Expand Down Expand Up @@ -97,7 +97,7 @@ BT::NodeStatus FollowLaneAction::tick()
if (
distance_to_front_entity.value() <=
calculateStopDistance(behavior_parameter_.dynamic_constraints) +
vehicle_parameters.bounding_box.dimensions.x + 5) {
vehicle_parameters.bounding_box.dimensions.x + front_entity_stop_margin) {
return BT::NodeStatus::FAILURE;
}
}
Expand All @@ -116,14 +116,15 @@ BT::NodeStatus FollowLaneAction::tick()
if (
distance_to_stopline.value() <=
calculateStopDistance(behavior_parameter_.dynamic_constraints) +
vehicle_parameters.bounding_box.dimensions.x * 0.5 + 5) {
vehicle_parameters.bounding_box.dimensions.x * bounding_box_half_factor +
stop_line_margin) {
return BT::NodeStatus::FAILURE;
}
}
if (distance_to_conflicting_entity) {
if (
distance_to_conflicting_entity.value() <
(vehicle_parameters.bounding_box.dimensions.x + 3 +
(vehicle_parameters.bounding_box.dimensions.x + conflicting_entity_margin +
calculateStopDistance(behavior_parameter_.dynamic_constraints))) {
return BT::NodeStatus::FAILURE;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@ StopAtCrossingEntityAction::StopAtCrossingEntityAction(
const std::string & name, const BT::NodeConfiguration & config)
: entity_behavior::VehicleActionNode(name, config)
{
in_stop_sequence_ = false;
}

const std::optional<traffic_simulator_msgs::msg::Obstacle>
Expand Down Expand Up @@ -89,19 +88,15 @@ BT::NodeStatus StopAtCrossingEntityAction::tick()
if (
request_ != traffic_simulator::behavior::Request::NONE &&
request_ != traffic_simulator::behavior::Request::FOLLOW_LANE) {
in_stop_sequence_ = false;
return BT::NodeStatus::FAILURE;
}
if (!canonicalized_entity_status_->isInLanelet()) {
in_stop_sequence_ = false;
return BT::NodeStatus::FAILURE;
}
if (!behavior_parameter_.see_around) {
in_stop_sequence_ = false;
return BT::NodeStatus::FAILURE;
}
if (getRightOfWayEntities(route_lanelets_).size() != 0) {
in_stop_sequence_ = false;
return BT::NodeStatus::FAILURE;
}
const auto waypoints = calculateWaypoints();
Expand All @@ -111,39 +106,26 @@ BT::NodeStatus StopAtCrossingEntityAction::tick()
if (trajectory == nullptr) {
return BT::NodeStatus::FAILURE;
}
distance_to_stop_target_ = getDistanceToConflictingEntity(route_lanelets_, *trajectory);
std::optional<double> target_linear_speed;
auto distance_to_stopline =
traffic_simulator::distance::distanceToStopLine(route_lanelets_, *trajectory);
const auto distance_to_front_entity = getDistanceToFrontEntity(*trajectory);
if (!distance_to_stop_target_) {
in_stop_sequence_ = false;
distance_to_stop_target_ = getDistanceToConflictingEntity(route_lanelets_, *trajectory);
if (distance_to_stop_target_) {
target_linear_speed = calculateTargetSpeed(canonicalized_entity_status_->getTwist().linear.x);
} else {
return BT::NodeStatus::FAILURE;
}
if (distance_to_front_entity) {
if (distance_to_front_entity.value() <= distance_to_stop_target_.value()) {
in_stop_sequence_ = false;
return BT::NodeStatus::FAILURE;
}
}
if (distance_to_stopline) {
if (distance_to_stopline.value() <= distance_to_stop_target_.value()) {
in_stop_sequence_ = false;
return BT::NodeStatus::FAILURE;
}
}
std::optional<double> target_linear_speed;
if (distance_to_stop_target_) {
target_linear_speed = calculateTargetSpeed(canonicalized_entity_status_->getTwist().linear.x);
} else {
target_linear_speed = std::nullopt;
}
if (!distance_to_stop_target_) {
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(0));
setOutput("waypoints", waypoints);
setOutput("obstacle", calculateObstacle(waypoints));
in_stop_sequence_ = false;
return BT::NodeStatus::SUCCESS;
}
if (target_speed_) {
if (target_speed_.value() > target_linear_speed.value()) {
target_speed_ = target_linear_speed.value();
Expand All @@ -154,7 +136,6 @@ BT::NodeStatus StopAtCrossingEntityAction::tick()
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed_.value()));
setOutput("waypoints", waypoints);
setOutput("obstacle", calculateObstacle(waypoints));
in_stop_sequence_ = true;
return BT::NodeStatus::RUNNING;
}
} // namespace follow_lane_sequence
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@ StopAtStopLineAction::StopAtStopLineAction(
const std::string & name, const BT::NodeConfiguration & config)
: entity_behavior::VehicleActionNode(name, config)
{
stopped_ = false;
}

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

const traffic_simulator_msgs::msg::WaypointsArray StopAtStopLineAction::calculateWaypoints()
{
if (!canonicalized_entity_status_->isInLanelet()) {
THROW_SIMULATION_ERROR("failed to assign lane");
}
if (canonicalized_entity_status_->getTwist().linear.x >= 0) {
traffic_simulator_msgs::msg::WaypointsArray waypoints;
double horizon = getHorizon();
const auto lanelet_pose = canonicalized_entity_status_->getLaneletPose();
waypoints.waypoints = reference_trajectory->getTrajectory(
lanelet_pose.s, lanelet_pose.s + horizon, 1.0, lanelet_pose.offset);
lanelet_pose.s, lanelet_pose.s + horizon, waypoint_interval, lanelet_pose.offset);
trajectory = std::make_unique<math::geometry::CatmullRomSubspline>(
reference_trajectory, lanelet_pose.s, lanelet_pose.s + horizon);
return waypoints;
Expand All @@ -79,7 +75,8 @@ std::optional<double> StopAtStopLineAction::calculateTargetSpeed(double current_
* @brief hard coded parameter!! 1.0 is a stop margin
*/
double rest_distance =
distance_to_stopline_.value() - (vehicle_parameters.bounding_box.dimensions.x * 0.5 + 1.0);
distance_to_stopline_.value() -
(vehicle_parameters.bounding_box.dimensions.x * bounding_box_half_factor + stop_margin);
if (rest_distance < calculateStopDistance(behavior_parameter_.dynamic_constraints)) {
return 0;
}
Expand All @@ -92,7 +89,6 @@ BT::NodeStatus StopAtStopLineAction::tick()
if (
request_ != traffic_simulator::behavior::Request::NONE &&
request_ != traffic_simulator::behavior::Request::FOLLOW_LANE) {
stopped_ = false;
return BT::NodeStatus::FAILURE;
}
if (!behavior_parameter_.see_around) {
Expand All @@ -101,6 +97,9 @@ BT::NodeStatus StopAtStopLineAction::tick()
if (getRightOfWayEntities(route_lanelets_).size() != 0) {
return BT::NodeStatus::FAILURE;
}
if (!canonicalized_entity_status_->isInLanelet()) {
return BT::NodeStatus::FAILURE;
}
const auto waypoints = calculateWaypoints();
if (waypoints.waypoints.empty()) {
return BT::NodeStatus::FAILURE;
Expand All @@ -113,49 +112,37 @@ BT::NodeStatus StopAtStopLineAction::tick()
const auto distance_to_stop_target = getDistanceToConflictingEntity(route_lanelets_, *trajectory);
const auto distance_to_front_entity = getDistanceToFrontEntity(*trajectory);
if (!distance_to_stopline_) {
stopped_ = false;
return BT::NodeStatus::FAILURE;
}
if (distance_to_front_entity) {
if (distance_to_front_entity.value() <= distance_to_stopline_.value()) {
stopped_ = false;
return BT::NodeStatus::FAILURE;
}
}
if (distance_to_stop_target) {
if (distance_to_stop_target.value() <= distance_to_stopline_.value()) {
stopped_ = false;
return BT::NodeStatus::FAILURE;
}
}

if (std::fabs(canonicalized_entity_status_->getTwist().linear.x) < 0.001) {
if (std::fabs(canonicalized_entity_status_->getTwist().linear.x) < velocity_epsilon) {
if (distance_to_stopline_) {
if (distance_to_stopline_.value() <= vehicle_parameters.bounding_box.dimensions.x + 5) {
stopped_ = true;
if (
distance_to_stopline_.value() <=
vehicle_parameters.bounding_box.dimensions.x + front_stopline_margin) {
if (!target_speed_) {
target_speed_ = hdmap_utils_->getSpeedLimit(route_lanelets_);
}
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed_.value()));
setOutput("waypoints", waypoints);
setOutput("obstacle", calculateObstacle(waypoints));
return BT::NodeStatus::RUNNING;
}
}
}
if (stopped_) {
if (!target_speed_) {
target_speed_ = hdmap_utils_->getSpeedLimit(route_lanelets_);
}
if (!distance_to_stopline_) {
stopped_ = false;
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed_.value()));
setOutput("waypoints", waypoints);
setOutput("obstacle", calculateObstacle(waypoints));
return BT::NodeStatus::SUCCESS;
}
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed_.value()));
setOutput("waypoints", waypoints);
setOutput("obstacle", calculateObstacle(waypoints));
return BT::NodeStatus::RUNNING;
}
auto target_linear_speed =
calculateTargetSpeed(canonicalized_entity_status_->getTwist().linear.x);
if (!target_linear_speed) {
stopped_ = false;
return BT::NodeStatus::FAILURE;
}
if (target_speed_) {
Expand All @@ -166,7 +153,6 @@ BT::NodeStatus StopAtStopLineAction::tick()
target_speed_ = target_linear_speed.value();
}
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(target_speed_.value()));
stopped_ = false;
setOutput("waypoints", waypoints);
setOutput("obstacle", calculateObstacle(waypoints));
return BT::NodeStatus::RUNNING;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -118,12 +118,6 @@ BT::NodeStatus StopAtTrafficLightAction::tick()
} else {
return BT::NodeStatus::FAILURE;
}
if (!distance_to_stop_target_) {
setCanonicalizedEntityStatus(calculateUpdatedEntityStatus(0));
setOutput("waypoints", waypoints);
setOutput("obstacle", calculateObstacle(waypoints));
return BT::NodeStatus::SUCCESS;
}
if (target_speed_) {
if (target_speed_.value() > target_linear_speed.value()) {
target_speed_ = target_linear_speed.value();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -171,6 +171,9 @@ BT::NodeStatus LaneChangeAction::tick()
lane_change_velocity_ = curve_->getLength() / lane_change_parameters_->constraint.value;
break;
}
if (target_speed_) {
lane_change_velocity_ = std::clamp(lane_change_velocity_, 0.0, target_speed_.value());
}
} else {
return BT::NodeStatus::FAILURE;
}
Expand Down
Loading