/// \file MappingHelpers.h /// \brief Helper functions for mapping operation such as (load and initialize vector maps , convert map from one format to another, .. ) /// \author Hatem Darweesh /// \date Jul 2, 2016 #ifndef MAPPINGHELPERS_H_ #define MAPPINGHELPERS_H_ #include #include "RoadNetwork.h" #include "op_utility/UtilityH.h" #include "op_utility/DataRW.h" #include "tinyxml.h" namespace PlannerHNS { class MappingHelpers { public: MappingHelpers(); virtual ~MappingHelpers(); static void ConstructRoadNetworkFromROSMessage(const std::vector& lanes_data, const std::vector& points_data, const std::vector& dt_data, const std::vector& intersection_data, const std::vector& area_data, const std::vector& line_data, const std::vector& stop_line_data, const std::vector& signal_data, const std::vector& vector_data, const std::vector& curb_data, const std::vector& roadedge_data, const std::vector& wayarea_data, const std::vector& crosswalk_data, const std::vector& nodes_data, const std::vector& conn_data, const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag = false, const bool& bFindLaneChangeLanes = false, const bool& bFindCurbsAndWayArea = false); static void ConstructRoadNetworkFromROSMessageV2(const std::vector& lanes_data, const std::vector& points_data, const std::vector& dt_data, const std::vector& intersection_data, const std::vector& area_data, const std::vector& line_data, const std::vector& stop_line_data, const std::vector& signal_data, const std::vector& vector_data, const std::vector& curb_data, const std::vector& roadedge_data, const std::vector& wayarea_data, const std::vector& crosswalk_data, const std::vector& nodes_data, const std::vector& conn_data, UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanPointsFileReader* pPointsData, UtilityHNS::AisanNodesFileReader* pNodesData, UtilityHNS::AisanLinesFileReader* pLinedata, const GPSPoint& origin, RoadNetwork& map, const bool& bSpecialFlag = false, const bool& bFindLaneChangeLanes = false, const bool& bFindCurbsAndWayArea = false); static void ConstructRoadNetworkFromDataFiles(const std::string vectoMapPath, RoadNetwork& map, const bool& bZeroOrigin = false); static void UpdateMapWithOccupancyGrid(OccupancyToGridMap& map_info, const std::vector& data, RoadNetwork& map, std::vector& updated_list); static bool GetWayPoint(const int& id, const int& laneID,const double& refVel, const int& did, const std::vector& dtpoints, const std::vector& points, const GPSPoint& origin, WayPoint& way_point); static void LoadKML(const std::string& kmlMap, RoadNetwork& map); static TiXmlElement* GetHeadElement(TiXmlElement* pMainElem); static TiXmlElement* GetDataFolder(const std::string& folderName, TiXmlElement* pMainElem); static Lane* GetClosestLaneFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance = 5.0, const bool bDirectionBased = true); static std::vector GetClosestLanesListFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance = 2.0, const bool bDirectionBased = true); static Lane* GetClosestLaneFromMapDirectionBased(const WayPoint& pos, RoadNetwork& map, const double& distance = 5.0); static std::vector GetClosestMultipleLanesFromMap(const WayPoint& pos, RoadNetwork& map, const double& distance = 5.0); static WayPoint* GetClosestWaypointFromMap(const WayPoint& pos, RoadNetwork& map, const bool bDirectionBased = true); static std::vector GetClosestLanesFast(const WayPoint& pos, RoadNetwork& map, const double& distance = 10.0); static std::vector GetClosestWaypointsListFromMap(const WayPoint& center, RoadNetwork& map, const double& distance = 2.0, const bool bDirectionBased = true); static WayPoint* GetClosestBackWaypointFromMap(const WayPoint& pos, RoadNetwork& map); static WayPoint GetFirstWaypoint(RoadNetwork& map); static WayPoint* GetLastWaypoint(RoadNetwork& map); static void FindAdjacentLanes(RoadNetwork& map); static void FindAdjacentLanesV2(RoadNetwork& map); static void ExtractSignalData(const std::vector& signal_data, const std::vector& vector_data, const std::vector& points_data, const GPSPoint& origin, RoadNetwork& map); static void ExtractSignalDataV2(const std::vector& signal_data, const std::vector& vector_data, UtilityHNS::AisanPointsFileReader* pPointsData, const GPSPoint& origin, RoadNetwork& map); static void ExtractStopLinesData(const std::vector& stop_line_data, const std::vector& line_data, const std::vector& points_data, const GPSPoint& origin, RoadNetwork& map); static void ExtractStopLinesDataV2(const std::vector& stop_line_data, UtilityHNS::AisanLinesFileReader* pLineData, UtilityHNS::AisanPointsFileReader* pPointData, const GPSPoint& origin, RoadNetwork& map); static void ExtractCurbData(const std::vector& curb_data, const std::vector& line_data, const std::vector& points_data, const GPSPoint& origin, RoadNetwork& map); static void ExtractCurbDataV2(const std::vector& curb_data, UtilityHNS::AisanLinesFileReader* pLinedata, UtilityHNS::AisanPointsFileReader* pPointsData, const GPSPoint& origin, RoadNetwork& map); static void ExtractWayArea(const std::vector& area_data, const std::vector& wayarea_data, const std::vector& line_data, const std::vector& points_data, const GPSPoint& origin, RoadNetwork& map); static void LinkMissingBranchingWayPoints(RoadNetwork& map); static void LinkMissingBranchingWayPointsV2(RoadNetwork& map); static void LinkTrafficLightsAndStopLinesConData(const std::vector& conn_data, const std::vector >& id_replace_list, RoadNetwork& map); static void LinkTrafficLightsAndStopLines(RoadNetwork& map); static void LinkTrafficLightsAndStopLinesV2(RoadNetwork& map); static void GetUniqueNextLanes(const Lane* l, const std::vector& traversed_lanes, std::vector& lanes_list); static GPSPoint GetTransformationOrigin(const int& bToyotaCityMap = 0); static Lane* GetLaneFromPath(const WayPoint& currPos, const std::vector& currPath); static Lane* GetLaneById(const int& id,RoadNetwork& map); static int GetLaneIdByWaypointId(const int& id,std::vector& lanes); static WayPoint* FindWaypoint(const int& id, RoadNetwork& map); static WayPoint* FindWaypointV2(const int& id, const int& l_id, RoadNetwork& map); static std::vector GetCurbsList(TiXmlElement* pElem); static std::vector GetBoundariesList(TiXmlElement* pElem); static std::vector GetMarkingsList(TiXmlElement* pElem); static std::vector GetCrossingsList(TiXmlElement* pElem); static std::vector GetTrafficSignsList(TiXmlElement* pElem); static std::vector GetTrafficLightsList(TiXmlElement* pElem); static std::vector GetStopLinesList(TiXmlElement* pElem); static std::vector GetLanesList(TiXmlElement* pElem); static std::vector GetRoadSegmentsList(TiXmlElement* pElem); static std::vector GetIDsFromPrefix(const std::string& str, const std::string& prefix, const std::string& postfix); static std::vector GetDoubleFromPrefix(const std::string& str, const std::string& prefix, const std::string& postfix); static std::pair GetActionPairFromPrefix(const std::string& str, const std::string& prefix, const std::string& postfix); static std::vector GetCenterLaneData(TiXmlElement* pElem, const int& currLaneID); static std::vector GetCenterLaneDataVer0(TiXmlElement* pElem, const int& currLaneID); static std::vector GetPointsData(TiXmlElement* pElem); static std::vector SplitString(const std::string& str, const std::string& token); //static void CreateKmlFromLocalizationPathFile(const std::string& pathFileName,const double& maxLaneDistance, const double& density,const std::vector& trafficLights, const std::vector& stopLines); static void AssignActionCostToLane(Lane* pL, ACTION_TYPE action, double cost); static int ReplaceMyID(int& id, const std::vector >& rep_list); static void GetLanesStartPoints(UtilityHNS::AisanLanesFileReader* pLaneData, std::vector& m_LanesStartIds); static void GetLanePoints(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanPointsFileReader* pPointsData, UtilityHNS::AisanNodesFileReader* pNodesData, int lnID, PlannerHNS::Lane& out_lane); static void CreateLanes(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanPointsFileReader* pPointsData, UtilityHNS::AisanNodesFileReader* pNodesData, std::vector& out_lanes); static void ConnectLanes(UtilityHNS::AisanLanesFileReader* pLaneData, std::vector& lanes); static bool GetPointFromDataList(UtilityHNS::AisanPointsFileReader* pPointsData,const int& pid, WayPoint& out_wp); static int GetBeginPointIdFromLaneNo(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanPointsFileReader* pPointsData, UtilityHNS::AisanNodesFileReader* pNodesData, const int& LnID); static int GetEndPointIdFromLaneNo(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanPointsFileReader* pPointsData, UtilityHNS::AisanNodesFileReader* pNodesData,const int& LnID); static bool IsStartLanePoint(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanLanesFileReader::AisanLane* pL); static bool IsEndLanePoint(UtilityHNS::AisanLanesFileReader* pLaneData, UtilityHNS::AisanLanesFileReader::AisanLane* pL); static void FixRedundantPointsLanes(std::vector& lanes); static void FixTwoPointsLanes(std::vector& lanes); static void FixTwoPointsLane(Lane& lanes); static void FixUnconnectedLanes(std::vector& lanes); static void InsertWayPointToBackOfLane(const WayPoint& wp, Lane& lane, int& global_id); static void InsertWayPointToFrontOfLane(const WayPoint& wp, Lane& lane, int& global_id); static void LinkLanesPointers(PlannerHNS::RoadNetwork& map); static void GetMapMaxIds(PlannerHNS::RoadNetwork& map); static double m_USING_VER_ZERO; static int g_max_point_id; static int g_max_lane_id; static int g_max_stop_line_id; static int g_max_traffic_light_id ; }; } /* namespace PlannerHNS */ #endif /* MAPPINGHELPERS_H_ */