scenario_simulator_v2 C++ API
Namespaces | Classes | Typedefs | Enumerations | Functions
traffic_simulator Namespace Reference

Namespaces

 behavior
 
 distance
 
 entity
 
 entity_status
 
 follow_trajectory
 
 helper
 
 job
 
 lane_change
 
 lanelet_map
 
 lanelet_pose
 
 lanelet_wrapper
 
 longitudinal_speed_planning
 
 pedestrian
 
 pose
 
 route
 
 routing_graph_type
 
 speed_change
 
 traffic
 

Classes

struct  VehicleBehavior
 
struct  PedestrianBehavior
 
class  API
 
struct  Configuration
 
class  RoutePlanner
 
struct  RoutingConfiguration
 
class  SimulationClock
 
class  ConfigurableRateUpdater
 
struct  TrafficLight
 
class  TrafficLightMarkerPublisher
 
class  TrafficLightPublisherBase
 
class  TrafficLightPublisher
 
class  ConventionalTrafficLights
 
class  V2ITrafficLights
 
class  TrafficLights
 
class  TrafficLightsBase
 
class  VisualizationComponent
 ROS 2 component for visualizing simulation result. More...
 
class  CanonicalizedEntityStatus
 
class  CanonicalizedLaneletPose
 

Typedefs

using EntityStatus = traffic_simulator_msgs::msg::EntityStatus
 
using EntityType = traffic_simulator_msgs::msg::EntityType
 
using EntitySubtype = traffic_simulator_msgs::msg::EntitySubtype
 
using LaneletPose = traffic_simulator_msgs::msg::LaneletPose
 
using Point = geometry_msgs::msg::Point
 
using Pose = geometry_msgs::msg::Pose
 

Enumerations

enum class  RoutingGraphType : std::uint8_t { VEHICLE , PEDESTRIAN , VEHICLE_WITH_ROAD_SHOULDER }
 

Functions

auto isSameLaneletId (const CanonicalizedEntityStatus &first_status, const CanonicalizedEntityStatus &second_status) -> bool
 
auto isSameLaneletId (const CanonicalizedEntityStatus &status, const lanelet::Id lanelet_id) -> bool
 
auto isSameLaneletId (const CanonicalizedLaneletPose &, const CanonicalizedLaneletPose &) -> bool
 
auto isSameLaneletId (const CanonicalizedLaneletPose &, const lanelet::Id lanelet_id) -> bool
 
char const * to_string (const RoutingGraphType &)
 
auto lateralDistance (const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const traffic_simulator::RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< double >
 
auto lateralDistance (const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, double matching_distance, const traffic_simulator::RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< double >
 
auto countLaneChanges (const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const traffic_simulator::RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< std::pair< int, int >>
 
auto longitudinalDistance (const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, bool include_adjacent_lanelet, bool include_opposite_direction, const traffic_simulator::RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< double >
 
auto boundingBoxDistance (const geometry_msgs::msg::Pose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const geometry_msgs::msg::Pose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box) -> std::optional< double >
 
auto boundingBoxLaneLateralDistance (const CanonicalizedLaneletPose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const CanonicalizedLaneletPose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box, const traffic_simulator::RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< double >
 
auto boundingBoxLaneLongitudinalDistance (const CanonicalizedLaneletPose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const CanonicalizedLaneletPose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box, bool include_adjacent_lanelet, bool include_opposite_direction, const traffic_simulator::RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< double >
 
auto distanceToLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, lanelet::Id lanelet_id, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> double
 
auto distanceToLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Ids &lanelet_ids, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> double
 
auto distanceToLeftLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, lanelet::Id lanelet_id, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> double
 
auto distanceToLeftLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Ids &lanelet_ids, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> double
 
auto distanceToRightLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, lanelet::Id lanelet_id, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> double
 
auto distanceToRightLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Ids &lanelet_ids, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> double
 
auto distanceToCrosswalk (const traffic_simulator_msgs::msg::WaypointsArray &waypoints_array, const lanelet::Id target_crosswalk_id, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< double >
 
auto distanceToStopLine (const traffic_simulator_msgs::msg::WaypointsArray &waypoints_array, const lanelet::Id target_stop_line_id, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< double >
 
auto distanceToSpline (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const math::geometry::CatmullRomSplineInterface &spline, const double s_reference) -> double
 
template<typename... Ts>
auto activate (Ts &&... xs)
 
auto laneletLength (const lanelet::Id lanelet_id) -> double
 
template<typename... Ts>
auto laneletAltitude (Ts &&... xs)
 
auto noNextLaneletPoses () -> std::vector< std::pair< lanelet::Id, Pose >>
 Calculates all poses on the map that have no next lanelet (dead ends) More...
 
template<typename ParameterT >
auto getParameter (rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters, const std::string &name, const ParameterT &default_value={}) -> ParameterT
 
auto quietNaNPose () -> geometry_msgs::msg::Pose
 
auto quietNaNLaneletPose () -> LaneletPose
 
auto canonicalize (const LaneletPose &lanelet_pose) -> LaneletPose
 
auto canonicalize (const LaneletPose &lanelet_pose, const lanelet::Ids &route_lanelets) -> LaneletPose
 
auto toMapPose (const CanonicalizedLaneletPose &lanelet_pose) -> geometry_msgs::msg::Pose
 
auto toMapPose (const LaneletPose &lanelet_pose) -> geometry_msgs::msg::Pose
 
auto alternativeLaneletPoses (const LaneletPose &lanelet_pose) -> std::vector< LaneletPose >
 
auto toCanonicalizedLaneletPose (const LaneletPose &lanelet_pose) -> std::optional< CanonicalizedLaneletPose >
 
auto toCanonicalizedLaneletPose (const geometry_msgs::msg::Pose &map_pose, const bool include_crosswalk) -> std::optional< CanonicalizedLaneletPose >
 
auto toCanonicalizedLaneletPose (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const bool include_crosswalk, const double matching_distance) -> std::optional< CanonicalizedLaneletPose >
 
auto toCanonicalizedLaneletPose (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Ids &unique_route_lanelets, const bool include_crosswalk, const double matching_distance) -> std::optional< CanonicalizedLaneletPose >
 
auto transformRelativePoseToGlobal (const geometry_msgs::msg::Pose &global_pose, const geometry_msgs::msg::Pose &relative_pose) -> geometry_msgs::msg::Pose
 
auto updatePositionForLaneletTransition (const CanonicalizedLaneletPose &canonicalized_lanelet_pose, const lanelet::Id next_lanelet_id, const geometry_msgs::msg::Vector3 &desired_velocity, const bool desired_velocity_is_global, const double step_time) -> std::optional< geometry_msgs::msg::Point >
 
auto relativePose (const geometry_msgs::msg::Pose &from, const geometry_msgs::msg::Pose &to) -> std::optional< geometry_msgs::msg::Pose >
 
auto relativePose (const geometry_msgs::msg::Pose &from, const CanonicalizedLaneletPose &to) -> std::optional< geometry_msgs::msg::Pose >
 
auto relativePose (const CanonicalizedLaneletPose &from, const geometry_msgs::msg::Pose &to) -> std::optional< geometry_msgs::msg::Pose >
 
auto boundingBoxRelativePose (const geometry_msgs::msg::Pose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const geometry_msgs::msg::Pose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box) -> std::optional< geometry_msgs::msg::Pose >
 
auto isAltitudeMatching (const CanonicalizedLaneletPose &lanelet_pose, const CanonicalizedLaneletPose &target_lanelet_pose) -> bool
 
auto relativeLaneletPose (const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> LaneletPose
 
auto boundingBoxRelativeLaneletPose (const CanonicalizedLaneletPose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const CanonicalizedLaneletPose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box, const RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> LaneletPose
 
auto isInLanelet (const CanonicalizedLaneletPose &canonicalized_lanelet_pose, const lanelet::Id lanelet_id, const double tolerance, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> bool
 
auto isInLanelet (const geometry_msgs::msg::Point &point, const lanelet::Id lanelet_id) -> bool
 
auto isAtEndOfLanelets (const CanonicalizedLaneletPose &canonicalized_lanelet_pose, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> bool
 
auto findRoutableAlternativeLaneletPoseFrom (const lanelet::Id from_lanelet_id, const CanonicalizedLaneletPose &canonicalized_lanelet_pose, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box) -> std::optional< traffic_simulator::CanonicalizedLaneletPose >
 
template<typename... Ts>
auto route (Ts &&... xs)
 
auto operator>> (std::istream &is, TrafficLight::Color &color) -> std::istream &
 
auto operator<< (std::ostream &os, const TrafficLight::Color &color) -> std::ostream &
 
auto operator>> (std::istream &is, TrafficLight::Status &status) -> std::istream &
 
auto operator<< (std::ostream &os, const TrafficLight::Status &status) -> std::ostream &
 
auto operator>> (std::istream &is, TrafficLight::Shape &shape) -> std::istream &
 
auto operator<< (std::ostream &os, const TrafficLight::Shape &shape) -> std::ostream &
 
auto operator<< (std::ostream &os, const TrafficLight::Bulb &bulb) -> std::ostream &
 
auto operator<< (std::ostream &os, const TrafficLight &traffic_light) -> std::ostream &
 

Typedef Documentation

◆ EntityStatus

using traffic_simulator::EntityStatus = typedef traffic_simulator_msgs::msg::EntityStatus

◆ EntitySubtype

using traffic_simulator::EntitySubtype = typedef traffic_simulator_msgs::msg::EntitySubtype

◆ EntityType

using traffic_simulator::EntityType = typedef traffic_simulator_msgs::msg::EntityType

◆ LaneletPose

using traffic_simulator::LaneletPose = typedef traffic_simulator_msgs::msg::LaneletPose

Function Documentation

◆ getParameter()

template<typename ParameterT >
auto traffic_simulator::getParameter ( rclcpp::node_interfaces::NodeParametersInterface::SharedPtr  node_parameters,
const std::string &  name,
const ParameterT &  default_value = {} 
) -> ParameterT

Get parameter or declare it if it has not been declared before. Declare it with a default value.

Parameters
node_parametersThe node parameters interface pointer, it will be used to access the parameters
nameThe name of the parameter
default_valueThe default value of the parameter
Returns
The value of the parameter

◆ isSameLaneletId() [1/4]

auto traffic_simulator::isSameLaneletId ( const CanonicalizedEntityStatus first_status,
const CanonicalizedEntityStatus second_status 
) -> bool

◆ isSameLaneletId() [2/4]

auto traffic_simulator::isSameLaneletId ( const CanonicalizedEntityStatus status,
const lanelet::Id  lanelet_id 
) -> bool

◆ isSameLaneletId() [3/4]

auto traffic_simulator::isSameLaneletId ( const CanonicalizedLaneletPose p0,
const CanonicalizedLaneletPose p1 
) -> bool

◆ isSameLaneletId() [4/4]

auto traffic_simulator::isSameLaneletId ( const CanonicalizedLaneletPose p,
const lanelet::Id  lanelet_id 
) -> bool

◆ operator<<() [1/5]

auto traffic_simulator::operator<< ( std::ostream &  os,
const TrafficLight traffic_light 
) -> std::ostream &

◆ operator<<() [2/5]

auto traffic_simulator::operator<< ( std::ostream &  os,
const TrafficLight::Bulb bulb 
) -> std::ostream &

◆ operator<<() [3/5]

auto traffic_simulator::operator<< ( std::ostream &  os,
const TrafficLight::Color color 
) -> std::ostream &

◆ operator<<() [4/5]

auto traffic_simulator::operator<< ( std::ostream &  os,
const TrafficLight::Shape shape 
) -> std::ostream &

◆ operator<<() [5/5]

auto traffic_simulator::operator<< ( std::ostream &  os,
const TrafficLight::Status status 
) -> std::ostream &

◆ operator>>() [1/3]

auto traffic_simulator::operator>> ( std::istream &  is,
TrafficLight::Color color 
) -> std::istream &

◆ operator>>() [2/3]

auto traffic_simulator::operator>> ( std::istream &  is,
TrafficLight::Shape shape 
) -> std::istream &

◆ operator>>() [3/3]

auto traffic_simulator::operator>> ( std::istream &  is,
TrafficLight::Status status 
) -> std::istream &