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

#include <api.hpp>

Public Member Functions

template<typename NodeT , typename AllocatorT = std::allocator<void>, typename... Ts>
 API (NodeT &&node, const Configuration &configuration, Ts &&... xs)
 
template<typename Node >
int getZMQSocketPort (Node &node)
 
void closeZMQConnection ()
 
void setVerbose (const bool verbose)
 
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="")
 
geometry_msgs::msg::Pose toMapPose (const geometry_msgs::msg::Pose &pose)
 
geometry_msgs::msg::Pose toMapPose (const traffic_simulator_msgs::msg::LaneletPose &pose)
 
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="")
 
template<typename Pose >
auto spawn (const std::string &name, const Pose &pose, const traffic_simulator_msgs::msg::MiscObjectParameters &parameters, const std::string &model3d="")
 
bool despawn (const std::string &name)
 
bool despawnEntities ()
 
auto respawn (const std::string &name, const geometry_msgs::msg::PoseWithCovarianceStamped &new_pose, const geometry_msgs::msg::PoseStamped &goal_pose) -> void
 
auto setEntityStatus (const std::string &name, const CanonicalizedEntityStatus &) -> void
 
auto setEntityStatus (const std::string &name, const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::ActionStatus &action_status=helper::constructActionStatus()) -> void
 
auto setEntityStatus (const std::string &name, const CanonicalizedLaneletPose &lanelet_pose, const traffic_simulator_msgs::msg::ActionStatus &action_status=helper::constructActionStatus()) -> void
 
auto setEntityStatus (const std::string &name, const std::string &reference_entity_name, const geometry_msgs::msg::Pose &relative_pose, const traffic_simulator_msgs::msg::ActionStatus &action_status=helper::constructActionStatus()) -> void
 
auto setEntityStatus (const std::string &name, const std::string &reference_entity_name, const geometry_msgs::msg::Point &relative_position, const geometry_msgs::msg::Vector3 &relative_rpy, const traffic_simulator_msgs::msg::ActionStatus &action_status=helper::constructActionStatus()) -> void
 
std::optional< double > getTimeHeadway (const std::string &from, const std::string &to)
 
bool attachPseudoTrafficLightDetector (const simulation_api_schema::PseudoTrafficLightDetectorConfiguration &)
 
bool attachLidarSensor (const simulation_api_schema::LidarConfiguration &)
 
bool attachLidarSensor (const std::string &, const double lidar_sensor_delay, const helper::LidarType=helper::LidarType::VLP16)
 
bool attachDetectionSensor (const simulation_api_schema::DetectionSensorConfiguration &)
 
bool attachDetectionSensor (const std::string &, double detection_sensor_range, bool detect_all_objects_in_range, double pos_noise_stddev, int random_seed, double probability_of_lost, double object_recognition_delay)
 
bool attachOccupancyGridSensor (const simulation_api_schema::OccupancyGridSensorConfiguration &)
 
bool updateFrame ()
 
double getCurrentTime () const noexcept
 
void startNpcLogic ()
 
void requestLaneChange (const std::string &name, const lanelet::Id &lanelet_id)
 
void requestLaneChange (const std::string &name, const lane_change::Direction &direction)
 
void requestLaneChange (const std::string &name, const lane_change::Parameter &)
 
void requestLaneChange (const std::string &name, const lane_change::RelativeTarget &target, const lane_change::TrajectoryShape trajectory_shape, const lane_change::Constraint &constraint)
 
void requestLaneChange (const std::string &name, const lane_change::AbsoluteTarget &target, const lane_change::TrajectoryShape trajectory_shape, const lane_change::Constraint &constraint)
 
template<typename... Ts>
decltype(auto) activateOutOfRangeJob (Ts &&... xs)
 Forward to arguments to the EntityManager:: activateOutOfRangeJob function. More...
 
template<typename... Ts>
decltype(auto) asFieldOperatorApplication (Ts &&... xs)
 Forward to arguments to the EntityManager:: asFieldOperatorApplication function. More...
 
template<typename... Ts>
decltype(auto) cancelRequest (Ts &&... xs)
 Forward to arguments to the EntityManager:: cancelRequest function. More...
 
template<typename... Ts>
decltype(auto) checkCollision (Ts &&... xs)
 Forward to arguments to the EntityManager:: checkCollision function. More...
 
template<typename... Ts>
decltype(auto) entityExists (Ts &&... xs)
 Forward to arguments to the EntityManager:: entityExists function. More...
 
template<typename... Ts>
decltype(auto) getBehaviorParameter (Ts &&... xs)
 Forward to arguments to the EntityManager:: getBehaviorParameter function. More...
 
template<typename... Ts>
decltype(auto) getBoundingBox (Ts &&... xs)
 Forward to arguments to the EntityManager:: getBoundingBox function. More...
 
template<typename... Ts>
decltype(auto) getBoundingBoxDistance (Ts &&... xs)
 Forward to arguments to the EntityManager:: getBoundingBoxDistance function. More...
 
template<typename... Ts>
decltype(auto) getBoundingBoxLaneLateralDistance (Ts &&... xs)
 Forward to arguments to the EntityManager:: getBoundingBoxLaneLateralDistance function. More...
 
template<typename... Ts>
decltype(auto) getBoundingBoxLaneLongitudinalDistance (Ts &&... xs)
 Forward to arguments to the EntityManager:: getBoundingBoxLaneLongitudinalDistance function. More...
 
template<typename... Ts>
decltype(auto) getBoundingBoxRelativePose (Ts &&... xs)
 Forward to arguments to the EntityManager:: getBoundingBoxRelativePose function. More...
 
template<typename... Ts>
decltype(auto) getConventionalTrafficLight (Ts &&... xs)
 Forward to arguments to the EntityManager:: getConventionalTrafficLight function. More...
 
template<typename... Ts>
decltype(auto) getConventionalTrafficLights (Ts &&... xs)
 Forward to arguments to the EntityManager:: getConventionalTrafficLights function. More...
 
template<typename... Ts>
decltype(auto) getCurrentAccel (Ts &&... xs)
 Forward to arguments to the EntityManager:: getCurrentAccel function. More...
 
template<typename... Ts>
decltype(auto) getCurrentAction (Ts &&... xs)
 Forward to arguments to the EntityManager:: getCurrentAction function. More...
 
template<typename... Ts>
decltype(auto) getCurrentTwist (Ts &&... xs)
 Forward to arguments to the EntityManager:: getCurrentTwist function. More...
 
template<typename... Ts>
decltype(auto) getDistanceToLaneBound (Ts &&... xs)
 Forward to arguments to the EntityManager:: getDistanceToLaneBound function. More...
 
template<typename... Ts>
decltype(auto) getDistanceToLeftLaneBound (Ts &&... xs)
 Forward to arguments to the EntityManager:: getDistanceToLeftLaneBound function. More...
 
template<typename... Ts>
decltype(auto) getDistanceToRightLaneBound (Ts &&... xs)
 Forward to arguments to the EntityManager:: getDistanceToRightLaneBound function. More...
 
template<typename... Ts>
decltype(auto) getEgoName (Ts &&... xs)
 Forward to arguments to the EntityManager:: getEgoName function. More...
 
template<typename... Ts>
decltype(auto) getEntityNames (Ts &&... xs)
 Forward to arguments to the EntityManager:: getEntityNames function. More...
 
template<typename... Ts>
decltype(auto) getEntityStatus (Ts &&... xs)
 Forward to arguments to the EntityManager:: getEntityStatus function. More...
 
template<typename... Ts>
decltype(auto) getEntityStatusBeforeUpdate (Ts &&... xs)
 Forward to arguments to the EntityManager:: getEntityStatusBeforeUpdate function. More...
 
template<typename... Ts>
decltype(auto) getLaneletLength (Ts &&... xs)
 Forward to arguments to the EntityManager:: getLaneletLength function. More...
 
template<typename... Ts>
decltype(auto) getLaneletPose (Ts &&... xs)
 Forward to arguments to the EntityManager:: getLaneletPose function. More...
 
template<typename... Ts>
decltype(auto) getLateralDistance (Ts &&... xs)
 Forward to arguments to the EntityManager:: getLateralDistance function. More...
 
template<typename... Ts>
decltype(auto) getLinearJerk (Ts &&... xs)
 Forward to arguments to the EntityManager:: getLinearJerk function. More...
 
template<typename... Ts>
decltype(auto) getLongitudinalDistance (Ts &&... xs)
 Forward to arguments to the EntityManager:: getLongitudinalDistance function. More...
 
template<typename... Ts>
decltype(auto) getMapPose (Ts &&... xs)
 Forward to arguments to the EntityManager:: getMapPose function. More...
 
template<typename... Ts>
decltype(auto) getMapPoseFromRelativePose (Ts &&... xs)
 Forward to arguments to the EntityManager:: getMapPoseFromRelativePose function. More...
 
template<typename... Ts>
decltype(auto) getRelativePose (Ts &&... xs)
 Forward to arguments to the EntityManager:: getRelativePose function. More...
 
template<typename... Ts>
decltype(auto) getStandStillDuration (Ts &&... xs)
 Forward to arguments to the EntityManager:: getStandStillDuration function. More...
 
template<typename... Ts>
decltype(auto) getTraveledDistance (Ts &&... xs)
 Forward to arguments to the EntityManager:: getTraveledDistance function. More...
 
template<typename... Ts>
decltype(auto) getV2ITrafficLight (Ts &&... xs)
 Forward to arguments to the EntityManager:: getV2ITrafficLight function. More...
 
template<typename... Ts>
decltype(auto) getV2ITrafficLights (Ts &&... xs)
 Forward to arguments to the EntityManager:: getV2ITrafficLights function. More...
 
template<typename... Ts>
decltype(auto) isEgoSpawned (Ts &&... xs)
 Forward to arguments to the EntityManager:: isEgoSpawned function. More...
 
template<typename... Ts>
decltype(auto) isInLanelet (Ts &&... xs)
 Forward to arguments to the EntityManager:: isInLanelet function. More...
 
template<typename... Ts>
decltype(auto) isNpcLogicStarted (Ts &&... xs)
 Forward to arguments to the EntityManager:: isNpcLogicStarted function. More...
 
template<typename... Ts>
decltype(auto) laneMatchingSucceed (Ts &&... xs)
 Forward to arguments to the EntityManager:: laneMatchingSucceed function. More...
 
template<typename... Ts>
decltype(auto) reachPosition (Ts &&... xs)
 Forward to arguments to the EntityManager:: reachPosition function. More...
 
template<typename... Ts>
decltype(auto) requestAcquirePosition (Ts &&... xs)
 Forward to arguments to the EntityManager:: requestAcquirePosition function. More...
 
template<typename... Ts>
decltype(auto) requestAssignRoute (Ts &&... xs)
 Forward to arguments to the EntityManager:: requestAssignRoute function. More...
 
template<typename... Ts>
decltype(auto) requestFollowTrajectory (Ts &&... xs)
 Forward to arguments to the EntityManager:: requestFollowTrajectory function. More...
 
template<typename... Ts>
decltype(auto) requestSpeedChange (Ts &&... xs)
 Forward to arguments to the EntityManager:: requestSpeedChange function. More...
 
template<typename... Ts>
decltype(auto) requestWalkStraight (Ts &&... xs)
 Forward to arguments to the EntityManager:: requestWalkStraight function. More...
 
template<typename... Ts>
decltype(auto) resetBehaviorPlugin (Ts &&... xs)
 Forward to arguments to the EntityManager:: resetBehaviorPlugin function. More...
 
template<typename... Ts>
decltype(auto) resetConventionalTrafficLightPublishRate (Ts &&... xs)
 Forward to arguments to the EntityManager:: resetConventionalTrafficLightPublishRate function. More...
 
template<typename... Ts>
decltype(auto) resetV2ITrafficLightPublishRate (Ts &&... xs)
 Forward to arguments to the EntityManager:: resetV2ITrafficLightPublishRate function. More...
 
template<typename... Ts>
decltype(auto) setAcceleration (Ts &&... xs)
 Forward to arguments to the EntityManager:: setAcceleration function. More...
 
template<typename... Ts>
decltype(auto) setAccelerationLimit (Ts &&... xs)
 Forward to arguments to the EntityManager:: setAccelerationLimit function. More...
 
template<typename... Ts>
decltype(auto) setAccelerationRateLimit (Ts &&... xs)
 Forward to arguments to the EntityManager:: setAccelerationRateLimit function. More...
 
template<typename... Ts>
decltype(auto) setBehaviorParameter (Ts &&... xs)
 Forward to arguments to the EntityManager:: setBehaviorParameter function. More...
 
template<typename... Ts>
decltype(auto) setConventionalTrafficLightConfidence (Ts &&... xs)
 Forward to arguments to the EntityManager:: setConventionalTrafficLightConfidence function. More...
 
template<typename... Ts>
decltype(auto) setDecelerationLimit (Ts &&... xs)
 Forward to arguments to the EntityManager:: setDecelerationLimit function. More...
 
template<typename... Ts>
decltype(auto) setDecelerationRateLimit (Ts &&... xs)
 Forward to arguments to the EntityManager:: setDecelerationRateLimit function. More...
 
template<typename... Ts>
decltype(auto) setLinearVelocity (Ts &&... xs)
 Forward to arguments to the EntityManager:: setLinearVelocity function. More...
 
template<typename... Ts>
decltype(auto) setMapPose (Ts &&... xs)
 Forward to arguments to the EntityManager:: setMapPose function. More...
 
template<typename... Ts>
decltype(auto) setTwist (Ts &&... xs)
 Forward to arguments to the EntityManager:: setTwist function. More...
 
template<typename... Ts>
decltype(auto) setVelocityLimit (Ts &&... xs)
 Forward to arguments to the EntityManager:: setVelocityLimit function. More...
 
template<typename... Ts>
decltype(auto) toMapPose (Ts &&... xs)
 Forward to arguments to the EntityManager:: toMapPose function. More...
 
auto canonicalize (const LaneletPose &maybe_non_canonicalized_lanelet_pose) const -> CanonicalizedLaneletPose
 
auto canonicalize (const EntityStatus &may_non_canonicalized_entity_status) const -> CanonicalizedEntityStatus
 
auto toLaneletPose (const geometry_msgs::msg::Pose &map_pose, bool include_crosswalk) const -> std::optional< CanonicalizedLaneletPose >
 

Constructor & Destructor Documentation

◆ API()

template<typename NodeT , typename AllocatorT = std::allocator<void>, typename... Ts>
traffic_simulator::API::API ( NodeT &&  node,
const Configuration configuration,
Ts &&...  xs 
)
inlineexplicit

Member Function Documentation

◆ activateOutOfRangeJob()

template<typename... Ts>
decltype(auto) traffic_simulator::API::activateOutOfRangeJob ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: activateOutOfRangeJob function.

Returns
return value of the EntityManager:: activateOutOfRangeJob function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ asFieldOperatorApplication()

template<typename... Ts>
decltype(auto) traffic_simulator::API::asFieldOperatorApplication ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: asFieldOperatorApplication function.

Returns
return value of the EntityManager:: asFieldOperatorApplication function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ attachDetectionSensor() [1/2]

bool traffic_simulator::API::attachDetectionSensor ( const simulation_api_schema::DetectionSensorConfiguration &  sensor_configuration)

◆ attachDetectionSensor() [2/2]

bool traffic_simulator::API::attachDetectionSensor ( const std::string &  entity_name,
double  detection_sensor_range,
bool  detect_all_objects_in_range,
double  pos_noise_stddev,
int  random_seed,
double  probability_of_lost,
double  object_recognition_delay 
)

◆ attachLidarSensor() [1/2]

bool traffic_simulator::API::attachLidarSensor ( const simulation_api_schema::LidarConfiguration &  lidar_configuration)

◆ attachLidarSensor() [2/2]

bool traffic_simulator::API::attachLidarSensor ( const std::string &  entity_name,
const double  lidar_sensor_delay,
const helper::LidarType  lidar_type = helper::LidarType::VLP16 
)

◆ attachOccupancyGridSensor()

bool traffic_simulator::API::attachOccupancyGridSensor ( const simulation_api_schema::OccupancyGridSensorConfiguration &  sensor_configuration)

◆ attachPseudoTrafficLightDetector()

bool traffic_simulator::API::attachPseudoTrafficLightDetector ( const simulation_api_schema::PseudoTrafficLightDetectorConfiguration &  configuration)

◆ cancelRequest()

template<typename... Ts>
decltype(auto) traffic_simulator::API::cancelRequest ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: cancelRequest function.

Returns
return value of the EntityManager:: cancelRequest function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ canonicalize() [1/2]

auto traffic_simulator::API::canonicalize ( const EntityStatus may_non_canonicalized_entity_status) const -> CanonicalizedEntityStatus

◆ canonicalize() [2/2]

auto traffic_simulator::API::canonicalize ( const LaneletPose maybe_non_canonicalized_lanelet_pose) const -> CanonicalizedLaneletPose

◆ checkCollision()

template<typename... Ts>
decltype(auto) traffic_simulator::API::checkCollision ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: checkCollision function.

Returns
return value of the EntityManager:: checkCollision function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ closeZMQConnection()

void traffic_simulator::API::closeZMQConnection ( )
inline

◆ despawn()

bool traffic_simulator::API::despawn ( const std::string &  name)

◆ despawnEntities()

bool traffic_simulator::API::despawnEntities ( )

◆ entityExists()

template<typename... Ts>
decltype(auto) traffic_simulator::API::entityExists ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: entityExists function.

Returns
return value of the EntityManager:: entityExists function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getBehaviorParameter()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getBehaviorParameter ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getBehaviorParameter function.

Returns
return value of the EntityManager:: getBehaviorParameter function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getBoundingBox()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getBoundingBox ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getBoundingBox function.

Returns
return value of the EntityManager:: getBoundingBox function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getBoundingBoxDistance()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getBoundingBoxDistance ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getBoundingBoxDistance function.

Returns
return value of the EntityManager:: getBoundingBoxDistance function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getBoundingBoxLaneLateralDistance()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getBoundingBoxLaneLateralDistance ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getBoundingBoxLaneLateralDistance function.

Returns
return value of the EntityManager:: getBoundingBoxLaneLateralDistance function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getBoundingBoxLaneLongitudinalDistance()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getBoundingBoxLaneLongitudinalDistance ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getBoundingBoxLaneLongitudinalDistance function.

Returns
return value of the EntityManager:: getBoundingBoxLaneLongitudinalDistance function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getBoundingBoxRelativePose()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getBoundingBoxRelativePose ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getBoundingBoxRelativePose function.

Returns
return value of the EntityManager:: getBoundingBoxRelativePose function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getConventionalTrafficLight()

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

Forward to arguments to the EntityManager:: getConventionalTrafficLight function.

Returns
return value of the EntityManager:: getConventionalTrafficLight function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getConventionalTrafficLights()

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

Forward to arguments to the EntityManager:: getConventionalTrafficLights function.

Returns
return value of the EntityManager:: getConventionalTrafficLights function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getCurrentAccel()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getCurrentAccel ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getCurrentAccel function.

Returns
return value of the EntityManager:: getCurrentAccel function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getCurrentAction()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getCurrentAction ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getCurrentAction function.

Returns
return value of the EntityManager:: getCurrentAction function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getCurrentTime()

double traffic_simulator::API::getCurrentTime ( ) const
inlinenoexcept

◆ getCurrentTwist()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getCurrentTwist ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getCurrentTwist function.

Returns
return value of the EntityManager:: getCurrentTwist function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getDistanceToLaneBound()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getDistanceToLaneBound ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getDistanceToLaneBound function.

Returns
return value of the EntityManager:: getDistanceToLaneBound function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getDistanceToLeftLaneBound()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getDistanceToLeftLaneBound ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getDistanceToLeftLaneBound function.

Returns
return value of the EntityManager:: getDistanceToLeftLaneBound function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getDistanceToRightLaneBound()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getDistanceToRightLaneBound ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getDistanceToRightLaneBound function.

Returns
return value of the EntityManager:: getDistanceToRightLaneBound function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getEgoName()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getEgoName ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getEgoName function.

Returns
return value of the EntityManager:: getEgoName function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getEntityNames()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getEntityNames ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getEntityNames function.

Returns
return value of the EntityManager:: getEntityNames function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getEntityStatus()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getEntityStatus ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getEntityStatus function.

Returns
return value of the EntityManager:: getEntityStatus function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getEntityStatusBeforeUpdate()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getEntityStatusBeforeUpdate ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getEntityStatusBeforeUpdate function.

Returns
return value of the EntityManager:: getEntityStatusBeforeUpdate function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getLaneletLength()

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

Forward to arguments to the EntityManager:: getLaneletLength function.

Returns
return value of the EntityManager:: getLaneletLength function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getLaneletPose()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getLaneletPose ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getLaneletPose function.

Returns
return value of the EntityManager:: getLaneletPose function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getLateralDistance()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getLateralDistance ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getLateralDistance function.

Returns
return value of the EntityManager:: getLateralDistance function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getLinearJerk()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getLinearJerk ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getLinearJerk function.

Returns
return value of the EntityManager:: getLinearJerk function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getLongitudinalDistance()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getLongitudinalDistance ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getLongitudinalDistance function.

Returns
return value of the EntityManager:: getLongitudinalDistance function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getMapPose()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getMapPose ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getMapPose function.

Returns
return value of the EntityManager:: getMapPose function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getMapPoseFromRelativePose()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getMapPoseFromRelativePose ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getMapPoseFromRelativePose function.

Returns
return value of the EntityManager:: getMapPoseFromRelativePose function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getRelativePose()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getRelativePose ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getRelativePose function.

Returns
return value of the EntityManager:: getRelativePose function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getStandStillDuration()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getStandStillDuration ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getStandStillDuration function.

Returns
return value of the EntityManager:: getStandStillDuration function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getTimeHeadway()

std::optional< double > traffic_simulator::API::getTimeHeadway ( const std::string &  from,
const std::string &  to 
)

◆ getTraveledDistance()

template<typename... Ts>
decltype(auto) traffic_simulator::API::getTraveledDistance ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: getTraveledDistance function.

Returns
return value of the EntityManager:: getTraveledDistance function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getV2ITrafficLight()

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

Forward to arguments to the EntityManager:: getV2ITrafficLight function.

Returns
return value of the EntityManager:: getV2ITrafficLight function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getV2ITrafficLights()

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

Forward to arguments to the EntityManager:: getV2ITrafficLights function.

Returns
return value of the EntityManager:: getV2ITrafficLights function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ getZMQSocketPort()

template<typename Node >
int traffic_simulator::API::getZMQSocketPort ( Node &  node)
inline

◆ isEgoSpawned()

template<typename... Ts>
decltype(auto) traffic_simulator::API::isEgoSpawned ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: isEgoSpawned function.

Returns
return value of the EntityManager:: isEgoSpawned function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ isInLanelet()

template<typename... Ts>
decltype(auto) traffic_simulator::API::isInLanelet ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: isInLanelet function.

Returns
return value of the EntityManager:: isInLanelet function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ isNpcLogicStarted()

template<typename... Ts>
decltype(auto) traffic_simulator::API::isNpcLogicStarted ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: isNpcLogicStarted function.

Returns
return value of the EntityManager:: isNpcLogicStarted function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ laneMatchingSucceed()

template<typename... Ts>
decltype(auto) traffic_simulator::API::laneMatchingSucceed ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: laneMatchingSucceed function.

Returns
return value of the EntityManager:: laneMatchingSucceed function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ reachPosition()

template<typename... Ts>
decltype(auto) traffic_simulator::API::reachPosition ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: reachPosition function.

Returns
return value of the EntityManager:: reachPosition function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ requestAcquirePosition()

template<typename... Ts>
decltype(auto) traffic_simulator::API::requestAcquirePosition ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: requestAcquirePosition function.

Returns
return value of the EntityManager:: requestAcquirePosition function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ requestAssignRoute()

template<typename... Ts>
decltype(auto) traffic_simulator::API::requestAssignRoute ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: requestAssignRoute function.

Returns
return value of the EntityManager:: requestAssignRoute function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ requestFollowTrajectory()

template<typename... Ts>
decltype(auto) traffic_simulator::API::requestFollowTrajectory ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: requestFollowTrajectory function.

Returns
return value of the EntityManager:: requestFollowTrajectory function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ requestLaneChange() [1/5]

void traffic_simulator::API::requestLaneChange ( const std::string &  name,
const lane_change::AbsoluteTarget target,
const lane_change::TrajectoryShape  trajectory_shape,
const lane_change::Constraint constraint 
)

◆ requestLaneChange() [2/5]

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

◆ requestLaneChange() [3/5]

void traffic_simulator::API::requestLaneChange ( const std::string &  name,
const lane_change::Parameter parameter 
)

◆ requestLaneChange() [4/5]

void traffic_simulator::API::requestLaneChange ( const std::string &  name,
const lane_change::RelativeTarget target,
const lane_change::TrajectoryShape  trajectory_shape,
const lane_change::Constraint constraint 
)

◆ requestLaneChange() [5/5]

void traffic_simulator::API::requestLaneChange ( const std::string &  name,
const lanelet::Id &  lanelet_id 
)

◆ requestSpeedChange()

template<typename... Ts>
decltype(auto) traffic_simulator::API::requestSpeedChange ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: requestSpeedChange function.

Returns
return value of the EntityManager:: requestSpeedChange function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ requestWalkStraight()

template<typename... Ts>
decltype(auto) traffic_simulator::API::requestWalkStraight ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: requestWalkStraight function.

Returns
return value of the EntityManager:: requestWalkStraight function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ resetBehaviorPlugin()

template<typename... Ts>
decltype(auto) traffic_simulator::API::resetBehaviorPlugin ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: resetBehaviorPlugin function.

Returns
return value of the EntityManager:: resetBehaviorPlugin function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ resetConventionalTrafficLightPublishRate()

template<typename... Ts>
decltype(auto) traffic_simulator::API::resetConventionalTrafficLightPublishRate ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: resetConventionalTrafficLightPublishRate function.

Returns
return value of the EntityManager:: resetConventionalTrafficLightPublishRate function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ resetV2ITrafficLightPublishRate()

template<typename... Ts>
decltype(auto) traffic_simulator::API::resetV2ITrafficLightPublishRate ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: resetV2ITrafficLightPublishRate function.

Returns
return value of the EntityManager:: resetV2ITrafficLightPublishRate function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ respawn()

auto traffic_simulator::API::respawn ( const std::string &  name,
const geometry_msgs::msg::PoseWithCovarianceStamped &  new_pose,
const geometry_msgs::msg::PoseStamped &  goal_pose 
) -> void

◆ setAcceleration()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setAcceleration ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setAcceleration function.

Returns
return value of the EntityManager:: setAcceleration function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setAccelerationLimit()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setAccelerationLimit ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setAccelerationLimit function.

Returns
return value of the EntityManager:: setAccelerationLimit function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setAccelerationRateLimit()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setAccelerationRateLimit ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setAccelerationRateLimit function.

Returns
return value of the EntityManager:: setAccelerationRateLimit function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setBehaviorParameter()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setBehaviorParameter ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setBehaviorParameter function.

Returns
return value of the EntityManager:: setBehaviorParameter function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setConventionalTrafficLightConfidence()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setConventionalTrafficLightConfidence ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setConventionalTrafficLightConfidence function.

Returns
return value of the EntityManager:: setConventionalTrafficLightConfidence function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setDecelerationLimit()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setDecelerationLimit ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setDecelerationLimit function.

Returns
return value of the EntityManager:: setDecelerationLimit function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setDecelerationRateLimit()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setDecelerationRateLimit ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setDecelerationRateLimit function.

Returns
return value of the EntityManager:: setDecelerationRateLimit function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setEntityStatus() [1/5]

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

◆ setEntityStatus() [2/5]

auto traffic_simulator::API::setEntityStatus ( const std::string &  name,
const CanonicalizedLaneletPose lanelet_pose,
const traffic_simulator_msgs::msg::ActionStatus &  action_status = helper::constructActionStatus() 
) -> void

◆ setEntityStatus() [3/5]

auto traffic_simulator::API::setEntityStatus ( const std::string &  name,
const geometry_msgs::msg::Pose &  map_pose,
const traffic_simulator_msgs::msg::ActionStatus &  action_status = helper::constructActionStatus() 
) -> void

◆ setEntityStatus() [4/5]

auto traffic_simulator::API::setEntityStatus ( const std::string &  name,
const std::string &  reference_entity_name,
const geometry_msgs::msg::Point &  relative_position,
const geometry_msgs::msg::Vector3 &  relative_rpy,
const traffic_simulator_msgs::msg::ActionStatus &  action_status = helper::constructActionStatus() 
) -> void

◆ setEntityStatus() [5/5]

auto traffic_simulator::API::setEntityStatus ( const std::string &  name,
const std::string &  reference_entity_name,
const geometry_msgs::msg::Pose &  relative_pose,
const traffic_simulator_msgs::msg::ActionStatus &  action_status = helper::constructActionStatus() 
) -> void

◆ setLinearVelocity()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setLinearVelocity ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setLinearVelocity function.

Returns
return value of the EntityManager:: setLinearVelocity function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setMapPose()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setMapPose ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setMapPose function.

Returns
return value of the EntityManager:: setMapPose function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setTwist()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setTwist ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setTwist function.

Returns
return value of the EntityManager:: setTwist function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setVelocityLimit()

template<typename... Ts>
decltype(auto) traffic_simulator::API::setVelocityLimit ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: setVelocityLimit function.

Returns
return value of the EntityManager:: setVelocityLimit function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ setVerbose()

void traffic_simulator::API::setVerbose ( const bool  verbose)

◆ spawn() [1/3]

template<typename Pose >
auto traffic_simulator::API::spawn ( const std::string &  name,
const Pose &  pose,
const traffic_simulator_msgs::msg::MiscObjectParameters &  parameters,
const std::string &  model3d = "" 
)
inline

◆ spawn() [2/3]

template<typename Pose >
auto traffic_simulator::API::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 = "" 
)
inline

◆ spawn() [3/3]

template<typename Pose >
auto traffic_simulator::API::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 = "" 
)
inline
Todo:
Should be filled from function API

◆ startNpcLogic()

void traffic_simulator::API::startNpcLogic ( )

◆ toLaneletPose()

auto traffic_simulator::API::toLaneletPose ( const geometry_msgs::msg::Pose &  map_pose,
bool  include_crosswalk 
) const -> std::optional<CanonicalizedLaneletPose>

◆ toMapPose() [1/3]

geometry_msgs::msg::Pose traffic_simulator::API::toMapPose ( const geometry_msgs::msg::Pose &  pose)
inline

◆ toMapPose() [2/3]

geometry_msgs::msg::Pose traffic_simulator::API::toMapPose ( const traffic_simulator_msgs::msg::LaneletPose &  pose)
inline

◆ toMapPose() [3/3]

template<typename... Ts>
decltype(auto) traffic_simulator::API::toMapPose ( Ts &&...  xs)
inline

Forward to arguments to the EntityManager:: toMapPose function.

Returns
return value of the EntityManager:: toMapPose function.
Note
This function was defined by FORWARD_TO_ENTITY_MANAGER macro.

◆ updateFrame()

bool traffic_simulator::API::updateFrame ( )

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