|
template<typename NodeT , typename AllocatorT = std::allocator<void>, typename... Ts> |
| API (NodeT &&node, const Configuration &configuration, Ts &&... xs) |
|
template<typename ParameterT , typename... Ts> |
auto | getROS2Parameter (Ts &&... xs) const -> decltype(auto) |
|
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 ¶meters, const std::string &behavior=VehicleBehavior::defaultBehavior(), const std::string &model3d="") |
|
template<typename Pose > |
auto | spawn (const std::string &name, const Pose &pose, const traffic_simulator_msgs::msg::PedestrianParameters ¶meters, 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 ¶meters, const std::string &model3d="") |
|
bool | despawn (const std::string &name) |
|
bool | despawnEntities () |
|
auto | setEntityStatus (const std::string &name, const EntityStatus &status) -> void |
|
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 geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::ActionStatus &action_status=helper::constructActionStatus()) -> void |
|
auto | setEntityStatus (const std::string &name, const LaneletPose &lanelet_pose, const traffic_simulator_msgs::msg::ActionStatus &action_status) -> void |
|
auto | setEntityStatus (const std::string &name, const CanonicalizedLaneletPose &canonicalized_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) |
|
auto | attachImuSensor (const std::string &, const simulation_api_schema::ImuSensorConfiguration &configuration) -> bool |
|
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) |
|
auto | addTrafficSource (const double radius, const double rate, const double speed, const geometry_msgs::msg::Pose &position, const traffic::TrafficSource::Distribution &distribution, const bool allow_spawn_outside_lane=false, const bool require_footprint_fitting=false, const bool random_orientation=false, std::optional< int > random_seed=std::nullopt) -> void |
| Add a traffic source to the simulation. More...
|
|
auto | getV2ITrafficLights () |
|
auto | getConventionalTrafficLights () |
|
auto | getEntity (const std::string &name) const -> std::shared_ptr< entity::EntityBase > |
|
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) | 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) | 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) | getCanonicalizedStatusBeforeUpdate (Ts &&... xs) |
| Forward to arguments to the EntityManager:: getCanonicalizedStatusBeforeUpdate function. More...
|
|
template<typename... Ts> |
decltype(auto) | getHdmapUtils (Ts &&... xs) |
| Forward to arguments to the EntityManager:: getHdmapUtils function. More...
|
|
template<typename... Ts> |
decltype(auto) | getLinearJerk (Ts &&... xs) |
| Forward to arguments to the EntityManager:: getLinearJerk 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) | 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) | requestSynchronize (Ts &&... xs) |
| Forward to arguments to the EntityManager:: requestSynchronize function. More...
|
|
template<typename... Ts> |
decltype(auto) | requestWalkStraight (Ts &&... xs) |
| Forward to arguments to the EntityManager:: requestWalkStraight function. More...
|
|
template<typename... Ts> |
decltype(auto) | requestClearRoute (Ts &&... xs) |
| Forward to arguments to the EntityManager:: requestClearRoute function. More...
|
|
template<typename... Ts> |
decltype(auto) | resetBehaviorPlugin (Ts &&... xs) |
| Forward to arguments to the EntityManager:: resetBehaviorPlugin 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) | 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...
|
|