scenario_simulator_v2 C++ API
|
#include <entity_manager.hpp>
Public Member Functions | |
auto | setTrafficLights (const std::shared_ptr< traffic_simulator::TrafficLights > &traffic_lights_ptr) -> void |
template<typename Node > | |
auto | getOrigin (Node &node) const |
template<class NodeT , class AllocatorT = std::allocator<void>> | |
EntityManager (NodeT &&node, const Configuration &configuration, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node_parameters) | |
~EntityManager ()=default | |
visualization_msgs::msg::MarkerArray | makeDebugMarker () const |
auto | updateNpcLogic (const std::string &name, const double current_time, const double step_time) -> const CanonicalizedEntityStatus & |
void | broadcastEntityTransform () |
void | broadcastTransform (const geometry_msgs::msg::PoseStamped &pose, const bool static_transform=true) |
bool | despawnEntity (const std::string &name) |
auto | isEntityExist (const std::string &name) const -> bool |
auto | getEntityNames () const -> const std::vector< std::string > |
auto | getEntityPointer (const std::string &name) const -> std::shared_ptr< traffic_simulator::entity::EntityBase > |
auto | getEntity (const std::string &name) -> entity::EntityBase & |
auto | getEntity (const std::string &name) const -> const entity::EntityBase & |
auto | getEgoEntity (const std::string &name) -> entity::EgoEntity & |
auto | getEgoEntity (const std::string &name) const -> const entity::EgoEntity & |
auto | getHdmapUtils () -> const std::shared_ptr< hdmap_utils::HdMapUtils > & |
auto | getNumberOfEgo () const -> std::size_t |
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 > |
auto | isAnyEgoSpawned () const -> bool |
auto | getFirstEgoName () const -> std::optional< std::string > |
void | resetBehaviorPlugin (const std::string &name, const std::string &behavior_plugin_name) |
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... | |
void | setVerbose (const bool verbose) |
template<typename Entity , typename Pose , typename Parameters , typename... Ts> | |
auto | spawnEntity (const std::string &name, const Pose &pose, const Parameters ¶meters, const double current_time, Ts &&... xs) |
template<typename MessageT , typename... Args> | |
auto | createPublisher (Args &&... args) |
template<typename MessageT , typename... Args> | |
auto | createSubscription (Args &&... args) |
void | update (const double current_time, const double step_time) |
void | updateHdmapMarker () |
auto | startNpcLogic (const double current_time) -> void |
auto | isNpcLogicStarted () const -> bool |
|
inlineexplicit |
|
default |
auto traffic_simulator::entity::EntityManager::broadcastEntityTransform | ( | ) |
void traffic_simulator::entity::EntityManager::broadcastTransform | ( | const geometry_msgs::msg::PoseStamped & | pose, |
const bool | static_transform = true |
||
) |
|
inline |
|
inline |
bool traffic_simulator::entity::EntityManager::despawnEntity | ( | const std::string & | name | ) |
auto traffic_simulator::entity::EntityManager::getEgoEntity | ( | const std::string & | name | ) | -> entity::EgoEntity & |
auto traffic_simulator::entity::EntityManager::getEgoEntity | ( | const std::string & | name | ) | const -> const entity::EgoEntity & |
auto traffic_simulator::entity::EntityManager::getEntity | ( | const std::string & | name | ) | -> entity::EntityBase & |
auto traffic_simulator::entity::EntityManager::getEntity | ( | const std::string & | name | ) | const -> const entity::EntityBase & |
auto traffic_simulator::entity::EntityManager::getEntityNames | ( | ) | const -> const std::vector<std::string> |
auto traffic_simulator::entity::EntityManager::getEntityPointer | ( | const std::string & | name | ) | const -> std::shared_ptr<traffic_simulator::entity::EntityBase> |
auto traffic_simulator::entity::EntityManager::getFirstEgoName | ( | ) | const -> std::optional<std::string> |
|
inline |
auto traffic_simulator::entity::EntityManager::getHdmapUtils | ( | ) | -> const std::shared_ptr<hdmap_utils::HdMapUtils> & |
auto traffic_simulator::entity::EntityManager::getNumberOfEgo | ( | ) | const -> std::size_t |
auto traffic_simulator::entity::EntityManager::getObstacle | ( | const std::string & | name | ) | -> std::optional<traffic_simulator_msgs::msg::Obstacle> |
|
inline |
auto traffic_simulator::entity::EntityManager::getPedestrianParameters | ( | const std::string & | name | ) | const -> const traffic_simulator_msgs::msg::PedestrianParameters & |
auto traffic_simulator::entity::EntityManager::getVehicleParameters | ( | const std::string & | name | ) | const -> const traffic_simulator_msgs::msg::VehicleParameters & |
auto traffic_simulator::entity::EntityManager::getWaypoints | ( | const std::string & | name | ) | -> traffic_simulator_msgs::msg::WaypointsArray |
auto traffic_simulator::entity::EntityManager::isAnyEgoSpawned | ( | ) | const -> bool |
auto traffic_simulator::entity::EntityManager::isEntityExist | ( | const std::string & | name | ) | const -> bool |
|
inline |
visualization_msgs::msg::MarkerArray traffic_simulator::entity::EntityManager::makeDebugMarker | ( | ) | const |
void traffic_simulator::entity::EntityManager::resetBehaviorPlugin | ( | const std::string & | name, |
const std::string & | behavior_plugin_name | ||
) |
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.
name | The name of the target entity. |
behavior_plugin_name | The name of the behavior plugin you want to set. |
|
inline |
This function is necessary because the TrafficLights object is created after the EntityManager, so it cannot be assigned during the call of the EntityManager constructor. TrafficLights cannot be created before the EntityManager due to the dependency on HdMapUtils.
void traffic_simulator::entity::EntityManager::setVerbose | ( | const bool | verbose | ) |
|
inline |
auto traffic_simulator::entity::EntityManager::startNpcLogic | ( | const double | current_time | ) | -> void |
void traffic_simulator::entity::EntityManager::update | ( | const double | current_time, |
const double | step_time | ||
) |
void traffic_simulator::entity::EntityManager::updateHdmapMarker | ( | ) |
auto traffic_simulator::entity::EntityManager::updateNpcLogic | ( | const std::string & | name, |
const double | current_time, | ||
const double | step_time | ||
) | -> const CanonicalizedEntityStatus & |