scenario_simulator_v2 C++ API
|
#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 ¶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 () |
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... | |
|
inlineexplicit |
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.
radius | The radius defining the area on which entities will be spawned |
rate | The rate at which entities will be spawned [Hz] |
speed | The speed of the spawned entities |
position | The center of the area on which entities will be spawned (includes orientation) |
distribution | The parameters of the spawned entities with their respective weights for random distribution For each entity there are 4 parameters in a tuple:
|
allow_spawn_outside_lane | Whether entities can be spawned outside the lane |
require_footprint_fitting | Whether entities are required to fit inside lanelet polygon when spawned (allow_spawn_outside_lane has higher priority) |
random_orientation | Whether entities should have their orientation randomized before lane matching |
random_seed | [Optional] The seed for the random number generator |
bool traffic_simulator::API::attachDetectionSensor | ( | const simulation_api_schema::DetectionSensorConfiguration & | sensor_configuration | ) |
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 | ||
) |
auto traffic_simulator::API::attachImuSensor | ( | const std::string & | , |
const simulation_api_schema::ImuSensorConfiguration & | configuration | ||
) | -> bool |
bool traffic_simulator::API::attachLidarSensor | ( | const simulation_api_schema::LidarConfiguration & | lidar_configuration | ) |
bool traffic_simulator::API::attachLidarSensor | ( | const std::string & | entity_name, |
const double | lidar_sensor_delay, | ||
const helper::LidarType | lidar_type = helper::LidarType::VLP16 |
||
) |
bool traffic_simulator::API::attachOccupancyGridSensor | ( | const simulation_api_schema::OccupancyGridSensorConfiguration & | sensor_configuration | ) |
bool traffic_simulator::API::attachPseudoTrafficLightDetector | ( | const simulation_api_schema::PseudoTrafficLightDetectorConfiguration & | configuration | ) |
bool traffic_simulator::API::checkCollision | ( | const std::string & | first_entity_name, |
const std::string & | second_entity_name | ||
) |
|
inline |
bool traffic_simulator::API::despawn | ( | const std::string & | name | ) |
bool traffic_simulator::API::despawnEntities | ( | ) |
|
inline |
|
inlinenoexcept |
|
inline |
Forward to arguments to the EntityManager:: getEgoEntity function.
auto traffic_simulator::API::getEntity | ( | const std::string & | name | ) | -> entity::EntityBase & |
auto traffic_simulator::API::getEntity | ( | const std::string & | name | ) | const -> const entity::EntityBase & |
|
inline |
Forward to arguments to the EntityManager:: getEntityNames function.
|
inline |
Forward to arguments to the EntityManager:: getEntityPointer function.
|
inline |
Forward to arguments to the EntityManager:: getFirstEgoName function.
|
inline |
Forward to arguments to the EntityManager:: getHdmapUtils function.
|
inline |
|
inline |
|
inline |
|
inline |
Forward to arguments to the EntityManager:: isEntityExist function.
|
inline |
Forward to arguments to the EntityManager:: isNpcLogicStarted function.
|
inline |
Forward to arguments to the EntityManager:: resetBehaviorPlugin function.
auto traffic_simulator::API::respawn | ( | const std::string & | name, |
const geometry_msgs::msg::PoseWithCovarianceStamped & | new_pose, | ||
const geometry_msgs::msg::PoseStamped & | goal_pose | ||
) | -> void |
void traffic_simulator::API::setVerbose | ( | const bool | verbose | ) |
|
inline |
|
inline |
|
inline |
void traffic_simulator::API::startNpcLogic | ( | ) |
bool traffic_simulator::API::updateFrame | ( | ) |