AWViz-ROS
Loading...
Searching...
No Matches
awviz_plugin Namespace Reference

Namespaces

namespace  anonymous_namespace{lanelet_display.cpp}
 
namespace  anonymous_namespace{predicted_objects_display.cpp}
 
namespace  anonymous_namespace{trajectory_display.cpp}
 

Classes

class  CameraInfoDisplay
 Display plugin of sensor_msgs::msg::CameraInfo. More...
 
class  CompressedImageDisplay
 Display plugin of sensor_msgs::msg::CompressedImage. More...
 
class  DetectedObjectsDisplay
 
class  ImageDisplay
 Display plugin of sensor_msgs::msg::Image. More...
 
class  LaneletDisplay
 A display plugin for autoware_map_msgs::msg::LaneletMapBin. More...
 
class  LaneletLineStrips
 A class stores a set of line strips, and creates a new rerun::LineStrips3D object. More...
 
class  NavSatFixDisplay
 Display plugin of sensor_msgs::msg::NavSatFix. More...
 
class  PointCloud2Display
 Display plugin of sensor_msgs::msg::PointCloud2. More...
 
class  PredictedObjectsDisplay
 Display plugin of autoware_perception_msgs::msg::PredictedObjects. More...
 
class  TrackedObjectsDisplay
 
class  TrajectoryDisplay
 A display plugin for autoware_planning_msgs::msg::Trajectory. More...
 

Functions

bool has_attribute (const lanelet::ConstLineString3d &linestring, const std::set< std::string > &attributes)
 Check if the input linestring has same attribute in the specified set of attributes.
 
LaneletLineStrips convert_road_lanelets (const lanelet::LaneletLayer &layer, const lanelet::ConstLanelets &lanelets)
 Convert road lanelets to line strips.
 
LaneletLineStrips convert_road_boundaries (const lanelet::ConstLanelets &lanelets)
 Convert road boundaries to line strips.
 
LaneletLineStrips convert_centerlines (const lanelet::ConstLanelets &lanelets)
 Convert centerlines to line strips.
 
LaneletLineStrips convert_stop_lines (const lanelet::LineStringLayer &layer)
 Convert stop lines to line strips.
 
std::vector< LaneletLineStripsconvert_crosswalks (const lanelet::ConstLanelets &lanelets)
 Convert crosswalks to line strips.
 
std::vector< rerun::Color > colormap (const std::vector< float > &values)
 Return a color map as a list of rerun::Color.
 

Variables

constexpr float TurboBytes [256][3]
 

Function Documentation

◆ colormap()

std::vector< rerun::Color > awviz_plugin::colormap ( const std::vector< float > &  values)
inline

Return a color map as a list of rerun::Color.

Parameters
valuesList of colors.

◆ convert_centerlines()

LaneletLineStrips awviz_plugin::convert_centerlines ( const lanelet::ConstLanelets &  lanelets)

Convert centerlines to line strips.

Parameters
laneletsSet of all lanelets associated with the vector map.
Returns
LaneletLineStrips object.

◆ convert_crosswalks()

std::vector< LaneletLineStrips > awviz_plugin::convert_crosswalks ( const lanelet::ConstLanelets &  lanelets)

Convert crosswalks to line strips.

Parameters
laneletsSet of all lanelets associated with the vector map.
Returns
Vector of LaneletLineStrips.

◆ convert_road_boundaries()

LaneletLineStrips awviz_plugin::convert_road_boundaries ( const lanelet::ConstLanelets &  lanelets)

Convert road boundaries to line strips.

Parameters
laneletsSet of all lanelets associated with the vector map.
Returns
LaneletLineStrips object.

◆ convert_road_lanelets()

LaneletLineStrips awviz_plugin::convert_road_lanelets ( const lanelet::LaneletLayer &  layer,
const lanelet::ConstLanelets &  lanelets 
)

Convert road lanelets to line strips.

Parameters
layerLanelet layer.
laneletsSet of all lanelets associated with the vector map.
Returns
LaneletLineStrips object.

◆ convert_stop_lines()

LaneletLineStrips awviz_plugin::convert_stop_lines ( const lanelet::LineStringLayer &  layer)

Convert stop lines to line strips.

Parameters
layerLineString layer.
Returns
LaneletLineStrips object.

◆ has_attribute()

bool awviz_plugin::has_attribute ( const lanelet::ConstLineString3d &  linestring,
const std::set< std::string > &  attributes 
)

Check if the input linestring has same attribute in the specified set of attributes.

Parameters
linestringLineString object.
attributesSet of attributes.
Returns
Return true if the linestring has.

Variable Documentation

◆ TurboBytes

constexpr float awviz_plugin::TurboBytes[256][3]
constexpr