scenario_simulator_v2 C++ API
Namespaces | Functions
traffic_simulator::pose Namespace Reference

Namespaces

 pedestrian
 

Functions

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 >
 

Function Documentation

◆ alternativeLaneletPoses()

auto traffic_simulator::pose::alternativeLaneletPoses ( const LaneletPose lanelet_pose) -> std::vector<LaneletPose>

◆ boundingBoxRelativeLaneletPose()

auto traffic_simulator::pose::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
Todo:
HdMapUtils will be removed when lanelet_wrapper::distance is added
Note
here the s and offset are intentionally assigned independently, even if it is not possible to calculate one of them - it happens that one is sufficient
here the s and offset are intentionally assigned independently, even if it is not possible to calculate one of them - it happens that one is sufficient

◆ boundingBoxRelativePose()

auto traffic_simulator::pose::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>

◆ canonicalize() [1/2]

auto traffic_simulator::pose::canonicalize ( const LaneletPose lanelet_pose) -> LaneletPose
Note
Conversions

◆ canonicalize() [2/2]

auto traffic_simulator::pose::canonicalize ( const LaneletPose lanelet_pose,
const lanelet::Ids &  route_lanelets 
) -> LaneletPose

◆ findRoutableAlternativeLaneletPoseFrom()

auto traffic_simulator::pose::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>
Note
search_distance should be minimal, just to check nearest neighbour lanelets
default_match_to_lane_reduction_ratio is constant described in hdmap_utils.hpp
route::route requires routing_configuration, 'allow_lane_change = true' is needed to check distances to entities on neighbour lanelets
if there is already a route from_lanelet_id->to_lanelet_id, return it if not, transform the 'to_lanelet_id' position into the nearby lanelets and search for a route in relation to them
we want to have alternative lanelet pose with shortest route so we search for minimum
search_distance should be minimal, just to check nearest neighbour lanelets
default_match_to_lane_reduction_ratio is constant described in hdmap_utils.hpp
route::route requires routing_configuration, 'allow_lane_change = true' is needed to check distances to entities on neighbour lanelets
if there is already a route from_lanelet_id->to_lanelet_id, return it if not, transform the 'to_lanelet_id' position into the nearby lanelets and search for a route in relation to them
we want to have alternative lanelet pose with shortest route so we search for minimum

◆ isAltitudeMatching()

auto traffic_simulator::pose::isAltitudeMatching ( const CanonicalizedLaneletPose lanelet_pose,
const CanonicalizedLaneletPose target_lanelet_pose 
) -> bool
Note
Relative msg::Pose

◆ isAtEndOfLanelets()

auto traffic_simulator::pose::isAtEndOfLanelets ( const CanonicalizedLaneletPose canonicalized_lanelet_pose,
const std::shared_ptr< hdmap_utils::HdMapUtils > &  hdmap_utils_ptr 
) -> bool
Todo:
HdMapUtils will be removed when lanelet_wrapper::distance is added

◆ isInLanelet() [1/2]

auto traffic_simulator::pose::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
Todo:
HdMapUtils will be removed when lanelet_wrapper::distance is added

◆ isInLanelet() [2/2]

auto traffic_simulator::pose::isInLanelet ( const geometry_msgs::msg::Point &  point,
const lanelet::Id  lanelet_id 
) -> bool

◆ quietNaNLaneletPose()

auto traffic_simulator::pose::quietNaNLaneletPose ( ) -> LaneletPose

◆ quietNaNPose()

auto traffic_simulator::pose::quietNaNPose ( ) -> geometry_msgs::msg::Pose

◆ relativeLaneletPose()

auto traffic_simulator::pose::relativeLaneletPose ( const CanonicalizedLaneletPose from,
const CanonicalizedLaneletPose to,
const RoutingConfiguration routing_configuration,
const std::shared_ptr< hdmap_utils::HdMapUtils > &  hdmap_utils_ptr 
) -> LaneletPose
Note
Relative LaneletPose
Todo:
HdMapUtils will be removed when lanelet_wrapper::distance is added
Note
here the s and offset are intentionally assigned independently, even if it is not possible to calculate one of them - it happens that one is sufficient
here the s and offset are intentionally assigned independently, even if it is not possible to calculate one of them - it happens that one is sufficient

◆ relativePose() [1/3]

auto traffic_simulator::pose::relativePose ( const CanonicalizedLaneletPose from,
const geometry_msgs::msg::Pose &  to 
) -> std::optional<geometry_msgs::msg::Pose>

◆ relativePose() [2/3]

auto traffic_simulator::pose::relativePose ( const geometry_msgs::msg::Pose &  from,
const CanonicalizedLaneletPose to 
) -> std::optional<geometry_msgs::msg::Pose>

◆ relativePose() [3/3]

auto traffic_simulator::pose::relativePose ( const geometry_msgs::msg::Pose &  from,
const geometry_msgs::msg::Pose &  to 
) -> std::optional<geometry_msgs::msg::Pose>

◆ toCanonicalizedLaneletPose() [1/4]

auto traffic_simulator::pose::toCanonicalizedLaneletPose ( const geometry_msgs::msg::Pose &  map_pose,
const bool  include_crosswalk 
) -> std::optional<CanonicalizedLaneletPose>
Todo:
here matching_distance should be passed
Todo:
here matching_distance should be passed

◆ toCanonicalizedLaneletPose() [2/4]

auto traffic_simulator::pose::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>

◆ toCanonicalizedLaneletPose() [3/4]

auto traffic_simulator::pose::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>

◆ toCanonicalizedLaneletPose() [4/4]

auto traffic_simulator::pose::toCanonicalizedLaneletPose ( const LaneletPose lanelet_pose) -> std::optional<CanonicalizedLaneletPose>

◆ toMapPose() [1/2]

auto traffic_simulator::pose::toMapPose ( const CanonicalizedLaneletPose lanelet_pose) -> geometry_msgs::msg::Pose

◆ toMapPose() [2/2]

auto traffic_simulator::pose::toMapPose ( const LaneletPose lanelet_pose) -> geometry_msgs::msg::Pose

◆ transformRelativePoseToGlobal()

auto traffic_simulator::pose::transformRelativePoseToGlobal ( const geometry_msgs::msg::Pose &  global_pose,
const geometry_msgs::msg::Pose &  relative_pose 
) -> geometry_msgs::msg::Pose

◆ updatePositionForLaneletTransition()

auto traffic_simulator::pose::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 >
Note
This function does not modify the orientation of entity.
Note
Determine the displacement in the 2D lanelet coordinate system
Transform desired (global) velocity to local velocity
if longitudinal displacement exceeds the current lanelet length, use next lanelet if possible
Determine the displacement in the 2D lanelet coordinate system
Transform desired (global) velocity to local velocity
if longitudinal displacement exceeds the current lanelet length, use next lanelet if possible