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 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 &parameters, 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 &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 ()
 
bool checkCollision (const std::string &first_entity_name, const std::string &second_entity_name)
 
auto respawn (const std::string &name, const geometry_msgs::msg::PoseWithCovarianceStamped &new_pose, const geometry_msgs::msg::PoseStamped &goal_pose) -> void
 
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 ()
 
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) -> entity::EntityBase &
 
auto getEntity (const std::string &name) const -> const entity::EntityBase &
 
template<typename... Ts>
decltype(auto) getEgoEntity (Ts &&... xs)
 Forward to arguments to the EntityManager:: getEgoEntity function. More...
 
template<typename... Ts>
decltype(auto) getEntityNames (Ts &&... xs)
 Forward to arguments to the EntityManager:: getEntityNames function. More...
 
template<typename... Ts>
decltype(auto) getEntityPointer (Ts &&... xs)
 Forward to arguments to the EntityManager:: getEntityPointer function. More...
 
template<typename... Ts>
decltype(auto) getFirstEgoName (Ts &&... xs)
 Forward to arguments to the EntityManager:: getFirstEgoName function. More...
 
template<typename... Ts>
decltype(auto) getHdmapUtils (Ts &&... xs)
 Forward to arguments to the EntityManager:: getHdmapUtils function. More...
 
template<typename... Ts>
decltype(auto) isEntityExist (Ts &&... xs)
 Forward to arguments to the EntityManager:: isEntityExist function. More...
 
template<typename... Ts>
decltype(auto) isNpcLogicStarted (Ts &&... xs)
 Forward to arguments to the EntityManager:: isNpcLogicStarted function. More...
 
template<typename... Ts>
decltype(auto) resetBehaviorPlugin (Ts &&... xs)
 Forward to arguments to the EntityManager:: resetBehaviorPlugin function. More...
 

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

◆ addTrafficSource()

auto traffic_simulator::API::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.

Parameters
radiusThe radius defining the area on which entities will be spawned
rateThe rate at which entities will be spawned [Hz]
speedThe speed of the spawned entities
positionThe center of the area on which entities will be spawned (includes orientation)
distributionThe parameters of the spawned entities with their respective weights for random distribution For each entity there are 4 parameters in a tuple:
  • VehicleParameters or PedestrianParameters - parameters of entity
  • std::string - name of behavior to be used when spawning
  • std::string - name of 3D model to be used when spawning
  • double - weight of entity for random distribution
allow_spawn_outside_laneWhether entities can be spawned outside the lane
require_footprint_fittingWhether entities are required to fit inside lanelet polygon when spawned (allow_spawn_outside_lane has higher priority)
random_orientationWhether entities should have their orientation randomized before lane matching
random_seed[Optional] The seed for the random number generator

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

◆ attachImuSensor()

auto traffic_simulator::API::attachImuSensor ( const std::string &  ,
const simulation_api_schema::ImuSensorConfiguration &  configuration 
) -> bool

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

◆ checkCollision()

bool traffic_simulator::API::checkCollision ( const std::string &  first_entity_name,
const std::string &  second_entity_name 
)

◆ closeZMQConnection()

void traffic_simulator::API::closeZMQConnection ( )
inline

◆ despawn()

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

◆ despawnEntities()

bool traffic_simulator::API::despawnEntities ( )

◆ getConventionalTrafficLights()

auto traffic_simulator::API::getConventionalTrafficLights ( )
inline

◆ getCurrentTime()

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

◆ getEgoEntity()

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

Forward to arguments to the EntityManager:: getEgoEntity function.

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

◆ getEntity() [1/2]

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

◆ getEntity() [2/2]

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

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

◆ getEntityPointer()

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

Forward to arguments to the EntityManager:: getEntityPointer function.

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

◆ getFirstEgoName()

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

Forward to arguments to the EntityManager:: getFirstEgoName function.

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

◆ getHdmapUtils()

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

Forward to arguments to the EntityManager:: getHdmapUtils function.

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

◆ getROS2Parameter()

template<typename ParameterT , typename... Ts>
auto traffic_simulator::API::getROS2Parameter ( Ts &&...  xs) const -> decltype(auto)
inline

◆ getV2ITrafficLights()

auto traffic_simulator::API::getV2ITrafficLights ( )
inline

◆ getZMQSocketPort()

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

◆ isEntityExist()

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

Forward to arguments to the EntityManager:: isEntityExist function.

Returns
return value of the EntityManager:: isEntityExist 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.

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

◆ 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

◆ 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 ( )

◆ updateFrame()

bool traffic_simulator::API::updateFrame ( )

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