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

[tmp] RJD-1057 (4/5): Remove non-API member functions: EntityManager’s member functions forwarded to EntityBase (2/2) #1334

Draft
wants to merge 30 commits into
base: RJD-1057-remove-functions-forwarded-to-entity-base-middle
Choose a base branch
from

Conversation

TauTheLepton
Copy link
Contributor

@TauTheLepton TauTheLepton commented Jul 31, 2024

Description

DO NOT MERGE | THIS IS A TEMPORARY PR | WHEN THE RIGHT TIME COMES, TARGET WILL BE CHANGED TO MASTER

Abstract

This pull request mainly consists of refactoring and introduces changes in the API and EntityManager.

Background

This pull request is an extension of the #1473.
Due to the fact that these pull requests combined would have been too large for a review, they have been split into two.

As a result of the previous PR, changes have been made to the API and EntityManager classes.
These changes created a great opportunity to declutter / tidy up the code of these classes.
This pull request consists of the code cleanup and refactoring. Many of the changes introduced are just changes to the order of functions inside the implementation file to keep them grouped by functionality and consistent with the header file.

Some other minor changes have been introduced as well, like the addition of the ostream_helpers.cpp.

What is more, the functions EntityManager::spawnEntity and (most importantly) API::spawn have been modified to return the Entity object pointer:

Before:

template <typename Pose>
auto spawn(
const std::string & name, const Pose & pose,
const traffic_simulator_msgs::msg::VehicleParameters & parameters,
const std::string & behavior = VehicleBehavior::defaultBehavior(),
const std::string & model3d = "")
{

After:

template <typename PoseType, typename ParamsType>
auto spawn(
const std::string & name, const PoseType & pose, const ParamsType & parameters,
const std::string & behavior = "", const std::string & model3d = "")
-> std::shared_ptr<entity::EntityBase>
{

This change has been applied in the whole codebase, which includes multiple cpp mock scenarios.

Cpp mock scenarios have been all changed like the following:

Before:

api_.spawn(
"npc",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 10.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
auto npc_entity = api_.getEntity("npc");
npc_entity->setLinearVelocity(10);
npc_entity->requestSpeedChange(10, true);

After:

auto npc_entity = api_.spawn(
"npc",
traffic_simulator::helper::constructCanonicalizedLaneletPose(
34741, 10.0, 0.0, api_.getHdmapUtils()),
getVehicleParameters());
npc_entity->setLinearVelocity(10);
npc_entity->requestSpeedChange(10, true);

Details

Below are all changes made in this PR

API

  • Renamed member configuration to configuration_
  • Most of the constructor logic has been moved to API::init() member function
    auto API::init() -> bool
    {
    if (not configuration_.standalone_mode) {
    simulation_api_schema::InitializeRequest request;
    request.set_initialize_time(clock_.getCurrentSimulationTime());
    request.set_lanelet2_map_path(configuration_.lanelet2_map_path().string());
    request.set_realtime_factor(clock_.realtime_factor);
    request.set_step_time(clock_.getStepTime());
    simulation_interface::toProto(
    clock_.getCurrentRosTime(), *request.mutable_initialize_ros_time());
    return zeromq_client_.call(request).result().success();
    } else {
    return true;
    }
    }
  • Added member function setSiulationStepTime
    auto API::setSimulationStepTime(const double step_time) -> bool
    {
    /**
    * @note Pausing the simulation by setting the realtime_factor_ value to 0 is not supported and causes the simulation crash.
    * For that reason, before performing the action, it needs to be ensured that the incoming request data is a positive number.
    */
    if (step_time >= 0.001) {
    clock_.realtime_factor = step_time;
    simulation_api_schema::UpdateStepTimeRequest request;
    request.set_simulation_step_time(clock_.getStepTime());
    return zeromq_client_.call(request).result().success();
    } else {
    return false;
    }
    }
  • Removed member function getZMQSocketPort in favor of using getROS2Parameter
  • 3 spawn functions
    template <typename Pose>
    auto spawn(
    const std::string & name, const Pose & pose,
    const traffic_simulator_msgs::msg::VehicleParameters & parameters,
    const std::string & behavior = VehicleBehavior::defaultBehavior(),
    const std::string & model3d = "")
    {
    auto register_to_entity_manager = [&]() {
    if (behavior == VehicleBehavior::autoware()) {
    return entity_manager_ptr_->isEntityExist(name) or
    entity_manager_ptr_->spawnEntity<entity::EgoEntity>(
    name, pose, parameters, getCurrentTime(), configuration, node_parameters_);
    } else {
    return entity_manager_ptr_->spawnEntity<entity::VehicleEntity>(
    name, pose, parameters, getCurrentTime(), behavior);
    }
    };
    auto register_to_environment_simulator = [&]() {
    if (configuration.standalone_mode) {
    return true;
    } else if (const auto entity = entity_manager_ptr_->getEntityOrNullptr(name); not entity) {
    throw common::SemanticError(
    "Entity ", name, " can not be registered in simulator - it has not been spawned yet.");
    } else {
    simulation_api_schema::SpawnVehicleEntityRequest req;
    simulation_interface::toProto(parameters, *req.mutable_parameters());
    req.mutable_parameters()->set_name(name);
    req.set_asset_key(model3d);
    simulation_interface::toProto(entity->getMapPose(), *req.mutable_pose());
    req.set_is_ego(behavior == VehicleBehavior::autoware());
    /// @todo Should be filled from function API
    req.set_initial_speed(0.0);
    return zeromq_client_.call(req).result().success();
    }
    };
    return register_to_entity_manager() and register_to_environment_simulator();
    }
    template <typename Pose>
    auto spawn(
    const std::string & name, const Pose & pose,
    const traffic_simulator_msgs::msg::PedestrianParameters & parameters,
    const std::string & behavior = PedestrianBehavior::defaultBehavior(),
    const std::string & model3d = "")
    {
    auto register_to_entity_manager = [&]() {
    return entity_manager_ptr_->spawnEntity<entity::PedestrianEntity>(
    name, pose, parameters, getCurrentTime(), behavior);
    };
    auto register_to_environment_simulator = [&]() {
    if (configuration.standalone_mode) {
    return true;
    } else if (const auto entity = entity_manager_ptr_->getEntityOrNullptr(name); not entity) {
    throw common::SemanticError(
    "Entity ", name, " can not be registered in simulator - it has not been spawned yet.");
    } else {
    simulation_api_schema::SpawnPedestrianEntityRequest req;
    simulation_interface::toProto(parameters, *req.mutable_parameters());
    req.mutable_parameters()->set_name(name);
    req.set_asset_key(model3d);
    simulation_interface::toProto(entity->getMapPose(), *req.mutable_pose());
    return zeromq_client_.call(req).result().success();
    }
    };
    return register_to_entity_manager() and register_to_environment_simulator();
    }
    template <typename Pose>
    auto spawn(
    const std::string & name, const Pose & pose,
    const traffic_simulator_msgs::msg::MiscObjectParameters & parameters,
    const std::string & model3d = "")
    {
    auto register_to_entity_manager = [&]() {
    return entity_manager_ptr_->spawnEntity<entity::MiscObjectEntity>(
    name, pose, parameters, getCurrentTime());
    };
    auto register_to_environment_simulator = [&]() {
    if (configuration.standalone_mode) {
    return true;
    } else if (const auto entity = entity_manager_ptr_->getEntityOrNullptr(name); not entity) {
    throw common::SemanticError(
    "Entity ", name, " can not be registered in simulator - it has not been spawned yet.");
    } else {
    simulation_api_schema::SpawnMiscObjectEntityRequest req;
    simulation_interface::toProto(parameters, *req.mutable_parameters());
    req.mutable_parameters()->set_name(name);
    req.set_asset_key(model3d);
    simulation_interface::toProto(entity->getMapPose(), *req.mutable_pose());
    return zeromq_client_.call(req).result().success();
    }
    };
    return register_to_entity_manager() and register_to_environment_simulator();
    }

    have been combined in 1 spawn function
    template <typename PoseType, typename ParamsType>
    auto spawn(
    const std::string & name, const PoseType & pose, const ParamsType & parameters,
    const std::string & behavior = "", const std::string & model3d = "")
    -> std::shared_ptr<entity::EntityBase>
    {
    using VehicleParameters = traffic_simulator_msgs::msg::VehicleParameters;
    using PedestrianParameters = traffic_simulator_msgs::msg::PedestrianParameters;
    using MiscObjectParameters = traffic_simulator_msgs::msg::MiscObjectParameters;
    auto register_to_entity_manager = [&]() {
    if constexpr (std::is_same<ParamsType, VehicleParameters>::value) {
    if (behavior == VehicleBehavior::autoware()) {
    return entity_manager_ptr_->spawnEntity<entity::EgoEntity>(
    name, pose, parameters, getCurrentTime(), configuration_, node_parameters_);
    } else {
    return entity_manager_ptr_->spawnEntity<entity::VehicleEntity>(
    name, pose, parameters, getCurrentTime(),
    behavior.empty() ? VehicleBehavior::defaultBehavior() : behavior);
    }
    } else if constexpr (std::is_same<ParamsType, PedestrianParameters>::value) {
    return entity_manager_ptr_->spawnEntity<entity::PedestrianEntity>(
    name, pose, parameters, getCurrentTime(),
    behavior.empty() ? PedestrianBehavior::defaultBehavior() : behavior);
    } else if constexpr (std::is_same<ParamsType, MiscObjectParameters>::value) {
    return entity_manager_ptr_->spawnEntity<entity::MiscObjectEntity>(
    name, pose, parameters, getCurrentTime());
    } else {
    THROW_SEMANTIC_ERROR("Entity ", std::quoted(name), " has an undefined type.");
    }
    };
    auto prepare_and_send_request = [&](const auto & entity, auto & reqest) -> bool {
    simulation_interface::toProto(parameters, *reqest.mutable_parameters());
    reqest.mutable_parameters()->set_name(name);
    reqest.set_asset_key(model3d);
    simulation_interface::toProto(entity->getMapPose(), *reqest.mutable_pose());
    return zeromq_client_.call(reqest).result().success();
    };
    auto register_to_environment_simulator = [&](const auto & entity) -> bool {
    if (configuration_.standalone_mode) {
    return true;
    } else {
    if constexpr (std::is_same<ParamsType, VehicleParameters>::value) {
    simulation_api_schema::SpawnVehicleEntityRequest reqest;
    reqest.set_is_ego(behavior == VehicleBehavior::autoware());
    /// @todo Should be filled from function API
    reqest.set_initial_speed(0.0);
    return prepare_and_send_request(entity, reqest);
    } else if constexpr (std::is_same<ParamsType, PedestrianParameters>::value) {
    simulation_api_schema::SpawnPedestrianEntityRequest reqest;
    return prepare_and_send_request(entity, reqest);
    } else if constexpr (std::is_same<ParamsType, MiscObjectParameters>::value) {
    simulation_api_schema::SpawnMiscObjectEntityRequest reqest;
    return prepare_and_send_request(entity, reqest);
    } else {
    return false;
    }
    }
    };
    const auto entity = register_to_entity_manager();
    if (entity && register_to_environment_simulator(entity)) {
    return entity;
    } else {
    THROW_SEMANTIC_ERROR("Spawn entity ", std::quoted(name), " resulted in failure.");
    }
    }
  • The remaining functions that were defined using the FORWARD_TO_ENTITY_MANAGER macro have been converted to standard functions
    • isAnyEgoSpawned
    • getEgoEntity
    • isEntityExist
    • getEntityNames
    • getEntityOrNullptr
    • resetBehaviorPlugin
    • isNpcLogicStarted
    • getHdmapUtils

All other changes are minor refactoring or just reordering functions in the file, which GitHub shows as changes.

EntityBase

  • Add member function as
    /* */ auto as() -> std::shared_ptr<EntityType>
    {
    if (auto derived = std::dynamic_pointer_cast<EntityType>(shared_from_this()); !derived) {
    THROW_SEMANTIC_ERROR(
    "Entity ", std::quoted(name), " is not ", std::quoted(typeid(EntityType).name()), "type");
    } else {
    return derived;
    }
    }
    template <typename EntityType>
    /* */ auto as() const -> std::shared_ptr<const EntityType>
    {
    if (auto derived = std::dynamic_pointer_cast<const EntityType>(shared_from_this()); !derived) {
    THROW_SEMANTIC_ERROR(
    "Entity ", std::quoted(name), " is not ", std::quoted(typeid(EntityType).name()), "type");
    } else {
    return derived;
    }
    }
  • Change getGoalPoses return type
    • auto getGoalPoses() -> std::vector<CanonicalizedLaneletPose>

      auto getGoalPoses() -> std::vector<geometry_msgs::msg::Pose>

All other changes are minor refactoring or just reordering functions in the file, which GitHub shows as changes.

EntityManager

  • Renamed member configuration to configuration_
  • Moved member function getOrigin to free function
    auto getOrigin(const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node_parameters)
    -> geographic_msgs::msg::GeoPoint;
  • Removed these member functions in favor of using Entity member function directly:
    • getObstacle
    • getWaypoints
    • getGoalPoses
  • Removed these member functions in favor of using Entity field directly:
    • getPedestrianParameters
    • getVehicleParameters
  • As mentioned in Background, the spawnEntity function now returns a pointer to the created entity.
  • Removed member function createPublisher
  • Removed member function createSubscription

All other changes are minor refactoring or just reordering functions in the file, which GitHub shows as changes.

MiscObjectEntity

  • Change getGoalPoses return type
    • auto getGoalPoses() -> std::vector<CanonicalizedLaneletPose>

      auto getGoalPoses() -> std::vector<geometry_msgs::msg::Pose>

PedestrianEntity

  • Change getGoalPoses return type
    • auto getGoalPoses() -> std::vector<CanonicalizedLaneletPose>

      auto getGoalPoses() -> std::vector<geometry_msgs::msg::Pose>
  • Added member function auto getParameters() const -> const traffic_simulator_msgs::msg::PedestrianParameters &;

VehicleEntity

  • Change getGoalPoses return type
    • auto getGoalPoses() -> std::vector<CanonicalizedLaneletPose>

      auto getGoalPoses() -> std::vector<geometry_msgs::msg::Pose>
  • Added member function auto getParameters() const -> const traffic_simulator_msgs::msg::VehicleParameters &;

References

INTERNAL LINK 1
INTERNAL LINK 2

Destructive Changes

--

Known Limitations

--

dmoszynski and others added 13 commits July 2, 2024 13:09
…o RJD-1057-remove-functions-forwarded-to-entity-base

Signed-off-by: Mateusz Palczuk <[email protected]>
…ed-to-entity-base' into RJD-1057-remove-functions-forwarded-to-entity-base

Signed-off-by: Mateusz Palczuk <[email protected]>
…o RJD-1057-remove-functions-forwarded-to-entity-base

Signed-off-by: Mateusz Palczuk <[email protected]>
Signed-off-by: Mateusz Palczuk <[email protected]>
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-with-middle

Signed-off-by: Mateusz Palczuk <[email protected]>
@dmoszynski dmoszynski self-assigned this Jul 31, 2024
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-with-middle

Signed-off-by: Mateusz Palczuk <[email protected]>
@TauTheLepton TauTheLepton force-pushed the RJD-1057-remove-functions-forwarded-to-entity-base-refactor branch from c9057f9 to ff759fe Compare July 31, 2024 14:16
@yamacir-kit yamacir-kit deleted the branch RJD-1057-remove-functions-forwarded-to-entity-base-middle September 18, 2024 01:42
@yamacir-kit yamacir-kit deleted the RJD-1057-remove-functions-forwarded-to-entity-base-refactor branch September 18, 2024 01:43
@TauTheLepton TauTheLepton restored the RJD-1057-remove-functions-forwarded-to-entity-base-refactor branch October 2, 2024 07:32
@TauTheLepton TauTheLepton reopened this Oct 2, 2024
TauTheLepton and others added 3 commits October 3, 2024 16:43
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor

Signed-off-by: Mateusz Palczuk <[email protected]>
…ded-to-entity-base-middle' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor
@TauTheLepton TauTheLepton self-assigned this Oct 15, 2024
@dmoszynski dmoszynski changed the title [tmp] Remove non-API member functions: EntityManager’s member functions forwarded to EntityBase (2/2) [tmp] RJD-1057 (4/5): Remove non-API member functions: EntityManager’s member functions forwarded to EntityBase (2/2) Oct 15, 2024
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor
Copy link

dmoszynski and others added 9 commits December 16, 2024 14:18
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor
…le' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor

Signed-off-by: Mateusz Palczuk <[email protected]>
…ed-to-entity-base-middle' into RJD-1057-remove-functions-forwarded-to-entity-base-refactor

Signed-off-by: Mateusz Palczuk <[email protected]>
Signed-off-by: Mateusz Palczuk <[email protected]>
Signed-off-by: Mateusz Palczuk <[email protected]>
Signed-off-by: Mateusz Palczuk <[email protected]>
@TauTheLepton
Copy link
Contributor Author

No regressions confirmed here.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants