|
Autoware.Auto
|
|
Typedefs | |
| using | Kernel = CGAL::Exact_predicates_exact_constructions_kernel |
| using | CGAL_Point = Kernel::Point_2 |
| using | CGAL_Polygon = CGAL::Polygon_2< Kernel > |
| using | CGAL_Polygon_with_holes = CGAL::Polygon_with_holes_2< Kernel > |
Functions | |
| lanelet::Polygon3d HAD_MAP_UTILS_PUBLIC | coalesce_drivable_areas (const autoware_auto_msgs::msg::Route &route, const lanelet::LaneletMapPtr &lanelet_map_ptr) |
| void HAD_MAP_UTILS_PUBLIC | toBinaryMsg (const std::shared_ptr< lanelet::LaneletMap > &map, autoware_auto_msgs::msg::HADMapBin &msg) |
| void HAD_MAP_UTILS_PUBLIC | fromBinaryMsg (const autoware_auto_msgs::msg::HADMapBin &msg, std::shared_ptr< lanelet::LaneletMap > &map) |
| lanelet::Areas HAD_MAP_UTILS_PUBLIC | getAreaLayer (const lanelet::LaneletMapPtr ll_map) |
| lanelet::Areas HAD_MAP_UTILS_PUBLIC | subtypeAreas (const lanelet::Areas areas, const char subtype[]) |
| lanelet::Polygons3d HAD_MAP_UTILS_PUBLIC | getPolygonLayer (const lanelet::LaneletMapPtr ll_map) |
| lanelet::Polygons3d HAD_MAP_UTILS_PUBLIC | subtypePolygons (const lanelet::Polygons3d polygons, const char subtype[]) |
| lanelet::LineStrings3d HAD_MAP_UTILS_PUBLIC | getLineStringLayer (const lanelet::LaneletMapPtr ll_map) |
| lanelet::LineStrings3d HAD_MAP_UTILS_PUBLIC | subtypeLineStrings (const lanelet::LineStrings3d linestrings, const char subtype[]) |
| lanelet::ConstLanelets HAD_MAP_UTILS_PUBLIC | getConstLaneletLayer (const std::shared_ptr< lanelet::LaneletMap > &ll_map) |
| lanelet::Lanelets HAD_MAP_UTILS_PUBLIC | getLaneletLayer (const std::shared_ptr< lanelet::LaneletMap > &ll_map) |
| void HAD_MAP_UTILS_PUBLIC | overwriteLaneletsCenterline (lanelet::LaneletMapPtr lanelet_map, const autoware::common::types::bool8_t force_overwrite) |
| lanelet::LineString3d HAD_MAP_UTILS_PUBLIC | generateFineCenterline (const lanelet::ConstLanelet &lanelet_obj, const float64_t resolution) |
| void HAD_MAP_UTILS_PUBLIC | setColor (std_msgs::msg::ColorRGBA *cl, const float32_t &r, const float32_t &g, const float32_t &b, const float32_t &a) |
| Set set rgba information to a Color Object. More... | |
| void HAD_MAP_UTILS_PUBLIC | setMarkerHeader (visualization_msgs::msg::Marker *m, const int32_t &id, const rclcpp::Time &t, const std::string &frame_id, const std::string &ns, const std_msgs::msg::ColorRGBA &c, const int32_t &action, const int32_t &type, const float32_t &scale) |
| Set the header information to a marker object. More... | |
| visualization_msgs::msg::Marker HAD_MAP_UTILS_PUBLIC | lineString2Marker (const rclcpp::Time &t, const lanelet::LineString3d &ls, const std::string &frame_id, const std::string &ns, const std_msgs::msg::ColorRGBA &c, const float32_t &lss) |
| creates marker with type LINE_STRIP from a lanelet::LineString3d object More... | |
| visualization_msgs::msg::Marker HAD_MAP_UTILS_PUBLIC | lineString2Marker (const rclcpp::Time &t, const lanelet::ConstLineString3d &ls, const std::string &frame_id, const std::string &ns, const std_msgs::msg::ColorRGBA &c, const float32_t &lss) |
| creates marker with type LINE_STRIP from a lanelet::ConstLineString3d object More... | |
| visualization_msgs::msg::MarkerArray HAD_MAP_UTILS_PUBLIC | lineStringsAsMarkerArray (const rclcpp::Time &t, const std::string &ns, const lanelet::LineStrings3d &linestrings, const std_msgs::msg::ColorRGBA &c) |
| converts lanelet::LineString into markers with type LINE_STRIP More... | |
| visualization_msgs::msg::MarkerArray HAD_MAP_UTILS_PUBLIC | laneletsBoundaryAsMarkerArray (const rclcpp::Time &t, const lanelet::ConstLanelets &lanelets, const std_msgs::msg::ColorRGBA &c, const bool8_t &viz_centerline) |
| converts outer bound of lanelet::Lanelet into markers with type LINE_STRIP More... | |
| visualization_msgs::msg::Marker HAD_MAP_UTILS_PUBLIC | basicPolygon2Marker (const rclcpp::Time &t, const int32_t &line_id, const lanelet::BasicPolygon3d &pg, const std::string &frame_id, const std::string &ns, const std_msgs::msg::ColorRGBA &c, const float32_t &lss) |
| creates marker with type LINE_STRIP from a lanelet::BasicPolygon object More... | |
| visualization_msgs::msg::MarkerArray HAD_MAP_UTILS_PUBLIC | areasBoundaryAsMarkerArray (const rclcpp::Time &t, const std::string &ns, const lanelet::Areas &areas, const std_msgs::msg::ColorRGBA &c) |
| converts outer bound of lanelet::Area into markers with type LINE_STRIP More... | |
| visualization_msgs::msg::MarkerArray HAD_MAP_UTILS_PUBLIC | polygonsBoundaryAsMarkerArray (const rclcpp::Time &t, const std::string &ns, const lanelet::Polygons3d &polygons, const std_msgs::msg::ColorRGBA &c) |
| converts outer bound of lanelet::Polygon into markers with type LINE_STRIP More... | |
| visualization_msgs::msg::Marker HAD_MAP_UTILS_PUBLIC | bbox2Marker (const rclcpp::Time &t, const int32_t &line_id, const float64_t lower[], const float64_t upper[], const std::string &frame_id, const std::string &ns, const std_msgs::msg::ColorRGBA &c, const float32_t &lss) |
| creates marker with type LINE_STRIP from a bounding box More... | |
| visualization_msgs::msg::MarkerArray HAD_MAP_UTILS_PUBLIC | boundingBoxAsMarkerArray (const rclcpp::Time &t, const std::string &ns, const float64_t upper[], const float64_t lower[], const std_msgs::msg::ColorRGBA &c) |
| creates marker array from bounding box More... | |
| std::vector< geometry_msgs::msg::Polygon > HAD_MAP_UTILS_PUBLIC | lanelet2Triangle (const lanelet::ConstLanelet &ll) |
| converts area enclosed by lanelet::Lanelet into list of triangles. More... | |
| std::vector< geometry_msgs::msg::Polygon > HAD_MAP_UTILS_PUBLIC | polygon2Triangle (const geometry_msgs::msg::Polygon &polygon) |
| converts area enclosed by geometry_msg::msg::Polygon into list of triangles. More... | |
| geometry_msgs::msg::Polygon HAD_MAP_UTILS_PUBLIC | area2Polygon (const lanelet::ConstArea &area) |
| converts lanelet::Area into geometry_msgs::msg::Polygon type More... | |
| geometry_msgs::msg::Polygon HAD_MAP_UTILS_PUBLIC | lanelet2Polygon (const lanelet::ConstLanelet &ll) |
| converts lanelet::Lanelet into geometry_msgs::msg::Polygon type More... | |
| visualization_msgs::msg::MarkerArray HAD_MAP_UTILS_PUBLIC | laneletsAsTriangleMarkerArray (const rclcpp::Time &t, const std::string &ns, const lanelet::ConstLanelets &lanelets, const std_msgs::msg::ColorRGBA &c) |
| converts bounded area by lanelet::Lanelet into triangle markers More... | |
| visualization_msgs::msg::MarkerArray HAD_MAP_UTILS_PUBLIC | areasAsTriangleMarkerArray (const rclcpp::Time &t, const std::string &ns, const lanelet::Areas &areas, const std_msgs::msg::ColorRGBA &c) |
| converts bounded area by lanelet::Area into triangle markers More... | |
| std::vector< float64_t > | calculateSegmentDistances (const lanelet::ConstLineString3d &line_string) |
| std::vector< float64_t > | calculateAccumulatedLengths (const lanelet::ConstLineString3d &line_string) |
| std::pair< size_t, size_t > | findNearestIndexPair (const std::vector< float64_t > &accumulated_lengths, const float64_t target_length) |
| std::vector< lanelet::BasicPoint3d > | resamplePoints (const lanelet::ConstLineString3d &line_string, const int32_t num_segments) |
| template<typename T > | |
| bool8_t | exists (const std::unordered_set< T > &set, const T &element) |
| geometry_msgs::msg::Point | toGeomMsgPt (const geometry_msgs::msg::Point32 &src) |
| geometry_msgs::msg::Point32 | toGeomMsgPt32 (const lanelet::BasicPoint3d &src) |
| void | adjacentPoints (const size_t i, const size_t N, const geometry_msgs::msg::Polygon poly, geometry_msgs::msg::Point32 *p0, geometry_msgs::msg::Point32 *p1, geometry_msgs::msg::Point32 *p2) |
| std::vector< geometry_msgs::msg::Polygon > | area2Triangle (const lanelet::Area &area) |
| bool8_t | isAcuteAngle (const geometry_msgs::msg::Point32 &vertex_a, const geometry_msgs::msg::Point32 &vertex_o, const geometry_msgs::msg::Point32 &vertex_b) |
| bool8_t | isWithinTriangle (const geometry_msgs::msg::Point32 &vertex_a, const geometry_msgs::msg::Point32 &vertex_b, const geometry_msgs::msg::Point32 &vertex_c, const geometry_msgs::msg::Point32 &pt) |
| using autoware::common::had_map_utils::CGAL_Point = typedef Kernel::Point_2 |
| using autoware::common::had_map_utils::CGAL_Polygon = typedef CGAL::Polygon_2<Kernel> |
| using autoware::common::had_map_utils::CGAL_Polygon_with_holes = typedef CGAL::Polygon_with_holes_2<Kernel> |
| using autoware::common::had_map_utils::Kernel = typedef CGAL::Exact_predicates_exact_constructions_kernel |
| void autoware::common::had_map_utils::adjacentPoints | ( | const size_t | i, |
| const size_t | N, | ||
| const geometry_msgs::msg::Polygon | poly, | ||
| geometry_msgs::msg::Point32 * | p0, | ||
| geometry_msgs::msg::Point32 * | p1, | ||
| geometry_msgs::msg::Point32 * | p2 | ||
| ) |
| geometry_msgs::msg::Polygon autoware::common::had_map_utils::area2Polygon | ( | const lanelet::ConstArea & | area | ) |
converts lanelet::Area into geometry_msgs::msg::Polygon type
| area | input area |
| std::vector<geometry_msgs::msg::Polygon> autoware::common::had_map_utils::area2Triangle | ( | const lanelet::Area & | area | ) |
| visualization_msgs::msg::MarkerArray autoware::common::had_map_utils::areasAsTriangleMarkerArray | ( | const rclcpp::Time & | t, |
| const std::string & | ns, | ||
| const lanelet::Areas & | areas, | ||
| const std_msgs::msg::ColorRGBA & | c | ||
| ) |
converts bounded area by lanelet::Area into triangle markers
| t | Time set to returned marker message |
| ns | Namespace set to returned marker message |
| areas | input lanelet::Area objects |
| c | Color of the marker array |
| visualization_msgs::msg::MarkerArray autoware::common::had_map_utils::areasBoundaryAsMarkerArray | ( | const rclcpp::Time & | t, |
| const std::string & | ns, | ||
| const lanelet::Areas & | areas, | ||
| const std_msgs::msg::ColorRGBA & | c | ||
| ) |
converts outer bound of lanelet::Area into markers with type LINE_STRIP
| t | time set to returned marker message |
| ns | namespace set to the marker |
| areas | input area objects |
| c | color of the marker |
| visualization_msgs::msg::Marker autoware::common::had_map_utils::basicPolygon2Marker | ( | const rclcpp::Time & | t, |
| const int32_t & | line_id, | ||
| const lanelet::BasicPolygon3d & | pg, | ||
| const std::string & | frame_id, | ||
| const std::string & | ns, | ||
| const std_msgs::msg::ColorRGBA & | c, | ||
| const float32_t & | lss | ||
| ) |
creates marker with type LINE_STRIP from a lanelet::BasicPolygon object
| t | timestamp set to the marker |
| line_id | id set to the marker |
| pg | input polygon |
| frame_id | frame id set to the marker |
| ns | namespace set to the marker |
| c | color of the marker |
| lss | linestrip scale (i.e. width) |
| visualization_msgs::msg::Marker autoware::common::had_map_utils::bbox2Marker | ( | const rclcpp::Time & | t, |
| const int32_t & | line_id, | ||
| const float64_t | lower[], | ||
| const float64_t | upper[], | ||
| const std::string & | frame_id, | ||
| const std::string & | ns, | ||
| const std_msgs::msg::ColorRGBA & | c, | ||
| const float32_t & | lss | ||
| ) |
creates marker with type LINE_STRIP from a bounding box
| t | Time set to returned marker message |
| line_id | id set to marker |
| lower | lower bound of the bounding box with length 3(x,y,z) |
| upper | upper bound of the bounding box with length 3(x,y,z) |
| frame_id | frame id set to the marker |
| ns | namespace set to the marker |
| c | color of the marker |
| lss | linestrip scale (i.e. width) |
| visualization_msgs::msg::MarkerArray autoware::common::had_map_utils::boundingBoxAsMarkerArray | ( | const rclcpp::Time & | t, |
| const std::string & | ns, | ||
| const float64_t | upper[], | ||
| const float64_t | lower[], | ||
| const std_msgs::msg::ColorRGBA & | c | ||
| ) |
creates marker array from bounding box
| t | Time set to returned marker message |
| ns | Namespace set to returned marker message |
| upper | upper bound of the bounding box with length 3(x,y,z) |
| lower | lower bound of the bounding box with length 3(x,y,z) |
| c | Color of the marker array |
| std::vector<float64_t> autoware::common::had_map_utils::calculateAccumulatedLengths | ( | const lanelet::ConstLineString3d & | line_string | ) |
| std::vector<float64_t> autoware::common::had_map_utils::calculateSegmentDistances | ( | const lanelet::ConstLineString3d & | line_string | ) |
| lanelet::Polygon3d autoware::common::had_map_utils::coalesce_drivable_areas | ( | const autoware_auto_msgs::msg::Route & | route, |
| const lanelet::LaneletMapPtr & | lanelet_map_ptr | ||
| ) |
| bool8_t autoware::common::had_map_utils::exists | ( | const std::unordered_set< T > & | set, |
| const T & | element | ||
| ) |
| std::pair<size_t, size_t> autoware::common::had_map_utils::findNearestIndexPair | ( | const std::vector< float64_t > & | accumulated_lengths, |
| const float64_t | target_length | ||
| ) |
| void autoware::common::had_map_utils::fromBinaryMsg | ( | const autoware_auto_msgs::msg::HADMapBin & | msg, |
| std::shared_ptr< lanelet::LaneletMap > & | map | ||
| ) |
| lanelet::LineString3d autoware::common::had_map_utils::generateFineCenterline | ( | const lanelet::ConstLanelet & | lanelet_obj, |
| const float64_t | resolution | ||
| ) |
| lanelet::Areas autoware::common::had_map_utils::getAreaLayer | ( | const lanelet::LaneletMapPtr | ll_map | ) |
| lanelet::ConstLanelets autoware::common::had_map_utils::getConstLaneletLayer | ( | const std::shared_ptr< lanelet::LaneletMap > & | ll_map | ) |
| lanelet::Lanelets autoware::common::had_map_utils::getLaneletLayer | ( | const std::shared_ptr< lanelet::LaneletMap > & | ll_map | ) |
| lanelet::LineStrings3d autoware::common::had_map_utils::getLineStringLayer | ( | const lanelet::LaneletMapPtr | ll_map | ) |
| lanelet::Polygons3d autoware::common::had_map_utils::getPolygonLayer | ( | const lanelet::LaneletMapPtr | ll_map | ) |
| bool8_t autoware::common::had_map_utils::isAcuteAngle | ( | const geometry_msgs::msg::Point32 & | vertex_a, |
| const geometry_msgs::msg::Point32 & | vertex_o, | ||
| const geometry_msgs::msg::Point32 & | vertex_b | ||
| ) |
| bool8_t autoware::common::had_map_utils::isWithinTriangle | ( | const geometry_msgs::msg::Point32 & | vertex_a, |
| const geometry_msgs::msg::Point32 & | vertex_b, | ||
| const geometry_msgs::msg::Point32 & | vertex_c, | ||
| const geometry_msgs::msg::Point32 & | pt | ||
| ) |
| geometry_msgs::msg::Polygon autoware::common::had_map_utils::lanelet2Polygon | ( | const lanelet::ConstLanelet & | ll | ) |
converts lanelet::Lanelet into geometry_msgs::msg::Polygon type
| ll | input lanelet |
| std::vector< geometry_msgs::msg::Polygon > autoware::common::had_map_utils::lanelet2Triangle | ( | const lanelet::ConstLanelet & | ll | ) |
converts area enclosed by lanelet::Lanelet into list of triangles.
| ll | input lanelet |
| visualization_msgs::msg::MarkerArray autoware::common::had_map_utils::laneletsAsTriangleMarkerArray | ( | const rclcpp::Time & | t, |
| const std::string & | ns, | ||
| const lanelet::ConstLanelets & | lanelets, | ||
| const std_msgs::msg::ColorRGBA & | c | ||
| ) |
converts bounded area by lanelet::Lanelet into triangle markers
| t | Time set to returned marker message |
| ns | Namespace set to returned marker message |
| lanelets | input lanelet::Lanelet |
| c | Color of the marker array |
| visualization_msgs::msg::MarkerArray autoware::common::had_map_utils::laneletsBoundaryAsMarkerArray | ( | const rclcpp::Time & | t, |
| const lanelet::ConstLanelets & | lanelets, | ||
| const std_msgs::msg::ColorRGBA & | c, | ||
| const bool8_t & | viz_centerline | ||
| ) |
converts outer bound of lanelet::Lanelet into markers with type LINE_STRIP
| t | time set to returned marker message |
| lanelets | input lanelet objects |
| c | color of the marker |
| viz_centerline | option to add centerline to the marker array |
| visualization_msgs::msg::Marker autoware::common::had_map_utils::lineString2Marker | ( | const rclcpp::Time & | t, |
| const lanelet::LineString3d & | ls, | ||
| const std::string & | frame_id, | ||
| const std::string & | ns, | ||
| const std_msgs::msg::ColorRGBA & | c, | ||
| const float32_t & | lss | ||
| ) |
creates marker with type LINE_STRIP from a lanelet::LineString3d object
| t | timestamp set to the marker |
| ls | input linestring |
| frame_id | frame id set to the marker |
| ns | namespace set to the marker |
| c | color of the marker |
| lss | linestrip scale (i.e. width) |
| visualization_msgs::msg::Marker autoware::common::had_map_utils::lineString2Marker | ( | const rclcpp::Time & | t, |
| const lanelet::ConstLineString3d & | ls, | ||
| const std::string & | frame_id, | ||
| const std::string & | ns, | ||
| const std_msgs::msg::ColorRGBA & | c, | ||
| const float32_t & | lss | ||
| ) |
creates marker with type LINE_STRIP from a lanelet::ConstLineString3d object
| t | timestamp set to the marker |
| ls | input linestring |
| frame_id | frame id set to the marker |
| ns | namespace set to the marker |
| c | color of the marker |
| lss | linestrip scale (i.e. width) |
| visualization_msgs::msg::MarkerArray autoware::common::had_map_utils::lineStringsAsMarkerArray | ( | const rclcpp::Time & | t, |
| const std::string & | ns, | ||
| const lanelet::LineStrings3d & | linestrings, | ||
| const std_msgs::msg::ColorRGBA & | c | ||
| ) |
converts lanelet::LineString into markers with type LINE_STRIP
| t | time set to returned marker message |
| ns | namespace set to the marker |
| linestrings | input linestring objects |
| c | color of the marker |
| void autoware::common::had_map_utils::overwriteLaneletsCenterline | ( | lanelet::LaneletMapPtr | lanelet_map, |
| const autoware::common::types::bool8_t | force_overwrite | ||
| ) |
| std::vector< geometry_msgs::msg::Polygon > autoware::common::had_map_utils::polygon2Triangle | ( | const geometry_msgs::msg::Polygon & | polygon | ) |
converts area enclosed by geometry_msg::msg::Polygon into list of triangles.
| polygon | input polygon |
| visualization_msgs::msg::MarkerArray autoware::common::had_map_utils::polygonsBoundaryAsMarkerArray | ( | const rclcpp::Time & | t, |
| const std::string & | ns, | ||
| const lanelet::Polygons3d & | polygons, | ||
| const std_msgs::msg::ColorRGBA & | c | ||
| ) |
converts outer bound of lanelet::Polygon into markers with type LINE_STRIP
| t | Time set to returned marker message |
| ns | namespace set to the marker |
| polygons | input polygons |
| c | color of the marker |
| std::vector<lanelet::BasicPoint3d> autoware::common::had_map_utils::resamplePoints | ( | const lanelet::ConstLineString3d & | line_string, |
| const int32_t | num_segments | ||
| ) |
| void autoware::common::had_map_utils::setColor | ( | std_msgs::msg::ColorRGBA * | cl, |
| const float32_t & | r, | ||
| const float32_t & | g, | ||
| const float32_t & | b, | ||
| const float32_t & | a | ||
| ) |
Set set rgba information to a Color Object.
| [out] | cl | color object to be set |
| r | red value | |
| g | green value | |
| b | blue value | |
| a | alpha value |
| void autoware::common::had_map_utils::setMarkerHeader | ( | visualization_msgs::msg::Marker * | m, |
| const int32_t & | id, | ||
| const rclcpp::Time & | t, | ||
| const std::string & | frame_id, | ||
| const std::string & | ns, | ||
| const std_msgs::msg::ColorRGBA & | c, | ||
| const int32_t & | action, | ||
| const int32_t & | type, | ||
| const float32_t & | scale | ||
| ) |
Set the header information to a marker object.
| m | input marker |
| id | id of the marker |
| t | timestamp of the marker |
| frame_id | frame of the marker |
| ns | namespace of the marker |
| c | color of the marker |
| action | action used to visualize the marker |
| type | type of the marker |
| scale | scale of the marker |
| lanelet::Areas autoware::common::had_map_utils::subtypeAreas | ( | const lanelet::Areas | areas, |
| const char | subtype[] | ||
| ) |
| lanelet::LineStrings3d autoware::common::had_map_utils::subtypeLineStrings | ( | const lanelet::LineStrings3d | linestrings, |
| const char | subtype[] | ||
| ) |
| lanelet::Polygons3d autoware::common::had_map_utils::subtypePolygons | ( | const lanelet::Polygons3d | polygons, |
| const char | subtype[] | ||
| ) |
| void autoware::common::had_map_utils::toBinaryMsg | ( | const std::shared_ptr< lanelet::LaneletMap > & | map, |
| autoware_auto_msgs::msg::HADMapBin & | msg | ||
| ) |
| geometry_msgs::msg::Point autoware::common::had_map_utils::toGeomMsgPt | ( | const geometry_msgs::msg::Point32 & | src | ) |
| geometry_msgs::msg::Point32 autoware::common::had_map_utils::toGeomMsgPt32 | ( | const lanelet::BasicPoint3d & | src | ) |