Skip to content

Commit

Permalink
Update EgoEntity to have FieldOperatorApplication as its base class
Browse files Browse the repository at this point in the history
Signed-off-by: yamacir-kit <[email protected]>
  • Loading branch information
yamacir-kit committed Dec 19, 2024
1 parent 2f5f1b0 commit fddce82
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,8 @@ namespace traffic_simulator
{
namespace entity
{
class EgoEntity : public VehicleEntity
class EgoEntity : public VehicleEntity, public concealer::FieldOperatorApplication
{
concealer::FieldOperatorApplication field_operator_application;

bool is_controlled_by_simulator_{false};
std::optional<double> target_speed_;
traffic_simulator_msgs::msg::BehaviorParameter behavior_parameter_;
Expand Down
31 changes: 15 additions & 16 deletions simulation/traffic_simulator/src/entity/ego_entity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,7 @@ EgoEntity::EgoEntity(
const traffic_simulator_msgs::msg::VehicleParameters & parameters,
const Configuration & configuration,
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters)
: VehicleEntity(name, entity_status, hdmap_utils_ptr, parameters),
field_operator_application([&]() {
: VehicleEntity(name, entity_status, hdmap_utils_ptr, parameters), FieldOperatorApplication([&]() {
if (const auto architecture_type =
getParameter<std::string>(node_parameters, "architecture_type", "awf/universe/20240605");
architecture_type.find("awf/universe") != std::string::npos) {
Expand Down Expand Up @@ -75,12 +74,12 @@ EgoEntity::EgoEntity(

auto EgoEntity::asFieldOperatorApplication() -> concealer::FieldOperatorApplication &
{
return field_operator_application;
return *this;
}

auto EgoEntity::getCurrentAction() const -> std::string
{
const auto state = field_operator_application.getAutowareStateName();
const auto state = getAutowareStateName();
return state.empty() ? "Launching" : state;
}

Expand All @@ -107,7 +106,7 @@ auto EgoEntity::getRouteLanelets(double /*unused horizon*/) -> lanelet::Ids
{
lanelet::Ids ids{};

for (const auto & point : field_operator_application.getPathWithLaneId().points) {
for (const auto & point : getPathWithLaneId().points) {
ids += point.lane_ids;
}

Expand All @@ -121,13 +120,13 @@ auto EgoEntity::getCurrentPose() const -> const geometry_msgs::msg::Pose &

auto EgoEntity::getWaypoints() -> const traffic_simulator_msgs::msg::WaypointsArray
{
return field_operator_application.getWaypoints();
return FieldOperatorApplication::getWaypoints();
}

void EgoEntity::updateFieldOperatorApplication()
{
field_operator_application.rethrow();
field_operator_application.spinSome();
rethrow();
spinSome();
}

void EgoEntity::onUpdate(double current_time, double step_time)
Expand All @@ -145,7 +144,7 @@ void EgoEntity::onUpdate(double current_time, double step_time)
// prefer current lanelet on ss2 side
setStatus(non_canonicalized_updated_status.value(), status_->getLaneletIds());
} else {
field_operator_application.enableAutowareControl();
enableAutowareControl();
is_controlled_by_simulator_ = false;
}
}
Expand Down Expand Up @@ -192,13 +191,13 @@ void EgoEntity::requestAssignRoute(const std::vector<geometry_msgs::msg::Pose> &
route.push_back(pose_stamped);
}

if (not field_operator_application.initialized()) {
field_operator_application.initialize(getMapPose());
field_operator_application.plan(route);
if (not initialized()) {
initialize(getMapPose());
plan(route);
// NOTE: engage() will be executed at simulation-time 0.
} else {
field_operator_application.plan(route);
field_operator_application.engage();
plan(route);
engage();
}
}

Expand Down Expand Up @@ -244,7 +243,7 @@ auto EgoEntity::requestSpeedChange(
"purposes only.");
}

void EgoEntity::requestClearRoute() { field_operator_application.clearRoute(); }
void EgoEntity::requestClearRoute() { clearRoute(); }

auto EgoEntity::getDefaultDynamicConstraints() const
-> const traffic_simulator_msgs::msg::DynamicConstraints &
Expand Down Expand Up @@ -278,7 +277,7 @@ auto EgoEntity::requestSpeedChange(
auto EgoEntity::setVelocityLimit(double value) -> void //
{
behavior_parameter_.dynamic_constraints.max_speed = value;
field_operator_application.setVelocityLimit(value);
FieldOperatorApplication::setVelocityLimit(value);
}

auto EgoEntity::setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void
Expand Down

0 comments on commit fddce82

Please sign in to comment.