scenario_simulator_v2 C++ API
Public Member Functions | List of all members
traffic_simulator::entity::EntityManager Class Reference

#include <entity_manager.hpp>

Public Member Functions

template<class NodeT , class AllocatorT = std::allocator<void>>
 EntityManager (NodeT &&node, const Configuration &configuration, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node_parameters)
 
 ~EntityManager ()=default
 
auto setTrafficLights (const std::shared_ptr< TrafficLights > &traffic_lights_ptr) -> void
 
auto setVerbose (const bool verbose) -> void
 
auto startNpcLogic (const double current_time) -> void
 
auto isNpcLogicStarted () const -> bool
 
auto makeDebugMarker () const -> visualization_msgs::msg::MarkerArray
 
auto update (const double current_time, const double step_time) -> void
 
auto updateNpcLogic (const std::string &name, const double current_time, const double step_time) -> const CanonicalizedEntityStatus &
 
auto updateHdmapMarker () const -> void
 
auto broadcastEntityTransform () -> void
 
auto broadcastTransform (const geometry_msgs::msg::PoseStamped &pose, const bool static_transform=true) -> void
 
template<typename EntityType , typename PoseType , typename ParametersType , typename... Ts>
auto spawnEntity (const std::string &name, const PoseType &pose, const ParametersType &parameters, const double current_time, Ts &&... xs) -> entity::EntityBase &
 
auto getNumberOfEgo () const -> std::size_t
 
auto isAnyEgoSpawned () const -> bool
 
auto getFirstEgoName () const -> std::optional< std::string >
 
auto getEgoEntity (const std::string &name) -> entity::EgoEntity &
 
auto getEgoEntity (const std::string &name) const -> const entity::EgoEntity &
 
auto isEntityExist (const std::string &name) const -> bool
 
auto getEntityNames () const -> const std::vector< std::string >
 
auto getEntity (const std::string &name) -> entity::EntityBase &
 
auto getEntity (const std::string &name) const -> const entity::EntityBase &
 
auto getEntityPointer (const std::string &name) const -> std::shared_ptr< entity::EntityBase >
 
auto resetBehaviorPlugin (const std::string &name, const std::string &behavior_plugin_name) -> void
 Reset behavior plugin of the target entity. The internal behavior is to take over the various parameters and save them, then respawn the Entity and set the parameters. More...
 
auto despawnEntity (const std::string &name) -> bool
 
auto getHdmapUtils () -> const std::shared_ptr< hdmap_utils::HdMapUtils > &
 
template<typename Node >
auto getOrigin (Node &node) const
 
auto getObstacle (const std::string &name) -> std::optional< traffic_simulator_msgs::msg::Obstacle >
 
auto getPedestrianParameters (const std::string &name) const -> const traffic_simulator_msgs::msg::PedestrianParameters &
 
auto getVehicleParameters (const std::string &name) const -> const traffic_simulator_msgs::msg::VehicleParameters &
 
auto getWaypoints (const std::string &name) -> traffic_simulator_msgs::msg::WaypointsArray
 
template<typename T >
auto getGoalPoses (const std::string &name) -> std::vector< T >
 

Constructor & Destructor Documentation

◆ EntityManager()

template<class NodeT , class AllocatorT = std::allocator<void>>
traffic_simulator::entity::EntityManager::EntityManager ( NodeT &&  node,
const Configuration configuration,
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &  node_parameters 
)
inlineexplicit

◆ ~EntityManager()

traffic_simulator::entity::EntityManager::~EntityManager ( )
default

Member Function Documentation

◆ broadcastEntityTransform()

auto traffic_simulator::entity::EntityManager::broadcastEntityTransform ( ) -> void
Note
This part of the process is intended to ensure that frames are issued in a position that makes it as easy as possible to see the entities that will appear in the scenario. In the past, we used to publish the frames of all entities, but that would be too heavy processing, so we publish the average of the coordinates of all entities.
This is the intended implementation. It is easier to create rviz config if the name "ego" is fixed, so the frame_id "ego" is issued regardless of the name of the ego entity.

◆ broadcastTransform()

auto traffic_simulator::entity::EntityManager::broadcastTransform ( const geometry_msgs::msg::PoseStamped &  pose,
const bool  static_transform = true 
) -> void

◆ despawnEntity()

auto traffic_simulator::entity::EntityManager::despawnEntity ( const std::string &  name) -> bool

◆ getEgoEntity() [1/2]

auto traffic_simulator::entity::EntityManager::getEgoEntity ( const std::string &  name) -> entity::EgoEntity &

◆ getEgoEntity() [2/2]

auto traffic_simulator::entity::EntityManager::getEgoEntity ( const std::string &  name) const -> const entity::EgoEntity &

◆ getEntity() [1/2]

auto traffic_simulator::entity::EntityManager::getEntity ( const std::string &  name) -> entity::EntityBase &

◆ getEntity() [2/2]

auto traffic_simulator::entity::EntityManager::getEntity ( const std::string &  name) const -> const entity::EntityBase &

◆ getEntityNames()

auto traffic_simulator::entity::EntityManager::getEntityNames ( ) const -> const std::vector<std::string>

◆ getEntityPointer()

auto traffic_simulator::entity::EntityManager::getEntityPointer ( const std::string &  name) const -> std::shared_ptr<entity::EntityBase>

◆ getFirstEgoName()

auto traffic_simulator::entity::EntityManager::getFirstEgoName ( ) const -> std::optional<std::string>

◆ getGoalPoses()

template<typename T >
auto traffic_simulator::entity::EntityManager::getGoalPoses ( const std::string &  name) -> std::vector<T>
inline

◆ getHdmapUtils()

auto traffic_simulator::entity::EntityManager::getHdmapUtils ( ) -> const std::shared_ptr<hdmap_utils::HdMapUtils> &

◆ getNumberOfEgo()

auto traffic_simulator::entity::EntityManager::getNumberOfEgo ( ) const -> std::size_t

◆ getObstacle()

auto traffic_simulator::entity::EntityManager::getObstacle ( const std::string &  name) -> std::optional<traffic_simulator_msgs::msg::Obstacle>

◆ getOrigin()

template<typename Node >
auto traffic_simulator::entity::EntityManager::getOrigin ( Node &  node) const
inline

◆ getPedestrianParameters()

auto traffic_simulator::entity::EntityManager::getPedestrianParameters ( const std::string &  name) const -> const traffic_simulator_msgs::msg::PedestrianParameters &

◆ getVehicleParameters()

auto traffic_simulator::entity::EntityManager::getVehicleParameters ( const std::string &  name) const -> const traffic_simulator_msgs::msg::VehicleParameters &

◆ getWaypoints()

auto traffic_simulator::entity::EntityManager::getWaypoints ( const std::string &  name) -> traffic_simulator_msgs::msg::WaypointsArray

◆ isAnyEgoSpawned()

auto traffic_simulator::entity::EntityManager::isAnyEgoSpawned ( ) const -> bool

◆ isEntityExist()

auto traffic_simulator::entity::EntityManager::isEntityExist ( const std::string &  name) const -> bool

◆ isNpcLogicStarted()

auto traffic_simulator::entity::EntityManager::isNpcLogicStarted ( ) const -> bool

◆ makeDebugMarker()

auto traffic_simulator::entity::EntityManager::makeDebugMarker ( ) const -> visualization_msgs::msg::MarkerArray

◆ resetBehaviorPlugin()

auto traffic_simulator::entity::EntityManager::resetBehaviorPlugin ( const std::string &  name,
const std::string &  behavior_plugin_name 
) -> void

Reset behavior plugin of the target entity. The internal behavior is to take over the various parameters and save them, then respawn the Entity and set the parameters.

Parameters
nameThe name of the target entity.
behavior_plugin_nameThe name of the behavior plugin you want to set.
See also
entity::PedestrianEntity::BuiltinBehavior
entity::VehicleEntity::BuiltinBehavior

◆ setTrafficLights()

auto traffic_simulator::entity::EntityManager::setTrafficLights ( const std::shared_ptr< TrafficLights > &  traffic_lights_ptr) -> void

This function is necessary because the TrafficLights object is created after the EntityManager, so it can be assigned during the call of the EntityManager constructor. TrafficLights cannot be created before the EntityManager due to the dependency on HdMapUtils.

◆ setVerbose()

auto traffic_simulator::entity::EntityManager::setVerbose ( const bool  verbose) -> void

◆ spawnEntity()

template<typename EntityType , typename PoseType , typename ParametersType , typename... Ts>
auto traffic_simulator::entity::EntityManager::spawnEntity ( const std::string &  name,
const PoseType &  pose,
const ParametersType &  parameters,
const double  current_time,
Ts &&...  xs 
) -> entity::EntityBase &
inline

◆ startNpcLogic()

auto traffic_simulator::entity::EntityManager::startNpcLogic ( const double  current_time) -> void

◆ update()

auto traffic_simulator::entity::EntityManager::update ( const double  current_time,
const double  step_time 
) -> void

◆ updateHdmapMarker()

auto traffic_simulator::entity::EntityManager::updateHdmapMarker ( ) const -> void

◆ updateNpcLogic()

auto traffic_simulator::entity::EntityManager::updateNpcLogic ( const std::string &  name,
const double  current_time,
const double  step_time 
) -> const CanonicalizedEntityStatus &

The documentation for this class was generated from the following files: