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<typename Node >
auto getOrigin (Node &node) const
 
template<typename... Ts>
auto makeV2ITrafficLightPublisher (Ts &&... xs) -> std::shared_ptr< TrafficLightPublisherBase >
 
template<class NodeT , class AllocatorT = std::allocator<void>>
 EntityManager (NodeT &&node, const Configuration &configuration, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node_parameters)
 
 ~EntityManager ()=default
 
template<typename... Ts>
decltype(auto) getConventionalTrafficLights (Ts &&... xs) const
 
template<typename... Ts>
decltype(auto) getV2ITrafficLights (Ts &&... xs) const
 
template<typename... Ts>
decltype(auto) getConventionalTrafficLight (Ts &&... xs) const
 
template<typename... Ts>
decltype(auto) getV2ITrafficLight (Ts &&... xs) const
 
auto generateUpdateRequestForConventionalTrafficLights ()
 
auto resetConventionalTrafficLightPublishRate (double rate) -> void
 
auto resetV2ITrafficLightPublishRate (double rate) -> void
 
auto setConventionalTrafficLightConfidence (lanelet::Id id, double confidence) -> void
 
template<typename... Ts>
decltype(auto) getLaneletLength (Ts &&... xs) const
 Forward to arguments to the HDMapUtils:: getLaneletLength function. More...
 
template<typename... Ts>
decltype(auto) toLaneletPose (Ts &&... xs) const
 Forward to arguments to the HDMapUtils:: toLaneletPose function. More...
 
template<typename... Ts>
decltype(auto) asFieldOperatorApplication (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: asFieldOperatorApplication function. More...
 
template<typename... Ts>
decltype(auto) fillLaneletPose (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: fillLaneletPose function. More...
 
template<typename... Ts>
decltype(auto) get2DPolygon (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: get2DPolygon function. More...
 
template<typename... Ts>
decltype(auto) getBehaviorParameter (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getBehaviorParameter function. More...
 
template<typename... Ts>
decltype(auto) getBoundingBox (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getBoundingBox function. More...
 
template<typename... Ts>
decltype(auto) getCurrentAccel (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getCurrentAccel function. More...
 
template<typename... Ts>
decltype(auto) getCurrentAction (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getCurrentAction function. More...
 
template<typename... Ts>
decltype(auto) getCurrentTwist (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getCurrentTwist function. More...
 
template<typename... Ts>
decltype(auto) getDefaultMatchingDistanceForLaneletPoseCalculation (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getDefaultMatchingDistanceForLaneletPoseCalculation function. More...
 
template<typename... Ts>
decltype(auto) getEntityStatusBeforeUpdate (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getEntityStatusBeforeUpdate function. More...
 
template<typename... Ts>
decltype(auto) getEntityType (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getEntityType function. More...
 
template<typename... Ts>
decltype(auto) reachPosition (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: reachPosition function. More...
 
template<typename... Ts>
decltype(auto) getEntityTypename (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getEntityTypename function. More...
 
template<typename... Ts>
decltype(auto) getLaneletPose (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getLaneletPose function. More...
 
template<typename... Ts>
decltype(auto) getLinearJerk (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getLinearJerk function. More...
 
template<typename... Ts>
decltype(auto) getMapPose (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getMapPose function. More...
 
template<typename... Ts>
decltype(auto) getMapPoseFromRelativePose (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getMapPoseFromRelativePose function. More...
 
template<typename... Ts>
decltype(auto) getRouteLanelets (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getRouteLanelets function. More...
 
template<typename... Ts>
decltype(auto) getStandStillDuration (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getStandStillDuration function. More...
 
template<typename... Ts>
decltype(auto) getTraveledDistance (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: getTraveledDistance function. More...
 
template<typename... Ts>
decltype(auto) laneMatchingSucceed (const std::string &name, Ts &&... xs) const
 Forward to arguments to the EntityBase:: laneMatchingSucceed function. More...
 
template<typename... Ts>
decltype(auto) activateOutOfRangeJob (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: activateOutOfRangeJob function. More...
 
template<typename... Ts>
decltype(auto) cancelRequest (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: cancelRequest function. More...
 
template<typename... Ts>
decltype(auto) isControlledBySimulator (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: isControlledBySimulator function. More...
 
template<typename... Ts>
decltype(auto) requestAcquirePosition (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: requestAcquirePosition function. More...
 
template<typename... Ts>
decltype(auto) requestAssignRoute (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: requestAssignRoute function. More...
 
template<typename... Ts>
decltype(auto) requestFollowTrajectory (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: requestFollowTrajectory function. More...
 
template<typename... Ts>
decltype(auto) requestLaneChange (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: requestLaneChange function. More...
 
template<typename... Ts>
decltype(auto) requestSynchronize (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: requestSynchronize function. More...
 
template<typename... Ts>
decltype(auto) requestWalkStraight (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: requestWalkStraight function. More...
 
template<typename... Ts>
decltype(auto) requestClearRoute (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: requestClearRoute function. More...
 
template<typename... Ts>
decltype(auto) setAcceleration (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setAcceleration function. More...
 
template<typename... Ts>
decltype(auto) setAccelerationLimit (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setAccelerationLimit function. More...
 
template<typename... Ts>
decltype(auto) setAccelerationRateLimit (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setAccelerationRateLimit function. More...
 
template<typename... Ts>
decltype(auto) setBehaviorParameter (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setBehaviorParameter function. More...
 
template<typename... Ts>
decltype(auto) setControlledBySimulator (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setControlledBySimulator function. More...
 
template<typename... Ts>
decltype(auto) setDecelerationLimit (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setDecelerationLimit function. More...
 
template<typename... Ts>
decltype(auto) setDecelerationRateLimit (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setDecelerationRateLimit function. More...
 
template<typename... Ts>
decltype(auto) setLinearJerk (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setLinearJerk function. More...
 
template<typename... Ts>
decltype(auto) setLinearVelocity (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setLinearVelocity function. More...
 
template<typename... Ts>
decltype(auto) setMapPose (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setMapPose function. More...
 
template<typename... Ts>
decltype(auto) setTwist (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setTwist function. More...
 
template<typename... Ts>
decltype(auto) setVelocityLimit (const std::string &name, Ts &&... xs)
 Forward to arguments to the EntityBase:: setVelocityLimit function. More...
 
visualization_msgs::msg::MarkerArray makeDebugMarker () const
 
bool trafficLightsChanged ()
 
void requestSpeedChange (const std::string &name, double target_speed, bool continuous)
 
void requestSpeedChange (const std::string &name, const double target_speed, const speed_change::Transition transition, const speed_change::Constraint constraint, const bool continuous)
 
void requestSpeedChange (const std::string &name, const speed_change::RelativeTargetSpeed &target_speed, bool continuous)
 
void requestSpeedChange (const std::string &name, const speed_change::RelativeTargetSpeed &target_speed, const speed_change::Transition transition, const speed_change::Constraint constraint, const bool continuous)
 
auto updateNpcLogic (const std::string &name) -> const CanonicalizedEntityStatus &
 
void broadcastEntityTransform ()
 
void broadcastTransform (const geometry_msgs::msg::PoseStamped &pose, const bool static_transform=true)
 
bool checkCollision (const std::string &name0, const std::string &name1)
 
bool despawnEntity (const std::string &name)
 
bool entityExists (const std::string &name)
 
auto getCurrentTime () const noexcept -> double
 
auto getEntityNames () const -> const std::vector< std::string >
 
auto getEntity (const std::string &name) const -> std::shared_ptr< traffic_simulator::entity::EntityBase >
 
auto getEntityStatus (const std::string &name) const -> CanonicalizedEntityStatus
 
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 getStepTime () const noexcept -> double
 
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 >
 
template<typename EntityType >
bool is (const std::string &name) const
 
bool isEgoSpawned () const
 
const std::string getEgoName () const
 
bool isInLanelet (const std::string &name, const lanelet::Id lanelet_id, const double tolerance)
 
bool isStopping (const std::string &name) const
 
void requestLaneChange (const std::string &name, const traffic_simulator::lane_change::Direction &direction)
 
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...
 
auto setEntityStatus (const std::string &name, const CanonicalizedEntityStatus &) -> void
 
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 &parameters, Ts &&... xs)
 
auto toMapPose (const CanonicalizedLaneletPose &) const -> const geometry_msgs::msg::Pose
 
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 ()
 
void startNpcLogic (const double current_time)
 
auto isNpcLogicStarted () const
 

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

◆ activateOutOfRangeJob()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::activateOutOfRangeJob ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: activateOutOfRangeJob function.

Returns
return value of the EntityBase:: activateOutOfRangeJob function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ asFieldOperatorApplication()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::asFieldOperatorApplication ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: asFieldOperatorApplication function.

Returns
return value of the EntityBase:: asFieldOperatorApplication function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ broadcastEntityTransform()

void traffic_simulator::entity::EntityManager::broadcastEntityTransform ( )
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()

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

◆ cancelRequest()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::cancelRequest ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: cancelRequest function.

Returns
return value of the EntityBase:: cancelRequest function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ checkCollision()

bool traffic_simulator::entity::EntityManager::checkCollision ( const std::string &  name0,
const std::string &  name1 
)

◆ createPublisher()

template<typename MessageT , typename... Args>
auto traffic_simulator::entity::EntityManager::createPublisher ( Args &&...  args)
inline

◆ createSubscription()

template<typename MessageT , typename... Args>
auto traffic_simulator::entity::EntityManager::createSubscription ( Args &&...  args)
inline

◆ despawnEntity()

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

◆ entityExists()

bool traffic_simulator::entity::EntityManager::entityExists ( const std::string &  name)

◆ fillLaneletPose()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::fillLaneletPose ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: fillLaneletPose function.

Returns
return value of the EntityBase:: fillLaneletPose function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ generateUpdateRequestForConventionalTrafficLights()

auto traffic_simulator::entity::EntityManager::generateUpdateRequestForConventionalTrafficLights ( )
inline

◆ get2DPolygon()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::get2DPolygon ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: get2DPolygon function.

Returns
return value of the EntityBase:: get2DPolygon function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getBehaviorParameter()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getBehaviorParameter ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getBehaviorParameter function.

Returns
return value of the EntityBase:: getBehaviorParameter function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getBoundingBox()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getBoundingBox ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getBoundingBox function.

Returns
return value of the EntityBase:: getBoundingBox function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getConventionalTrafficLight()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getConventionalTrafficLight ( Ts &&...  xs) const
inline

◆ getConventionalTrafficLights()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getConventionalTrafficLights ( Ts &&...  xs) const
inline

◆ getCurrentAccel()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getCurrentAccel ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getCurrentAccel function.

Returns
return value of the EntityBase:: getCurrentAccel function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getCurrentAction()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getCurrentAction ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getCurrentAction function.

Returns
return value of the EntityBase:: getCurrentAction function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getCurrentTime()

auto traffic_simulator::entity::EntityManager::getCurrentTime ( ) const -> double
noexcept

◆ getCurrentTwist()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getCurrentTwist ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getCurrentTwist function.

Returns
return value of the EntityBase:: getCurrentTwist function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getDefaultMatchingDistanceForLaneletPoseCalculation()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getDefaultMatchingDistanceForLaneletPoseCalculation ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getDefaultMatchingDistanceForLaneletPoseCalculation function.

Returns
return value of the EntityBase:: getDefaultMatchingDistanceForLaneletPoseCalculation function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getEgoName()

const std::string traffic_simulator::entity::EntityManager::getEgoName ( ) const

◆ getEntity()

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

◆ getEntityNames()

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

◆ getEntityStatus()

auto traffic_simulator::entity::EntityManager::getEntityStatus ( const std::string &  name) const -> CanonicalizedEntityStatus

◆ getEntityStatusBeforeUpdate()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getEntityStatusBeforeUpdate ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getEntityStatusBeforeUpdate function.

Returns
return value of the EntityBase:: getEntityStatusBeforeUpdate function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getEntityType()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getEntityType ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getEntityType function.

Returns
return value of the EntityBase:: getEntityType function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getEntityTypename()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getEntityTypename ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getEntityTypename function.

Returns
return value of the EntityBase:: getEntityTypename function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ 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> &

◆ getLaneletLength()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getLaneletLength ( Ts &&...  xs) const
inline

Forward to arguments to the HDMapUtils:: getLaneletLength function.

Returns
return value of the HDMapUtils:: getLaneletLength function.
Note
This function was defined by FORWARD_TO_HDMAP_UTILS macro.

◆ getLaneletPose()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getLaneletPose ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getLaneletPose function.

Returns
return value of the EntityBase:: getLaneletPose function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getLinearJerk()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getLinearJerk ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getLinearJerk function.

Returns
return value of the EntityBase:: getLinearJerk function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getMapPose()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getMapPose ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getMapPose function.

Returns
return value of the EntityBase:: getMapPose function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getMapPoseFromRelativePose()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getMapPoseFromRelativePose ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getMapPoseFromRelativePose function.

Returns
return value of the EntityBase:: getMapPoseFromRelativePose function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ 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 &

◆ getRouteLanelets()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getRouteLanelets ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getRouteLanelets function.

Returns
return value of the EntityBase:: getRouteLanelets function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getStandStillDuration()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getStandStillDuration ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getStandStillDuration function.

Returns
return value of the EntityBase:: getStandStillDuration function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getStepTime()

auto traffic_simulator::entity::EntityManager::getStepTime ( ) const -> double
noexcept

◆ getTraveledDistance()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getTraveledDistance ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: getTraveledDistance function.

Returns
return value of the EntityBase:: getTraveledDistance function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ getV2ITrafficLight()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getV2ITrafficLight ( Ts &&...  xs) const
inline

◆ getV2ITrafficLights()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::getV2ITrafficLights ( Ts &&...  xs) const
inline

◆ 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

◆ is()

template<typename EntityType >
bool traffic_simulator::entity::EntityManager::is ( const std::string &  name) const
inline

◆ isControlledBySimulator()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::isControlledBySimulator ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: isControlledBySimulator function.

Returns
return value of the EntityBase:: isControlledBySimulator function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ isEgoSpawned()

bool traffic_simulator::entity::EntityManager::isEgoSpawned ( ) const

◆ isInLanelet()

bool traffic_simulator::entity::EntityManager::isInLanelet ( const std::string &  name,
const lanelet::Id  lanelet_id,
const double  tolerance 
)

◆ isNpcLogicStarted()

auto traffic_simulator::entity::EntityManager::isNpcLogicStarted ( ) const
inline

◆ isStopping()

bool traffic_simulator::entity::EntityManager::isStopping ( const std::string &  name) const

◆ laneMatchingSucceed()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::laneMatchingSucceed ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: laneMatchingSucceed function.

Returns
return value of the EntityBase:: laneMatchingSucceed function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ makeDebugMarker()

visualization_msgs::msg::MarkerArray traffic_simulator::entity::EntityManager::makeDebugMarker ( ) const

◆ makeV2ITrafficLightPublisher()

template<typename... Ts>
auto traffic_simulator::entity::EntityManager::makeV2ITrafficLightPublisher ( Ts &&...  xs) -> std::shared_ptr<TrafficLightPublisherBase>
inline

◆ reachPosition()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::reachPosition ( const std::string &  name,
Ts &&...  xs 
) const
inline

Forward to arguments to the EntityBase:: reachPosition function.

Returns
return value of the EntityBase:: reachPosition function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ requestAcquirePosition()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::requestAcquirePosition ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: requestAcquirePosition function.

Returns
return value of the EntityBase:: requestAcquirePosition function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ requestAssignRoute()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::requestAssignRoute ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: requestAssignRoute function.

Returns
return value of the EntityBase:: requestAssignRoute function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ requestClearRoute()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::requestClearRoute ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: requestClearRoute function.

Returns
return value of the EntityBase:: requestClearRoute function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ requestFollowTrajectory()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::requestFollowTrajectory ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: requestFollowTrajectory function.

Returns
return value of the EntityBase:: requestFollowTrajectory function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ requestLaneChange() [1/2]

void traffic_simulator::entity::EntityManager::requestLaneChange ( const std::string &  name,
const traffic_simulator::lane_change::Direction direction 
)

◆ requestLaneChange() [2/2]

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::requestLaneChange ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: requestLaneChange function.

Returns
return value of the EntityBase:: requestLaneChange function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ requestSpeedChange() [1/4]

void traffic_simulator::entity::EntityManager::requestSpeedChange ( const std::string &  name,
const double  target_speed,
const speed_change::Transition  transition,
const speed_change::Constraint  constraint,
const bool  continuous 
)

◆ requestSpeedChange() [2/4]

void traffic_simulator::entity::EntityManager::requestSpeedChange ( const std::string &  name,
const speed_change::RelativeTargetSpeed target_speed,
bool  continuous 
)

◆ requestSpeedChange() [3/4]

void traffic_simulator::entity::EntityManager::requestSpeedChange ( const std::string &  name,
const speed_change::RelativeTargetSpeed target_speed,
const speed_change::Transition  transition,
const speed_change::Constraint  constraint,
const bool  continuous 
)

◆ requestSpeedChange() [4/4]

void traffic_simulator::entity::EntityManager::requestSpeedChange ( const std::string &  name,
double  target_speed,
bool  continuous 
)

◆ requestSynchronize()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::requestSynchronize ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: requestSynchronize function.

Returns
return value of the EntityBase:: requestSynchronize function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ requestWalkStraight()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::requestWalkStraight ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: requestWalkStraight function.

Returns
return value of the EntityBase:: requestWalkStraight function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ resetBehaviorPlugin()

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.

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

◆ resetConventionalTrafficLightPublishRate()

auto traffic_simulator::entity::EntityManager::resetConventionalTrafficLightPublishRate ( double  rate) -> void
inline

◆ resetV2ITrafficLightPublishRate()

auto traffic_simulator::entity::EntityManager::resetV2ITrafficLightPublishRate ( double  rate) -> void
inline

◆ setAcceleration()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setAcceleration ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setAcceleration function.

Returns
return value of the EntityBase:: setAcceleration function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setAccelerationLimit()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setAccelerationLimit ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setAccelerationLimit function.

Returns
return value of the EntityBase:: setAccelerationLimit function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setAccelerationRateLimit()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setAccelerationRateLimit ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setAccelerationRateLimit function.

Returns
return value of the EntityBase:: setAccelerationRateLimit function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setBehaviorParameter()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setBehaviorParameter ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setBehaviorParameter function.

Returns
return value of the EntityBase:: setBehaviorParameter function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setControlledBySimulator()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setControlledBySimulator ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setControlledBySimulator function.

Returns
return value of the EntityBase:: setControlledBySimulator function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setConventionalTrafficLightConfidence()

auto traffic_simulator::entity::EntityManager::setConventionalTrafficLightConfidence ( lanelet::Id  id,
double  confidence 
) -> void
inline

◆ setDecelerationLimit()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setDecelerationLimit ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setDecelerationLimit function.

Returns
return value of the EntityBase:: setDecelerationLimit function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setDecelerationRateLimit()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setDecelerationRateLimit ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setDecelerationRateLimit function.

Returns
return value of the EntityBase:: setDecelerationRateLimit function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setEntityStatus()

auto traffic_simulator::entity::EntityManager::setEntityStatus ( const std::string &  name,
const CanonicalizedEntityStatus status 
) -> void

◆ setLinearJerk()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setLinearJerk ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setLinearJerk function.

Returns
return value of the EntityBase:: setLinearJerk function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setLinearVelocity()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setLinearVelocity ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setLinearVelocity function.

Returns
return value of the EntityBase:: setLinearVelocity function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setMapPose()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setMapPose ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setMapPose function.

Returns
return value of the EntityBase:: setMapPose function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setTwist()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setTwist ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setTwist function.

Returns
return value of the EntityBase:: setTwist function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setVelocityLimit()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::setVelocityLimit ( const std::string &  name,
Ts &&...  xs 
)
inline

Forward to arguments to the EntityBase:: setVelocityLimit function.

Returns
return value of the EntityBase:: setVelocityLimit function.
Note
This function was defined by FORWARD_TO_ENTITY macro.        

◆ setVerbose()

void traffic_simulator::entity::EntityManager::setVerbose ( const bool  verbose)

◆ spawnEntity()

template<typename Entity , typename Pose , typename Parameters , typename... Ts>
auto traffic_simulator::entity::EntityManager::spawnEntity ( const std::string &  name,
const Pose &  pose,
const Parameters &  parameters,
Ts &&...  xs 
)
inline
Note
If the entity is pedestrian or misc object, we have to consider matching to crosswalk lanelet.
fix z, roll and pitch to fitting to the lanelet

◆ startNpcLogic()

void traffic_simulator::entity::EntityManager::startNpcLogic ( const double  current_time)

◆ toLaneletPose()

template<typename... Ts>
decltype(auto) traffic_simulator::entity::EntityManager::toLaneletPose ( Ts &&...  xs) const
inline

Forward to arguments to the HDMapUtils:: toLaneletPose function.

Returns
return value of the HDMapUtils:: toLaneletPose function.
Note
This function was defined by FORWARD_TO_HDMAP_UTILS macro.

◆ toMapPose()

auto traffic_simulator::entity::EntityManager::toMapPose ( const CanonicalizedLaneletPose lanelet_pose) const -> const geometry_msgs::msg::Pose

◆ trafficLightsChanged()

bool traffic_simulator::entity::EntityManager::trafficLightsChanged ( )

◆ update()

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

◆ updateHdmapMarker()

void traffic_simulator::entity::EntityManager::updateHdmapMarker ( )

◆ updateNpcLogic()

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

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