Skip to content
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

RJD-1057 (3/5): Remove non-API member functions: EntityManager’s member functions forwarded to EntityBase (1/2) #1473

Merged

Conversation

dmoszynski
Copy link
Contributor

@dmoszynski dmoszynski commented Dec 4, 2024

Description

Abstract

This pull request introduces the change of exposing direct access to Entity objects through the API. This change increases flexibility of using the API and removes the need to have many forwarding functions to Entities member functions.

Background

This pull request is one of many that aim to modularize the scenario_simulator_v2.

The main goal of this PR was to remove numerous member functions of EntityManager (and subsequently some of API too) that forwarded calls to Entities member functions:

#define FORWARD_TO_ENTITY(IDENTIFIER, ...) \
/*! \
@brief Forward to arguments to the EntityBase::IDENTIFIER function. \
@return return value of the EntityBase::IDENTIFIER function. \
@note This function was defined by FORWARD_TO_ENTITY macro.         \
*/ \
template <typename... Ts> \
decltype(auto) IDENTIFIER(const std::string & name, Ts &&... xs) __VA_ARGS__ \
try { \
return entities_.at(name)->IDENTIFIER(std::forward<decltype(xs)>(xs)...); \
} catch (const std::out_of_range &) { \
THROW_SEMANTIC_ERROR("entity : ", name, "does not exist"); \
} \
static_assert(true, "")
// clang-format on
FORWARD_TO_ENTITY(activateOutOfRangeJob, );
FORWARD_TO_ENTITY(asFieldOperatorApplication, const);
FORWARD_TO_ENTITY(cancelRequest, );
FORWARD_TO_ENTITY(get2DPolygon, const);
FORWARD_TO_ENTITY(getBehaviorParameter, const);
FORWARD_TO_ENTITY(getBoundingBox, const);
FORWARD_TO_ENTITY(getCanonicalizedStatusBeforeUpdate, const);
FORWARD_TO_ENTITY(getCurrentAccel, const);
FORWARD_TO_ENTITY(getCurrentTwist, const);
FORWARD_TO_ENTITY(getDefaultMatchingDistanceForLaneletPoseCalculation, const);
FORWARD_TO_ENTITY(getEntityType, const);
FORWARD_TO_ENTITY(getEntityTypename, const);
FORWARD_TO_ENTITY(getLinearJerk, const);
FORWARD_TO_ENTITY(getRouteLanelets, const);
FORWARD_TO_ENTITY(getStandStillDuration, const);
FORWARD_TO_ENTITY(getTraveledDistance, const);
FORWARD_TO_ENTITY(isControlledBySimulator, );
FORWARD_TO_ENTITY(laneMatchingSucceed, const);
FORWARD_TO_ENTITY(reachPosition, const);
FORWARD_TO_ENTITY(requestAcquirePosition, );
FORWARD_TO_ENTITY(requestAssignRoute, );
FORWARD_TO_ENTITY(requestClearRoute, );
FORWARD_TO_ENTITY(requestFollowTrajectory, );
FORWARD_TO_ENTITY(requestLaneChange, );
FORWARD_TO_ENTITY(requestSynchronize, );
FORWARD_TO_ENTITY(requestWalkStraight, );
FORWARD_TO_ENTITY(setAcceleration, );
FORWARD_TO_ENTITY(setAccelerationLimit, );
FORWARD_TO_ENTITY(setAccelerationRateLimit, );
FORWARD_TO_ENTITY(setBehaviorParameter, );
FORWARD_TO_ENTITY(setControlledBySimulator, );
FORWARD_TO_ENTITY(setDecelerationLimit, );
FORWARD_TO_ENTITY(setDecelerationRateLimit, );
FORWARD_TO_ENTITY(setLinearJerk, );
FORWARD_TO_ENTITY(setLinearVelocity, );
FORWARD_TO_ENTITY(setMapPose, );
FORWARD_TO_ENTITY(setTwist, );
FORWARD_TO_ENTITY(setVelocityLimit, );
FORWARD_TO_ENTITY(requestSpeedChange, );

This has largely been achieved by exposing direct access to Entity and its member functions through the API::getEntity function:

auto getEntity(const std::string & name) const -> std::shared_ptr<entity::EntityBase>;

The following change was to adjust all cpp mock scenarios to use the new interface.
This is the main reason why this PR is so large - all mock scenarios had to be corrected.

Scenarios using the new interface have been changed similarly to the example below.
Before:

void onUpdate() override
{
if (api_.isInLanelet("ego", 34408, 0.1)) {
stop(cpp_mock_scenarios::Result::SUCCESS);
}
}
void onInitialize() override
{
api_.spawn(
"ego",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 10.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
api_.setEntityStatus(
"ego",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34513, 0.0, 0.0, api_.getHdmapUtils()),
traffic_simulator::helper::constructActionStatus(10));
api_.requestSpeedChange("ego", 10, true);
const geometry_msgs::msg::Pose goal_pose = traffic_simulator::pose::toMapPose(
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34408, 1.0, 0.0, api_.getHdmapUtils()));
api_.requestAcquirePosition("ego", goal_pose);
}

After:
void onUpdate() override
{
if (api_.getEntity("ego")->isInLanelet(34408, 0.1)) {
stop(cpp_mock_scenarios::Result::SUCCESS);
}
}
void onInitialize() override
{
api_.spawn(
"ego",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 10.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
auto entity = api_.getEntity("ego");
entity->setStatus(
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34513, 0.0, 0.0, api_.getHdmapUtils()),
traffic_simulator::helper::constructActionStatus(10));
entity->requestSpeedChange(10, true);
const geometry_msgs::msg::Pose goal_pose = traffic_simulator::pose::toMapPose(
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34408, 1.0, 0.0, api_.getHdmapUtils()));
entity->requestAcquirePosition(goal_pose);
}

Similar changes had to be applied to the whole codebase relying on the API like simulator_core.hpp.

What is more, EgoEntity has been modified in such a way, that the function

auto asFieldOperatorApplication() const -> concealer::FieldOperatorApplication & override;

has been replaced with a set of other functions below:
auto engage() -> void;
auto isEngaged() const -> bool;
auto isEngageable() const -> bool;
auto replanRoute(const std::vector<geometry_msgs::msg::PoseStamped> & route) -> void;
auto sendCooperateCommand(const std::string & module_name, const std::string & command) -> void;
auto requestAutoModeForCooperation(const std::string & module_name, bool enable) -> void;
auto getMinimumRiskManeuverBehaviorName() const -> std::string;
auto getMinimumRiskManeuverStateName() const -> std::string;
auto getEmergencyStateName() const -> std::string;
auto getTurnIndicatorsCommandName() const -> const std::string;

This change simplifies the interface of calling Ego specific actions like engage or sendCooperateCommand.

Details

Below are the detailed interface changes that have been made to EntityStatus, EntityBase, EntityManager and the API.

EntityStatus

  • Renamed laneMatchingSucceed to isInLanelet:
    auto laneMatchingSucceed() const noexcept -> bool;
    ->
    auto isInLanelet() const noexcept -> bool;

EntityBase

  • Removed forwarded using macro to EntityStatus: laneMatchingSucceed:
    laneMatchingSucceed

  • Removed asFieldOperatorApplication, reachPosition and requestClearRoute:
    auto asFieldOperatorApplication() const -> concealer::FieldOperatorApplication &;
    bool reachPosition(const geometry_msgs::msg::Pose & target_pose, const double tolerance) const;
    bool reachPosition(const CanonicalizedLaneletPose & lanelet_pose, const double tolerance) const;
    bool reachPosition(const std::string & target_name, const double tolerance) const;
    void requestClearRoute();

  • Added: isStopped, isInPosition and isInLanelet.

auto isStopped() const -> bool;

auto isInPosition(const geometry_msgs::msg::Pose & pose, const double tolerance) const -> bool;
auto isInPosition(const CanonicalizedLaneletPose & lanelet_pose, const double tolerance) const -> bool;

auto isInLanelet() const -> bool;
auto isInLanelet(const lanelet::Id lanelet_id, std::optional<double> tolerance = std::nullopt) const -> bool;

Note: Maybe it's a good idea to provide that tolerance is always of type std::optional<double>?

EgoEntity

  • Removed asFieldOperatorApplication:
    auto asFieldOperatorApplication() const -> concealer::FieldOperatorApplication & override;

FieldOperatorApplicationFor

  • Added visibility to members of FieldOperatorApplication (see this comment).
  • EgoEntity now exposes these inherited members as a replacement of previous asFieldOperatorApplication:
auto isStopRequested() const -> bool;
auto isEngageable() const -> bool;
auto isEngaged() const -> bool;
auto engage() -> void;
auto sendCooperateCommand(const std::string & module_name, const std::string & command) -> void;
auto getAutowareStateName() const -> const std::string &;
auto getEmergencyStateName() const -> const std::string &;
auto getMinimumRiskManeuverBehaviorName() const -> const std::string &;
auto getMinimumRiskManeuverStateName() const -> const std::string &;
auto getTurnIndicatorsCommandName() const -> std::string;
auto requestAutoModeForCooperation(const std::string & module_name, const bool enable) -> void;
auto getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray;

EntityManager

  • Removed forwarded using macro to EntityBase: activateOutOfRangeJob, asFieldOperatorApplication, cancelRequest, get2DPolygon, getBehaviorParameter, getBoundingBox, getCanonicalizedStatusBeforeUpdate, getCurrentAccel, getCurrentTwist, getDefaultMatchingDistanceForLaneletPoseCalculation, getEntityType, getEntityTypename, getLinearJerk, getRouteLanelets, getStandStillDuration, getTraveledDistance, isControlledBySimulator, laneMatchingSucceed, reachPosition, requestAcquirePosition, requestAssignRoute, requestClearRoute, requestFollowTrajectory, requestLaneChange, requestSpeedChange, requestSynchronize, requestWalkStraight, setAcceleration, setAccelerationLimit, setAccelerationRateLimit, setBehaviorParameter, setControlledBySimulator, setDecelerationLimit, setDecelerationRateLimit, setLinearJerk, setLinearVelocity, setMapPose, setTwist, setVelocityLimit:
    FORWARD_TO_ENTITY(activateOutOfRangeJob);,
    FORWARD_TO_ENTITY(asFieldOperatorApplication);,
    FORWARD_TO_ENTITY(cancelRequest);,
    FORWARD_TO_ENTITY(get2DPolygon);,
    FORWARD_TO_ENTITY(getBehaviorParameter);,
    FORWARD_TO_ENTITY(getBoundingBox);,
    FORWARD_TO_ENTITY(getCanonicalizedStatusBeforeUpdate);,
    FORWARD_TO_ENTITY(getCurrentAccel);,
    FORWARD_TO_ENTITY(getCurrentTwist);,
    FORWARD_TO_ENTITY(getDefaultMatchingDistanceForLaneletPoseCalculation);,
    FORWARD_TO_ENTITY(getEntityType);,
    FORWARD_TO_ENTITY(getEntityTypename);,
    FORWARD_TO_ENTITY(getLinearJerk);,
    FORWARD_TO_ENTITY(getRouteLanelets);,
    FORWARD_TO_ENTITY(getStandStillDuration);,
    FORWARD_TO_ENTITY(getTraveledDistance);,
    FORWARD_TO_ENTITY(isControlledBySimulator);,
    FORWARD_TO_ENTITY(laneMatchingSucceed);,
    FORWARD_TO_ENTITY(reachPosition);,
    FORWARD_TO_ENTITY(requestAcquirePosition);,
    FORWARD_TO_ENTITY(requestAssignRoute);,
    FORWARD_TO_ENTITY(requestClearRoute);,
    FORWARD_TO_ENTITY(requestFollowTrajectory);,
    FORWARD_TO_ENTITY(requestLaneChange);,
    FORWARD_TO_ENTITY(requestSpeedChange);,
    FORWARD_TO_ENTITY(requestSynchronize);,
    FORWARD_TO_ENTITY(requestWalkStraight);,
    FORWARD_TO_ENTITY(setAcceleration);,
    FORWARD_TO_ENTITY(setAccelerationLimit);,
    FORWARD_TO_ENTITY(setAccelerationRateLimit);,
    FORWARD_TO_ENTITY(setBehaviorParameter);,
    FORWARD_TO_ENTITY(setControlledBySimulator);,
    FORWARD_TO_ENTITY(setDecelerationLimit);,
    FORWARD_TO_ENTITY(setDecelerationRateLimit);,
    FORWARD_TO_ENTITY(setLinearJerk);,
    FORWARD_TO_ENTITY(setLinearVelocity);,
    FORWARD_TO_ENTITY(setMapPose);,
    FORWARD_TO_ENTITY(setTwist);,
    FORWARD_TO_ENTITY(setVelocityLimit);

  • Removed is, isStopping, isInLanelet, checkCollision, getEntityStatus, getCurrentAction:
    bool is(const std::string & name) const;
    bool isStopping(const std::string & name) const;
    bool isInLanelet(const std::string & name, const lanelet::Id lanelet_id, const double tolerance);
    bool checkCollision(const std::string & first_entity_name, const std::string & second_entity_name);
    auto getEntityStatus(const std::string & name) const -> const CanonicalizedEntityStatus &;
    auto getCurrentAction(const std::string & name) const -> std::string;

  • Renamed entityExists to isEntitySpawned
    auto entityExists(const std::string & name) -> bool;
    ->
    auto isEntitySpawned(const std::string & name) -> bool;

  • Renamed getEntity to getEntityOrNullptr (which does not throw an exception but returns nullptr)
    auto getEntity(const std::string & name) const -> std::shared_ptr<entity::EntityBase>;
    ->
    auto getEntityOrNullptr(const std::string & name) const -> std::shared_ptr<entity::EntityBase>;

  • Renamed isEgoSpawned to isAnyEgoSpawned:
    auto isEgoSpawned() const -> bool;
    ->
    auto isAnyEgoSpawned() const -> bool;

  • Added getEntity (which throws an exception).

auto getEntity(const std::string & name) const -> std::shared_ptr<entity::EntityBase>;
  • Added getEgoEntity:
auto getEgoEntity(const std::string & name) const -> std::shared_ptr<entity::EgoEntity>;
auto getEgoEntity() const -> std::shared_ptr<entity::EgoEntity>;

API

  • Removed forwarded using macro to EntityManager: activateOutOfRangeJob, asFieldOperatorApplication, cancelRequest, checkCollision, entityExists, getBehaviorParameter, getBoundingBox, getCanonicalizedStatusBeforeUpdate, getCurrentAccel, getCurrentAction, getCurrentTwist, getDefaultMatchingDistanceForLaneletPoseCalculation, getEgoName, getEntityNames, getEntityStatus, getLinearJerk, getStandStillDuration, getTraveledDistance, isEgoSpawned, isInLanelet, laneMatchingSucceed, reachPosition, requestAcquirePosition, requestAssignRoute, requestClearRoute, requestFollowTrajectory, requestSpeedChange, requestSynchronize, requestWalkStraight, setAcceleration, setAccelerationLimit, setAccelerationRateLimit, setBehaviorParameter, setDecelerationLimit, setDecelerationRateLimit, setLinearVelocity, setMapPose, setTwist, setVelocityLimit:
    FORWARD_TO_ENTITY_MANAGER(activateOutOfRangeJob);,
    FORWARD_TO_ENTITY_MANAGER(asFieldOperatorApplication);,
    FORWARD_TO_ENTITY_MANAGER(cancelRequest);,
    FORWARD_TO_ENTITY_MANAGER(checkCollision);,
    FORWARD_TO_ENTITY_MANAGER(entityExists);,
    FORWARD_TO_ENTITY_MANAGER(getBehaviorParameter);,
    FORWARD_TO_ENTITY_MANAGER(getBoundingBox);,
    FORWARD_TO_ENTITY_MANAGER(getCanonicalizedStatusBeforeUpdate);,
    FORWARD_TO_ENTITY_MANAGER(getCurrentAccel);,
    FORWARD_TO_ENTITY_MANAGER(getCurrentAction);,
    FORWARD_TO_ENTITY_MANAGER(getCurrentTwist);,
    FORWARD_TO_ENTITY_MANAGER(getDefaultMatchingDistanceForLaneletPoseCalculation);,
    FORWARD_TO_ENTITY_MANAGER(getEgoName);,
    FORWARD_TO_ENTITY_MANAGER(getEntityNames);,
    FORWARD_TO_ENTITY_MANAGER(getEntityStatus);,
    FORWARD_TO_ENTITY_MANAGER(getLinearJerk);,
    FORWARD_TO_ENTITY_MANAGER(getStandStillDuration);,
    FORWARD_TO_ENTITY_MANAGER(getTraveledDistance);,
    FORWARD_TO_ENTITY_MANAGER(isEgoSpawned);,
    FORWARD_TO_ENTITY_MANAGER(isInLanelet);,
    FORWARD_TO_ENTITY_MANAGER(laneMatchingSucceed);,
    FORWARD_TO_ENTITY_MANAGER(reachPosition);,
    FORWARD_TO_ENTITY_MANAGER(requestAcquirePosition);,
    FORWARD_TO_ENTITY_MANAGER(requestAssignRoute);,
    FORWARD_TO_ENTITY_MANAGER(requestClearRoute);,
    FORWARD_TO_ENTITY_MANAGER(requestFollowTrajectory);,
    FORWARD_TO_ENTITY_MANAGER(requestSpeedChange);,
    FORWARD_TO_ENTITY_MANAGER(requestSynchronize);,
    FORWARD_TO_ENTITY_MANAGER(requestWalkStraight);,
    FORWARD_TO_ENTITY_MANAGER(setAcceleration);,
    FORWARD_TO_ENTITY_MANAGER(setAccelerationLimit);,
    FORWARD_TO_ENTITY_MANAGER(setAccelerationRateLimit);,
    FORWARD_TO_ENTITY_MANAGER(setBehaviorParameter);,
    FORWARD_TO_ENTITY_MANAGER(setDecelerationLimit);,
    FORWARD_TO_ENTITY_MANAGER(setDecelerationRateLimit);,
    FORWARD_TO_ENTITY_MANAGER(setLinearVelocity);,
    FORWARD_TO_ENTITY_MANAGER(setMapPose);,
    FORWARD_TO_ENTITY_MANAGER(setTwist);,
    FORWARD_TO_ENTITY_MANAGER(setVelocityLimit);

  • Removed setEntityStatus, requestLaneChange and getTimeHeadway:
    auto setEntityStatus(...) -> void;
    void requestLaneChange(...);
    std::optional<double> getTimeHeadway(const std::string & from, const std::string & to);

  • Added checkCollision:

auto API::checkCollision(const std::string & first_entity_name, const std::string & second_entity_name); -> bool
  • Added forwarded using macro to EntityManager: isEntitySpawned, isAnyEgoSpawned, getEntityOrNullptr, getEgoEntity:
FORWARD_TO_ENTITY_MANAGER(isEntitySpawned);
FORWARD_TO_ENTITY_MANAGER(isAnyEgoSpawned);
FORWARD_TO_ENTITY_MANAGER(getEntityOrNullptr);
FORWARD_TO_ENTITY_MANAGER(getEgoEntity);

Examples of interface changes

Below are many examples of how to use the interface after the changes.

entityExists -> isEntitySpawned

api_.entityExists("bob")

->

api_.isEntitySpawned("bob")

is<>

entity_manager_ptr_->is<entity::EgoEntity>(entity_name)

->

auto entity = api_.getEntity(entity_name);   
entity->is<entity::EgoEntity>())

getEntity -> getEntityOrNullptr

if (const auto from_entity = core->getEntity(from_entity_name)) {...}

->

if (const auto from_entity = core->getEntityOrNullptr(from_entity_name)) {...}

reachPosition -> isInPosition

api_.reachPosition("npc",traffic_simulator::helper::constructLaneletPose(34579, 0.0), 5)

->

const auto entity = getEntity("npc");
entity->isInPosition(traffic_simulator::helper::constructLaneletPose(34579, 0.0), 5)

getCurrentAction

api_.getCurrentAction("pedestrian")

->

api_.getEntity("pedestrian")->getCurrentAction()

setEntityStatus -> setStatus

api_.setEntityStatus(
"ego",
  traffic_simulator::helper::constructCanonicalizedLaneletPose(
  34513, 0.0, 0.0, api_.getHdmapUtils()),
  traffic_simulator::helper::constructActionStatus(10));
  api_.requestSpeedChange("ego", 10, true);
  const geometry_msgs::msg::Pose goal_pose = traffic_simulator::pose::toMapPose(
  traffic_simulator::helper::constructCanonicalizedLaneletPose(
  34408, 1.0, 0.0, api_.getHdmapUtils()));
  api_.requestAcquirePosition("ego", goal_pose);

->

auto ego_entity = api_.getEntity("ego");
ego_entity->setStatus(
  traffic_simulator::helper::constructCanonicalizedLaneletPose(
  34513, 0.0, 0.0, api_.getHdmapUtils()),
  traffic_simulator::helper::constructActionStatus(10));
  ego_entity->requestSpeedChange(10, true);
  const geometry_msgs::msg::Pose goal_pose = traffic_simulator::pose::toMapPose(
  traffic_simulator::helper::constructCanonicalizedLaneletPose(
  34408, 1.0, 0.0, api_.getHdmapUtils()));
  ego_entity->requestAcquirePosition(goal_pose);

asFieldOperatorApplication -> replacements

while (!api_.asFieldOperatorApplication("ego").engaged()) {
    if (api_.asFieldOperatorApplication("ego").engageable()) {
      api_.asFieldOperatorApplication("ego").engage();
      }

->

auto ego_entity = api_.getEgoEntity("ego");    
while (!ego_entity->isEngaged()) {
    if (ego_entity->isEngageable()) {
      ego_entity->engage();
      }

setMapPose(name, entity_status.pose);
setTwist(name, entity_status.action_status.twist);
setAcceleration(name, entity_status.action_status.accel);
entity_manager_ptr_->asFieldOperatorApplication(name).clearRoute();
entity_manager_ptr_->asFieldOperatorApplication(name).plan({goal_pose});
entity_manager_ptr_->asFieldOperatorApplication(name).engage();

->

auto ego_entity = entity_manager_ptr_->getEgoEntity(name);
ego_entity->setMapPose(entity_status.pose);
ego_entity->setTwist(entity_status.action_status.twist);
ego_entity->setAcceleration(entity_status.action_status.accel);
ego_entity->requestReplanRoute({goal_pose});

Others

api_.setLinearVelocity("ego", 0.0);
api_.requestSpeedChange("ego", 15, true);
api_.setBehaviorParameter("ego", behavior_parameter);

->

auto ego_entity = api_.getEntity("ego");
ego_entity->setLinearVelocity(0.0);
ego_entity->requestSpeedChange(15, true)
ego_entity->setBehaviorParameter(behavior_parameter);

double ego_linear_acceleration = api_.getCurrentAccel("ego").linear.x;
double ego_linear_velocity = api_.getCurrentTwist("ego").linear.x;

->

double ego_linear_acceleration = api_.getEntity("ego")->getCurrentAccel().linear.x;
double ego_linear_velocity = api_.getEntity("ego")->getCurrentTwist().linear.x;

References

INTERNAL LINK1
INTERNAL LINK2

Destructive Changes

--

Known Limitations

--

TauTheLepton and others added 30 commits June 19, 2024 13:16
… exceptions were thrown

Signed-off-by: Mateusz Palczuk <[email protected]>
Signed-off-by: Mateusz Palczuk <[email protected]>
Signed-off-by: Mateusz Palczuk <[email protected]>
…p-time' into RJD-1057-remove-functions-forwarded-to-entity-base
…d' into RJD-1057-remove-functions-forwarded-to-entity-base
…tityBase, also some getters, left setVelocityLimit and setBehaviorParameter
…develop templated is() in EntityBase and use it, rename isEgoSpawned to isAnyEgoSpawned, refactor
…ng setBehaviorParameter and setVelocityLimit
…ng request*, move requestLaneChange to EntityBase
…n forwarding, set "waiting" as init action state in behavior_tree
…develop getEgoEntity and dedicated methods in EgoEntity
…o RJD-1057-remove-functions-forwarded-to-entity-base
…y in calc it directly in evaluateTimeHeadway
@TauTheLepton TauTheLepton self-assigned this Jan 9, 2025
@robomic
Copy link
Contributor

robomic commented Jan 14, 2025

Considering recent changes in #1497 to the relation (composition -> inheritance) of EgoEntity and FieldOperatorApplication, I have made several minor changes in the last commit:

  • Change visibility of FieldOperatorApplication inheritance in EgoEntity (private -> public)
  • Remove EgoEntity member functions that were only accessing private fields inherited from FieldOperatorApplication
  • Change visibility of FieldOperatorApplication members (previously everything was public)
  • Add necessary accessors in FieldOperatorApplication
    This shifts responsibility of accessing data members of FieldOperatorApplication from EgoEntity to FieldOperatorApplication

@robomic
Copy link
Contributor

robomic commented Jan 14, 2025

@hakuturu583 @yamacir-kit
Please let me know if regression tests can be initiated.
Thank you 🙇

@yamacir-kit
Copy link
Collaborator

@robomic

Sorry, but please revert all of your latest changes related to #1497. The current state of FieldOperatorApplication is intentional (including all members being public). The concealer is currently being refactored, but is purposely stopped midway to reduce the burden of resolving conflicts in RJD-1057. The changes you have made are the ones I did not dare to make..

I appreciate your attitude, but please do not add any more changes to this already huge pull request.


Reviewing a pull request with more than 1000 lines takes an excruciating amount of time. It takes a day just to get a rough understanding of the changes, and several more reads to be confident that merging the pull request will not cause any problems. The review burden grows exponentially, not linearly, with the number of lines of code. Making new code changes late in the review requires not only verifying the new changes, but also verifying whether the new changes affect existing or unchanged code, or vice versa.

Because scenario_simulator_v2 is a tool used directly for Autoware testing, the attitude of "aggressively changing the code and quickly resolving bugs as soon as they are found" is not allowed. Whatever the reality, it is important that it is "believed" that there are no bugs or regressions and that it will remain stable. This means that if Autoware fails a simulator test, a bug in scenario_simulator_v2 should not be the first suspect.

This is why we put so much effort into pull requests, and why we hate large diff increments.

@TauTheLepton
Copy link
Contributor

@yamacir-kit

@robomic has reverted all changes related to #1497 he made before. Furthermore, he has adjusted the code of this PR to correctly account for the changes from #1497 (see here).

We are sorry for the inconvenience and hope that this PR now meets all expectations 🙇‍♂️

@TauTheLepton
Copy link
Contributor

@yamacir-kit

Does the PR now meet all expectations? Can we proceed with the regression tests?

@hakuturu583
Copy link
Collaborator

This Pull request was conflicted by #1472

Copy link
Collaborator

@hakuturu583 hakuturu583 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM!

But, currently CI/CD is broken.
So, please wait the CI was fixed.

Copy link
Collaborator

@hakuturu583 hakuturu583 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry, I forgot.
This branch must be follow upstream.

@hakuturu583
Copy link
Collaborator

@dmoszynski friendly ping.

Copy link

@dmoszynski
Copy link
Contributor Author

dmoszynski commented Jan 28, 2025

@hakuturu583 @yamacir-kit Done 🙇
In my feelings, it would be a worthwhile to run the regressions again before the merge of this PR.
(the last ones were run some time ago before the changes from the reviews).

What do you think? 🙇

@hakuturu583
Copy link
Collaborator

In my feelings, it would be a worthwhile to run the regressions again before the merge of this PR.
(the last ones were run some time ago before the changes from the reviews).
What do you think? 🙇

@dmoszynski I will review source code. And after that, please run regression test.

Copy link
Collaborator

@hakuturu583 hakuturu583 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Code is LGTM.
Please run regression test.

@TauTheLepton
Copy link
Contributor

No regressions confirmed here

@hakuturu583 hakuturu583 merged commit 66fc948 into master Jan 30, 2025
15 checks passed
@github-actions github-actions bot deleted the RJD-1057-remove-functions-forwarded-to-entity-base-middle branch January 30, 2025 02:37
@HansRobo HansRobo restored the RJD-1057-remove-functions-forwarded-to-entity-base-middle branch January 30, 2025 07:14
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bump major If this pull request merged, bump major version of the scenario_simulator_v2 refactor wait for regression test
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants