scenario_simulator_v2 C++ API
|
#include <geometry_msgs/msg/point.h>
#include <gtest/gtest.h>
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <geometry/quaternion/euler_to_quaternion.hpp>
#include <string>
#include <traffic_simulator/hdmap_utils/hdmap_utils.hpp>
#include <traffic_simulator/helper/helper.hpp>
#include "../expect_eq_macros.hpp"
#include "../helper_functions.hpp"
Classes | |
class | HdMapUtilsTest_StandardMap |
class | HdMapUtilsTest_WithRoadShoulderMap |
class | HdMapUtilsTest_EmptyMap |
class | HdMapUtilsTest_FourTrackHighwayMap |
class | HdMapUtilsTest_CrossroadsWithStoplinesMap |
class | HdMapUtilsTest_KashiwanohaMap |
class | HdMapUtilsTest_IntersectionMap |
Functions | |
int | main (int argc, char **argv) |
TEST (HdMapUtils, Construct) | |
TEST (HdMapUtils, Construct_invalid) | |
TEST_F (HdMapUtilsTest_StandardMap, toMapBin) | |
TEST_F (HdMapUtilsTest_StandardMap, matchToLane) | |
TEST_F (HdMapUtilsTest_StandardMap, matchToLane_includeCrosswalk) | |
TEST_F (HdMapUtilsTest_StandardMap, matchToLane_noMatch) | |
TEST_F (HdMapUtilsTest_StandardMap, AlongLaneletPose_insideDistance) | |
TEST_F (HdMapUtilsTest_StandardMap, AlongLaneletPose_outsideDistance) | |
TEST_F (HdMapUtilsTest_StandardMap, AlongLaneletPose_negativeDistance) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, AlongLaneletPose_afterLast) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, AlongLaneletPose_beforeFirst) | |
TEST_F (HdMapUtilsTest_StandardMap, CanonicalizeNegative) | |
TEST_F (HdMapUtilsTest_StandardMap, CanonicalizePositive) | |
TEST_F (HdMapUtilsTest_StandardMap, Canonicalize) | |
TEST_F (HdMapUtilsTest_StandardMap, CanonicalizeAllNegative) | |
TEST_F (HdMapUtilsTest_StandardMap, CanonicalizeAllPositive) | |
TEST_F (HdMapUtilsTest_StandardMap, CanonicalizeAll) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, CountLaneChangesAlongRoute) | |
TEST_F (HdMapUtilsTest_StandardMap, filterLaneletIds_correct) | |
TEST_F (HdMapUtilsTest_StandardMap, filterLaneletIds_emptyIds) | |
TEST_F (HdMapUtilsTest_StandardMap, filterLaneletIds_invalidSubtype) | |
TEST_F (HdMapUtilsTest_StandardMap, filterLaneletIds_invalidIds) | |
TEST_F (HdMapUtilsTest_StandardMap, getNearbyLaneletIds) | |
TEST_F (HdMapUtilsTest_StandardMap, getNearbyLaneletIds_unsuccessful) | |
TEST_F (HdMapUtilsTest_StandardMap, getNearbyLaneletIds_crosswalkUnsuccessful) | |
TEST_F (HdMapUtilsTest_StandardMap, getCollisionPointInLaneCoordinate_intersects) | |
TEST_F (HdMapUtilsTest_StandardMap, getCollisionPointInLaneCoordinate_disjoint) | |
TEST_F (HdMapUtilsTest_StandardMap, getCollisionPointInLaneCoordinate_invalidLanelet) | |
TEST_F (HdMapUtilsTest_StandardMap, getCollisionPointInLaneCoordinate_invalidCrosswalkLanelet) | |
TEST_F (HdMapUtilsTest_StandardMap, toLaneletPose_correct) | |
TEST_F (HdMapUtilsTest_StandardMap, toLaneletPose_negativeOffset) | |
TEST_F (HdMapUtilsTest_StandardMap, toLaneletPose_reverse) | |
TEST_F (HdMapUtilsTest_StandardMap, toLaneletPose_notOnLanelet) | |
TEST_F (HdMapUtilsTest_StandardMap, toLaneletPose_empty) | |
TEST_F (HdMapUtilsTest_StandardMap, toLaneletPose_boundingBoxMatchPrevious) | |
TEST_F (HdMapUtilsTest_StandardMap, getSpeedLimit_correct) | |
TEST_F (HdMapUtilsTest_StandardMap, getSpeedLimit_crosswalk) | |
TEST_F (HdMapUtilsTest_StandardMap, getSpeedLimit_empty) | |
TEST_F (HdMapUtilsTest_StandardMap, getClosestLaneletId_near) | |
TEST_F (HdMapUtilsTest_StandardMap, getClosestLaneletId_away) | |
TEST_F (HdMapUtilsTest_StandardMap, getClosestLaneletId_crosswalkCloserButExcluded) | |
TEST_F (HdMapUtilsTest_StandardMap, getClosestLaneletId_onlyCrosswalkNearButExcluded) | |
TEST_F (HdMapUtilsTest_EmptyMap, getClosestLaneletId_emptyMap) | |
TEST_F (HdMapUtilsTest_StandardMap, getPreviousLaneletIds) | |
TEST_F (HdMapUtilsTest_WithRoadShoulderMap, getPreviousLaneletIds_RoadShoulder) | |
TEST_F (HdMapUtilsTest_StandardMap, getPreviousLaneletIds_multiplePrevious) | |
TEST_F (HdMapUtilsTest_StandardMap, getPreviousLaneletIds_direction) | |
TEST_F (HdMapUtilsTest_StandardMap, getNextLaneletIds) | |
TEST_F (HdMapUtilsTest_WithRoadShoulderMap, getNextLaneletIds_RoadShoulder) | |
TEST_F (HdMapUtilsTest_StandardMap, getNextLaneletIds_multipleNext) | |
TEST_F (HdMapUtilsTest_StandardMap, getNextLaneletIds_direction) | |
TEST_F (HdMapUtilsTest_StandardMap, isInRoute_onRoute) | |
TEST_F (HdMapUtilsTest_StandardMap, isInRoute_notOnRoute) | |
TEST_F (HdMapUtilsTest_StandardMap, isInRoute_empty) | |
TEST_F (HdMapUtilsTest_StandardMap, isInLanelet_correct) | |
TEST_F (HdMapUtilsTest_StandardMap, isInLanelet_after) | |
TEST_F (HdMapUtilsTest_StandardMap, isInLanelet_before) | |
TEST_F (HdMapUtilsTest_StandardMap, toMapPoints_correctPoints) | |
TEST_F (HdMapUtilsTest_StandardMap, toMapPoints_negativeS) | |
TEST_F (HdMapUtilsTest_StandardMap, toMapPoints_sLargerThanLaneletLength) | |
TEST_F (HdMapUtilsTest_StandardMap, toMapPoints_empty) | |
TEST_F (HdMapUtilsTest_StandardMap, toMapPose_onlyOffset) | |
TEST_F (HdMapUtilsTest_StandardMap, toMapPose_additionalRotation) | |
TEST_F (HdMapUtilsTest_StandardMap, toMapPose_negativeS) | |
TEST_F (HdMapUtilsTest_StandardMap, toMapPose_sLargerThanLaneletLength) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLaneChangeableLaneletId_straight) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLaneChangeableLaneletId_leftNoChangeable) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLaneChangeableLaneletId_leftChangeable) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLaneChangeableLaneletId_rightNoChangeable) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLaneChangeableLaneletId_rightChangeable) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLaneChangeableLaneletId_shift2LeftPossible) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLaneChangeableLaneletId_shift2LeftNotPossible) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLaneChangeableLaneletId_shift2RightPossible) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLaneChangeableLaneletId_shift2RightNotPossible) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLaneChangeableLaneletId_shift0) | |
TEST_F (HdMapUtilsTest_StandardMap, getTrafficLightIds_correct) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getTrafficLightIds_noTrafficLight) | |
TEST_F (HdMapUtilsTest_StandardMap, getTrafficLightBulbPosition_correct) | |
TEST_F (HdMapUtilsTest_StandardMap, getTrafficLightBulbPosition_invalidTrafficLight) | |
TEST_F (HdMapUtilsTest_StandardMap, getConflictingLaneIds_conflicting) | |
TEST_F (HdMapUtilsTest_StandardMap, getConflictingLaneIds_notConflicting) | |
TEST_F (HdMapUtilsTest_StandardMap, getConflictingLaneIds_empty) | |
TEST_F (HdMapUtilsTest_StandardMap, getConflictingCrosswalkIds_conflicting) | |
TEST_F (HdMapUtilsTest_StandardMap, getConflictingCrosswalkIds_notConflictingWithCrosswalk) | |
TEST_F (HdMapUtilsTest_StandardMap, getConflictingCrosswalkIds_notConflicting) | |
TEST_F (HdMapUtilsTest_StandardMap, getConflictingCrosswalkIds_empty) | |
TEST_F (HdMapUtilsTest_StandardMap, clipTrajectoryFromLaneletIds_correct) | |
TEST_F (HdMapUtilsTest_StandardMap, clipTrajectoryFromLaneletIds_startNotOnTrajectory) | |
TEST_F (HdMapUtilsTest_StandardMap, clipTrajectoryFromLaneletIds_emptyTrajectory) | |
TEST_F (HdMapUtilsTest_StandardMap, clipTrajectoryFromLaneletIds_smallForwardDistance) | |
TEST_F (HdMapUtilsTest_StandardMap, getFollowingLanelets_straightAfter) | |
TEST_F (HdMapUtilsTest_StandardMap, getFollowingLanelets_curveAfter) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getFollowingLanelets_notEnoughLaneletsAfter) | |
TEST_F (HdMapUtilsTest_StandardMap, getFollowingLanelets_candidateTrajectory) | |
TEST_F (HdMapUtilsTest_StandardMap, getFollowingLanelets_candidateTrajectoryFalse) | |
TEST_F (HdMapUtilsTest_StandardMap, getFollowingLanelets_candidateTrajectoryNotEnough) | |
TEST_F (HdMapUtilsTest_StandardMap, getFollowingLanelets_candidatesDoNotMatch) | |
TEST_F (HdMapUtilsTest_StandardMap, getFollowingLanelets_candidateTrajectoryEmpty) | |
TEST_F (HdMapUtilsTest_StandardMap, getFollowingLanelets_candidatesDoNotMatchRealTrajectory) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, canChangeLane_canChange) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, canChangeLane_canNotChange) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, canChangeLane_invalidLaneletId) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLateralDistance_sameLane) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLateralDistance_parallelLanesCanNotChange) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLateralDistance_parallelLanesCanChange) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLateralDistance_notConnected) | |
TEST_F (HdMapUtilsTest_StandardMap, getRoute_correct) | |
TEST_F (HdMapUtilsTest_StandardMap, getRoute_correctCache) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getRoute_impossibleRouting) | |
TEST_F (HdMapUtilsTest_StandardMap, getRoute_circular) | |
TEST_F (HdMapUtilsTest_StandardMap, getCenterPoints_correct) | |
TEST_F (HdMapUtilsTest_StandardMap, getCenterPoints_correctCache) | |
TEST_F (HdMapUtilsTest_StandardMap, getCenterPoints_correctVector) | |
TEST_F (HdMapUtilsTest_StandardMap, getCenterPoints_empty) | |
TEST_F (HdMapUtilsTest_StandardMap, isTrafficLight_trafficLight) | |
TEST_F (HdMapUtilsTest_StandardMap, isTrafficLight_notTrafficLight) | |
TEST_F (HdMapUtilsTest_StandardMap, isTrafficLight_invalidId) | |
TEST_F (HdMapUtilsTest_StandardMap, isTrafficLightRegulatoryElement_trafficLightRegulatoryElement) | |
TEST_F (HdMapUtilsTest_StandardMap, isTrafficLightRegulatoryElement_noTrafficLightRegulatoryElement) | |
TEST_F (HdMapUtilsTest_StandardMap, isTrafficLightRegulatoryElement_invalidId) | |
TEST_F (HdMapUtilsTest_StandardMap, getLaneletLength_simple) | |
TEST_F (HdMapUtilsTest_StandardMap, getLaneletLength_cache) | |
TEST_F (HdMapUtilsTest_StandardMap, getTrafficLightIdsOnPath_noTrafficLights) | |
TEST_F (HdMapUtilsTest_StandardMap, getTrafficLightIdsOnPath_trafficLights) | |
TEST_F (HdMapUtilsTest_StandardMap, getTrafficLightIdsOnPath_empty) | |
TEST_F (HdMapUtilsTest_StandardMap, getLongitudinalDistance_sameLanelet) | |
TEST_F (HdMapUtilsTest_StandardMap, getLongitudinalDistance_sameLaneletBehind) | |
TEST_F (HdMapUtilsTest_StandardMap, getLongitudinalDistance_differentLanelet) | |
TEST_F (HdMapUtilsTest_FourTrackHighwayMap, getLongitudinalDistance_differentLaneletNoRoute) | |
TEST_F (HdMapUtilsTest_KashiwanohaMap, getLongitudinalDistance_PullRequest1348) | |
TEST_F (HdMapUtilsTest_IntersectionMap, getLongitudinalDistance_laneChange) | |
TEST_F (HdMapUtilsTest_StandardMap, getStopLineIdsOnPath_noStopLines) | |
TEST_F (HdMapUtilsTest_StandardMap, getStopLineIdsOnPath_someStopLines) | |
TEST_F (HdMapUtilsTest_StandardMap, getStopLineIdsOnPath_empty) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getTrafficLightStopLineIds_stopLine) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getTrafficLightStopLineIds_severalStopLines) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getTrafficLightStopLineIds_invalidTrafficLightId) | |
void | sortStoplines (std::vector< std::vector< geometry_msgs::msg::Point >> &stoplines) |
void | compareStoplines (const std::vector< std::vector< geometry_msgs::msg::Point >> &a, const std::vector< std::vector< geometry_msgs::msg::Point >> &b) |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getTrafficLightStopLinesPoints_stopLine) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getTrafficLightStopLinesPoints_severalStopLines) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getTrafficLightStopLinesPoints_invalidTrafficLightId) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getStopLinePolygon_stopLine) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getStopLinePolygon_invalidLaneletId) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_trafficLightOnSpline) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_noTrafficLightOnSpline) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_trafficLightOnWaypoints) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_noTrafficLightOnWaypoints) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_emptyVector_waypoints) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_routeWithTrafficLightsOnSpline) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_routeWithNoTrafficLightsOnSplineCongruent) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_routeWithTrafficLightsNotOnSplineIncongruent) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_emptyVector_splineRoute) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_routeWithTrafficLightsOnWaypoints) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_routeWithNoTrafficLightsOnWaypointsIncongruent) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_routeWithTrafficLightsNotOnWaypointsCongruent) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToTrafficLightStopLine_emptyVector_waypointsRoute) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToStopLine_stopLineOnSpline) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToStopLine_noStopLineOnSplineCongruent) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToStopLine_noStopLineOnSplineIncongruent) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToStopLine_emptyVector_spline) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToStopLine_stopLineOnWaypoints) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToStopLine_noStopLineOnWaypointsCongruent) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToStopLine_noStopLineOnWaypointsIncongruent) | |
TEST_F (HdMapUtilsTest_CrossroadsWithStoplinesMap, getDistanceToStopLine_emptyVector_waypoints) | |
TEST_F (HdMapUtilsTest_StandardMap, getPreviousLanelets) | |
void compareStoplines | ( | const std::vector< std::vector< geometry_msgs::msg::Point >> & | a, |
const std::vector< std::vector< geometry_msgs::msg::Point >> & | b | ||
) |
int main | ( | int | argc, |
char ** | argv | ||
) |
void sortStoplines | ( | std::vector< std::vector< geometry_msgs::msg::Point >> & | stoplines | ) |
TEST | ( | HdMapUtils | , |
Construct | |||
) |
TEST | ( | HdMapUtils | , |
Construct_invalid | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToStopLine_emptyVector_spline | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToStopLine_emptyVector_waypoints | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToStopLine_noStopLineOnSplineCongruent | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToStopLine_noStopLineOnSplineIncongruent | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToStopLine_noStopLineOnWaypointsCongruent | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToStopLine_noStopLineOnWaypointsIncongruent | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToStopLine_stopLineOnSpline | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToStopLine_stopLineOnWaypoints | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_emptyVector_splineRoute | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_emptyVector_waypoints | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_emptyVector_waypointsRoute | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_noTrafficLightOnSpline | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_noTrafficLightOnWaypoints | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_routeWithNoTrafficLightsOnSplineCongruent | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_routeWithNoTrafficLightsOnWaypointsIncongruent | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_routeWithTrafficLightsNotOnSplineIncongruent | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_routeWithTrafficLightsNotOnWaypointsCongruent | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_routeWithTrafficLightsOnSpline | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_routeWithTrafficLightsOnWaypoints | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_trafficLightOnSpline | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getDistanceToTrafficLightStopLine_trafficLightOnWaypoints | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getStopLinePolygon_invalidLaneletId | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getStopLinePolygon_stopLine | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getTrafficLightStopLineIds_invalidTrafficLightId | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getTrafficLightStopLineIds_severalStopLines | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getTrafficLightStopLineIds_stopLine | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getTrafficLightStopLinesPoints_invalidTrafficLightId | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getTrafficLightStopLinesPoints_severalStopLines | |||
) |
TEST_F | ( | HdMapUtilsTest_CrossroadsWithStoplinesMap | , |
getTrafficLightStopLinesPoints_stopLine | |||
) |
TEST_F | ( | HdMapUtilsTest_EmptyMap | , |
getClosestLaneletId_emptyMap | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
AlongLaneletPose_afterLast | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
AlongLaneletPose_beforeFirst | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
canChangeLane_canChange | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
canChangeLane_canNotChange | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
canChangeLane_invalidLaneletId | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
CountLaneChangesAlongRoute | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getFollowingLanelets_notEnoughLaneletsAfter | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLaneChangeableLaneletId_leftChangeable | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLaneChangeableLaneletId_leftNoChangeable | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLaneChangeableLaneletId_rightChangeable | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLaneChangeableLaneletId_rightNoChangeable | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLaneChangeableLaneletId_shift0 | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLaneChangeableLaneletId_shift2LeftNotPossible | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLaneChangeableLaneletId_shift2LeftPossible | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLaneChangeableLaneletId_shift2RightNotPossible | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLaneChangeableLaneletId_shift2RightPossible | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLaneChangeableLaneletId_straight | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLateralDistance_notConnected | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLateralDistance_parallelLanesCanChange | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLateralDistance_parallelLanesCanNotChange | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLateralDistance_sameLane | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getLongitudinalDistance_differentLaneletNoRoute | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getRoute_impossibleRouting | |||
) |
TEST_F | ( | HdMapUtilsTest_FourTrackHighwayMap | , |
getTrafficLightIds_noTrafficLight | |||
) |
TEST_F | ( | HdMapUtilsTest_IntersectionMap | , |
getLongitudinalDistance_laneChange | |||
) |
TEST_F | ( | HdMapUtilsTest_KashiwanohaMap | , |
getLongitudinalDistance_PullRequest1348 | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
AlongLaneletPose_insideDistance | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
AlongLaneletPose_negativeDistance | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
AlongLaneletPose_outsideDistance | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
Canonicalize | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
CanonicalizeAll | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
CanonicalizeAllNegative | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
CanonicalizeAllPositive | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
CanonicalizeNegative | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
CanonicalizePositive | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
clipTrajectoryFromLaneletIds_correct | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
clipTrajectoryFromLaneletIds_emptyTrajectory | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
clipTrajectoryFromLaneletIds_smallForwardDistance | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
clipTrajectoryFromLaneletIds_startNotOnTrajectory | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
filterLaneletIds_correct | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
filterLaneletIds_emptyIds | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
filterLaneletIds_invalidIds | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
filterLaneletIds_invalidSubtype | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getCenterPoints_correct | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getCenterPoints_correctCache | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getCenterPoints_correctVector | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getCenterPoints_empty | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getClosestLaneletId_away | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getClosestLaneletId_crosswalkCloserButExcluded | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getClosestLaneletId_near | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getClosestLaneletId_onlyCrosswalkNearButExcluded | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getCollisionPointInLaneCoordinate_disjoint | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getCollisionPointInLaneCoordinate_intersects | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getCollisionPointInLaneCoordinate_invalidCrosswalkLanelet | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getCollisionPointInLaneCoordinate_invalidLanelet | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getConflictingCrosswalkIds_conflicting | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getConflictingCrosswalkIds_empty | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getConflictingCrosswalkIds_notConflicting | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getConflictingCrosswalkIds_notConflictingWithCrosswalk | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getConflictingLaneIds_conflicting | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getConflictingLaneIds_empty | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getConflictingLaneIds_notConflicting | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getFollowingLanelets_candidatesDoNotMatch | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getFollowingLanelets_candidatesDoNotMatchRealTrajectory | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getFollowingLanelets_candidateTrajectory | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getFollowingLanelets_candidateTrajectoryEmpty | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getFollowingLanelets_candidateTrajectoryFalse | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getFollowingLanelets_candidateTrajectoryNotEnough | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getFollowingLanelets_curveAfter | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getFollowingLanelets_straightAfter | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getLaneletLength_cache | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getLaneletLength_simple | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getLongitudinalDistance_differentLanelet | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getLongitudinalDistance_sameLanelet | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getLongitudinalDistance_sameLaneletBehind | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getNearbyLaneletIds | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getNearbyLaneletIds_crosswalkUnsuccessful | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getNearbyLaneletIds_unsuccessful | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getNextLaneletIds | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getNextLaneletIds_direction | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getNextLaneletIds_multipleNext | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getPreviousLaneletIds | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getPreviousLaneletIds_direction | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getPreviousLaneletIds_multiplePrevious | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getPreviousLanelets | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getRoute_circular | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getRoute_correct | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getRoute_correctCache | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getSpeedLimit_correct | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getSpeedLimit_crosswalk | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getSpeedLimit_empty | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getStopLineIdsOnPath_empty | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getStopLineIdsOnPath_noStopLines | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getStopLineIdsOnPath_someStopLines | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getTrafficLightBulbPosition_correct | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getTrafficLightBulbPosition_invalidTrafficLight | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getTrafficLightIds_correct | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getTrafficLightIdsOnPath_empty | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getTrafficLightIdsOnPath_noTrafficLights | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
getTrafficLightIdsOnPath_trafficLights | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isInLanelet_after | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isInLanelet_before | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isInLanelet_correct | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isInRoute_empty | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isInRoute_notOnRoute | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isInRoute_onRoute | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isTrafficLight_invalidId | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isTrafficLight_notTrafficLight | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isTrafficLight_trafficLight | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isTrafficLightRegulatoryElement_invalidId | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isTrafficLightRegulatoryElement_noTrafficLightRegulatoryElement | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
isTrafficLightRegulatoryElement_trafficLightRegulatoryElement | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
matchToLane | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
matchToLane_includeCrosswalk | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
matchToLane_noMatch | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toLaneletPose_boundingBoxMatchPrevious | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toLaneletPose_correct | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toLaneletPose_empty | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toLaneletPose_negativeOffset | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toLaneletPose_notOnLanelet | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toLaneletPose_reverse | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toMapBin | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toMapPoints_correctPoints | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toMapPoints_empty | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toMapPoints_negativeS | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toMapPoints_sLargerThanLaneletLength | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toMapPose_additionalRotation | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toMapPose_negativeS | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toMapPose_onlyOffset | |||
) |
TEST_F | ( | HdMapUtilsTest_StandardMap | , |
toMapPose_sLargerThanLaneletLength | |||
) |
TEST_F | ( | HdMapUtilsTest_WithRoadShoulderMap | , |
getNextLaneletIds_RoadShoulder | |||
) |
TEST_F | ( | HdMapUtilsTest_WithRoadShoulderMap | , |
getPreviousLaneletIds_RoadShoulder | |||
) |