Static Public Member Functions | Static Public Attributes | List of all members
VIZ::VizHelperRVIZ Class Reference

#include <VizHelperRVIZ.hpp>

Static Public Member Functions

static std::vector< geometry_msgs::PointcalculateAxesPoints (ISM::PointPtr point, ISM::QuaternionPtr quat, float scale)
 
static ColorRGBA confidenceToColor (double confidence)
 
static visualization_msgs::MarkerArray createArrowMarkerFromVote (ISM::VoteSpecifierPtr vote, ISM::ObjectPtr o, std::string baseFrame, std::string ns, int32_t id, double bin_size, std_msgs::ColorRGBA binColor, std_msgs::ColorRGBA voteColor=VizHelperRVIZ::createColorRGBA(1.0, 0.0, 1.0, 0.5))
 
static Marker createArrowMarkerToPoint (ISM::PointPtr fromPoint, ISM::PointPtr to, std::string baseFrame, std::string markerNamespace, int id, float xScale, float yScale, float zScale, ColorRGBA color, double markerLifetime)
 
static Marker createArrowMarkerToPoint (ISM::PointPtr fromPoint, ISM::PointPtr to, std::string baseFrame, std::string markerNamespace, int id, float xScale, float yScale, float zScale, ColorRGBA color, double markerLifetime, double minLength)
 
static ColorRGBA createColorRGBA (float red, float green, float blue, float alpha)
 
static ColorRGBA createColorRGBA (std::vector< float > rgba)
 
static Marker createConeMarker (ISM::PosePtr pose, std::string baseFrame, std::string markerNamespace, int id, float radius, ColorRGBA color, double markerLifetime)
 
static MarkerArray createCoordinateArrow (std::vector< std::pair< ISM::PointPtr, std::vector< ISM::PosePtr > > > poses_vec, std::string baseFrame, std::string markerNamespace, float arrowScale, float axisScale, ColorRGBA color, double markerLifetime)
 
static MarkerArray createCoordinateMarker (ISM::PosePtr pose, std::string baseFrame, std::string markerNamespace, int id, float length, float radius, double markerLifetime)
 
static MarkerArray createCoordinateMarkerWithAngle (ISM::PosePtr pose, std::string baseFrame, std::string markerNamespace, int id, float length, float openAngle, double markerLifetime)
 
static MarkerArray createCubeArrow (ISM::PosePtr pose, std::string baseFrame, std::string markerNamespace, int &id, float scale, ColorRGBA cubeColor, ColorRGBA arrowColor, double markerLifetime)
 
static Marker createCylinderLine (ISM::PosePtr pose, std::string baseFrame, std::string markerNamespace, float scale, float length, ColorRGBA color, double markerLifetime)
 
static Marker createCylinderMarker (ISM::PosePtr pose, std::string baseFrame, std::string markerNamespace, int id, float radius, float height, ColorRGBA color, double markerLifetime)
 
static Marker createLine (ISM::PointPtr fromPoint, ISM::PointPtr toPoint, float width, int id, std::string baseFrame, std::string markerNamespace, std_msgs::ColorRGBA color, double markerLifetime)
 
static Marker createLineArrow (ISM::PointPtr fromPoint, std::vector< ISM::PosePtr > toPoses, std::string baseFrame, std::string markerNamespace, int &id, float arrowScale, ColorRGBA color, double markerLifetime)
 
static Marker createLineMarkerFormPair (std::vector< std::pair< ISM::PointPtr, ISM::PointPtr >> pointPair, std::string baseFrame, std::string markerNamespace, float arrowScale, ColorRGBA color, double markerLifetime)
 
static Marker createMarkerWithoutTypeAndPose (std::string baseFrame, std::string markerNamespace, int id, float xScale, float yScale, float zScale, ColorRGBA color, double markerLifetime)
 
static Marker createMeshMarker (ISM::PosePtr pose, std::string baseFrame, std::string markerNamespace, int id, ColorRGBA color, double markerLifetime, std::string resourcePath)
 
static geometry_msgs::Point createPoint (double x, double y, double z)
 
static MarkerArray createPositionVector (ISM::PosePtr pose, std::string baseFrame, std::string markerNamespace, ColorRGBA color, UniformDistributionGenerator *udg, int sampels, int axis, int id, float length, float openAngle, float sphereRadius, double markerLifetime)
 
static MarkerArray createRingMarker (ISM::PosePtr pose, std::string baseFrame, std::string markerNamespace, float scale, ColorRGBA x, ColorRGBA y, ColorRGBA z, ColorRGBA a, ColorRGBA b, ColorRGBA g, double markerLifetime)
 
static Marker createSphereMarker (ISM::PointPtr point, std::string baseFrame, std::string markerNamespace, int id, float radius, ColorRGBA color, double markerLifetime)
 
static visualization_msgs::MarkerArray createSphereMarkerWithOrientation (ISM::PosePtr pose, std::string baseFrame, std::string markerNamespace, int id, float radius, std_msgs::ColorRGBA color, double markerLifetime, int axesFirstId)
 
static MarkerArray createTrackMarkers (std::vector< ISM::PosePtr > trackPoses, std::string baseFrame, std::string markerNamespace, float lineWidth, ColorRGBA color, double markerLifetime)
 
static geometry_msgs::Point EVector3DToPointMsg (ISM::PointPtr point, Eigen::Vector3d v3d)
 
static geometry_msgs::Point genCuboidPoint (int xp, int yp, int zp, double x, double y, double z, double xwidth, double ywidth, double zwidth)
 
static MarkerArray getBinFromPoint (const ISM::PointPtr point, double sensivity, std::string baseFrame, std_msgs::ColorRGBA color)
 
static Marker getBinMarker (Eigen::Vector3i bin, double bin_size, std::string desc, int id, std::string baseFrame, std_msgs::ColorRGBA color)
 
static Marker getBinMarker (int x, int y, int z, double bin_size, std::string desc, int id, std::string baseFrame, std_msgs::ColorRGBA color)
 
static ColorRGBA getColorOfObject (const ISM::Object &object)
 
static ColorRGBA getColorOfObject (const ISM::ObjectPtr object_ptr)
 
static ColorRGBA hsvToRGBA (double hue, double saturation, double value)
 
static Marker pointToCube (std::string ns, int id, std::string frame, double x, double y, double z, double bin_size, std_msgs::ColorRGBA color)
 
static Marker pointToCuboid (std::string ns, int32_t id, std::string frame, double x, double y, double z, double xwitdh, double ywidth, double zwidth, std_msgs::ColorRGBA color)
 
static geometry_msgs::Point pointToPointMsg (ISM::PointPtr point)
 
static std::vector< ISM::PosePtr > posesFromTrack (ISM::TrackPtr track)
 
static geometry_msgs::Quaternion quatToQuaternionMsg (ISM::QuaternionPtr quat)
 

Static Public Attributes

static std::map< Eigen::Vector3i, bool, cmpVector3ibinDrawn
 

Detailed Description

Definition at line 64 of file VizHelperRVIZ.hpp.

Member Function Documentation

std::vector< geometry_msgs::Point > VIZ::VizHelperRVIZ::calculateAxesPoints ( ISM::PointPtr  point,
ISM::QuaternionPtr  quat,
float  scale 
)
static

Definition at line 562 of file VizHelperRVIZ.cpp.

ColorRGBA VIZ::VizHelperRVIZ::confidenceToColor ( double  confidence)
static
Parameters
confidencein [0.0,1.0]

Definition at line 234 of file VizHelperRVIZ.cpp.

MarkerArray VIZ::VizHelperRVIZ::createArrowMarkerFromVote ( ISM::VoteSpecifierPtr  vote,
ISM::ObjectPtr  o,
std::string  baseFrame,
std::string  ns,
int32_t  id,
double  bin_size,
std_msgs::ColorRGBA  binColor,
std_msgs::ColorRGBA  voteColor = VizHelperRVIZ::createColorRGBA(1.0, 0.0, 1.0, 0.5) 
)
static

Definition at line 46 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::createArrowMarkerToPoint ( ISM::PointPtr  fromPoint,
ISM::PointPtr  to,
std::string  baseFrame,
std::string  markerNamespace,
int  id,
float  xScale,
float  yScale,
float  zScale,
ColorRGBA  color,
double  markerLifetime 
)
static

Definition at line 343 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::createArrowMarkerToPoint ( ISM::PointPtr  fromPoint,
ISM::PointPtr  to,
std::string  baseFrame,
std::string  markerNamespace,
int  id,
float  xScale,
float  yScale,
float  zScale,
ColorRGBA  color,
double  markerLifetime,
double  minLength 
)
static

Definition at line 355 of file VizHelperRVIZ.cpp.

ColorRGBA VIZ::VizHelperRVIZ::createColorRGBA ( float  red,
float  green,
float  blue,
float  alpha 
)
static
Parameters
red,green,blue,alphain [0.0,1.0]

Definition at line 179 of file VizHelperRVIZ.cpp.

ColorRGBA VIZ::VizHelperRVIZ::createColorRGBA ( std::vector< float >  rgba)
static

Definition at line 191 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::createConeMarker ( ISM::PosePtr  pose,
std::string  baseFrame,
std::string  markerNamespace,
int  id,
float  radius,
ColorRGBA  color,
double  markerLifetime 
)
static

Definition at line 315 of file VizHelperRVIZ.cpp.

MarkerArray VIZ::VizHelperRVIZ::createCoordinateArrow ( std::vector< std::pair< ISM::PointPtr, std::vector< ISM::PosePtr > > >  poses_vec,
std::string  baseFrame,
std::string  markerNamespace,
float  arrowScale,
float  axisScale,
ColorRGBA  color,
double  markerLifetime 
)
static

Definition at line 372 of file VizHelperRVIZ.cpp.

visualization_msgs::MarkerArray VIZ::VizHelperRVIZ::createCoordinateMarker ( ISM::PosePtr  pose,
std::string  baseFrame,
std::string  markerNamespace,
int  id,
float  length,
float  radius,
double  markerLifetime 
)
static

Definition at line 836 of file VizHelperRVIZ.cpp.

visualization_msgs::MarkerArray VIZ::VizHelperRVIZ::createCoordinateMarkerWithAngle ( ISM::PosePtr  pose,
std::string  baseFrame,
std::string  markerNamespace,
int  id,
float  length,
float  openAngle,
double  markerLifetime 
)
static

Definition at line 807 of file VizHelperRVIZ.cpp.

MarkerArray VIZ::VizHelperRVIZ::createCubeArrow ( ISM::PosePtr  pose,
std::string  baseFrame,
std::string  markerNamespace,
int &  id,
float  scale,
ColorRGBA  cubeColor,
ColorRGBA  arrowColor,
double  markerLifetime 
)
static

Definition at line 652 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::createCylinderLine ( ISM::PosePtr  pose,
std::string  baseFrame,
std::string  markerNamespace,
float  scale,
float  length,
ColorRGBA  color,
double  markerLifetime 
)
static

Definition at line 739 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::createCylinderMarker ( ISM::PosePtr  pose,
std::string  baseFrame,
std::string  markerNamespace,
int  id,
float  radius,
float  height,
ColorRGBA  color,
double  markerLifetime 
)
static

Definition at line 331 of file VizHelperRVIZ.cpp.

visualization_msgs::Marker VIZ::VizHelperRVIZ::createLine ( ISM::PointPtr  fromPoint,
ISM::PointPtr  toPoint,
float  width,
int  id,
std::string  baseFrame,
std::string  markerNamespace,
std_msgs::ColorRGBA  color,
double  markerLifetime 
)
static

Definition at line 865 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::createLineArrow ( ISM::PointPtr  fromPoint,
std::vector< ISM::PosePtr >  toPoses,
std::string  baseFrame,
std::string  markerNamespace,
int &  id,
float  arrowScale,
ColorRGBA  color,
double  markerLifetime 
)
static

Definition at line 414 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::createLineMarkerFormPair ( std::vector< std::pair< ISM::PointPtr, ISM::PointPtr >>  pointPair,
std::string  baseFrame,
std::string  markerNamespace,
float  arrowScale,
ColorRGBA  color,
double  markerLifetime 
)
static

Definition at line 427 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::createMarkerWithoutTypeAndPose ( std::string  baseFrame,
std::string  markerNamespace,
int  id,
float  xScale,
float  yScale,
float  zScale,
ColorRGBA  color,
double  markerLifetime 
)
static
Parameters
markerLifetimeif 0 then the marker will not deleted automatically, else markerLifetime will be interpreted as seconds.

Definition at line 281 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::createMeshMarker ( ISM::PosePtr  pose,
std::string  baseFrame,
std::string  markerNamespace,
int  id,
ColorRGBA  color,
double  markerLifetime,
std::string  resourcePath 
)
static

Definition at line 441 of file VizHelperRVIZ.cpp.

geometry_msgs::Point VIZ::VizHelperRVIZ::createPoint ( double  x,
double  y,
double  z 
)
static

Definition at line 584 of file VizHelperRVIZ.cpp.

visualization_msgs::MarkerArray VIZ::VizHelperRVIZ::createPositionVector ( ISM::PosePtr  pose,
std::string  baseFrame,
std::string  markerNamespace,
ColorRGBA  color,
UniformDistributionGenerator udg,
int  sampels,
int  axis,
int  id,
float  length,
float  openAngle,
float  sphereRadius,
double  markerLifetime 
)
static

Definition at line 759 of file VizHelperRVIZ.cpp.

MarkerArray VIZ::VizHelperRVIZ::createRingMarker ( ISM::PosePtr  pose,
std::string  baseFrame,
std::string  markerNamespace,
float  scale,
ColorRGBA  x,
ColorRGBA  y,
ColorRGBA  z,
ColorRGBA  a,
ColorRGBA  b,
ColorRGBA  g,
double  markerLifetime 
)
static

Definition at line 593 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::createSphereMarker ( ISM::PointPtr  point,
std::string  baseFrame,
std::string  markerNamespace,
int  id,
float  radius,
ColorRGBA  color,
double  markerLifetime 
)
static

Definition at line 301 of file VizHelperRVIZ.cpp.

visualization_msgs::MarkerArray VIZ::VizHelperRVIZ::createSphereMarkerWithOrientation ( ISM::PosePtr  pose,
std::string  baseFrame,
std::string  markerNamespace,
int  id,
float  radius,
std_msgs::ColorRGBA  color,
double  markerLifetime,
int  axesFirstId 
)
static

Definition at line 90 of file VizHelperRVIZ.cpp.

MarkerArray VIZ::VizHelperRVIZ::createTrackMarkers ( std::vector< ISM::PosePtr >  trackPoses,
std::string  baseFrame,
std::string  markerNamespace,
float  lineWidth,
ColorRGBA  color,
double  markerLifetime 
)
static

Definition at line 469 of file VizHelperRVIZ.cpp.

static geometry_msgs::Point VIZ::VizHelperRVIZ::EVector3DToPointMsg ( ISM::PointPtr  point,
Eigen::Vector3d  v3d 
)
static
geometry_msgs::Point VIZ::VizHelperRVIZ::genCuboidPoint ( int  xp,
int  yp,
int  zp,
double  x,
double  y,
double  z,
double  xwidth,
double  ywidth,
double  zwidth 
)
static

Definition at line 678 of file VizHelperRVIZ.cpp.

MarkerArray VIZ::VizHelperRVIZ::getBinFromPoint ( const ISM::PointPtr  point,
double  sensivity,
std::string  baseFrame,
std_msgs::ColorRGBA  color 
)
static

Definition at line 528 of file VizHelperRVIZ.cpp.

visualization_msgs::Marker VIZ::VizHelperRVIZ::getBinMarker ( Eigen::Vector3i  bin,
double  bin_size,
std::string  desc,
int  id,
std::string  baseFrame,
std_msgs::ColorRGBA  color 
)
static

Definition at line 547 of file VizHelperRVIZ.cpp.

visualization_msgs::Marker VIZ::VizHelperRVIZ::getBinMarker ( int  x,
int  y,
int  z,
double  bin_size,
std::string  desc,
int  id,
std::string  baseFrame,
std_msgs::ColorRGBA  color 
)
static

Definition at line 553 of file VizHelperRVIZ.cpp.

ColorRGBA VIZ::VizHelperRVIZ::getColorOfObject ( const ISM::Object &  object)
static

Definition at line 240 of file VizHelperRVIZ.cpp.

ColorRGBA VIZ::VizHelperRVIZ::getColorOfObject ( const ISM::ObjectPtr  object_ptr)
static

Definition at line 275 of file VizHelperRVIZ.cpp.

ColorRGBA VIZ::VizHelperRVIZ::hsvToRGBA ( double  hue,
double  saturation,
double  value 
)
static
Parameters
huein [0.0,360.0]; saturation and value in [0.0,1.0]

Definition at line 200 of file VizHelperRVIZ.cpp.

visualization_msgs::Marker VIZ::VizHelperRVIZ::pointToCube ( std::string  ns,
int  id,
std::string  frame,
double  x,
double  y,
double  z,
double  bin_size,
std_msgs::ColorRGBA  color 
)
static

Definition at line 753 of file VizHelperRVIZ.cpp.

Marker VIZ::VizHelperRVIZ::pointToCuboid ( std::string  ns,
int32_t  id,
std::string  frame,
double  x,
double  y,
double  z,
double  xwitdh,
double  ywidth,
double  zwidth,
std_msgs::ColorRGBA  color 
)
static

Definition at line 688 of file VizHelperRVIZ.cpp.

geometry_msgs::Point VIZ::VizHelperRVIZ::pointToPointMsg ( ISM::PointPtr  point)
static

Definition at line 27 of file VizHelperRVIZ.cpp.

std::vector< ISM::PosePtr > VIZ::VizHelperRVIZ::posesFromTrack ( ISM::TrackPtr  track)
static

Definition at line 160 of file VizHelperRVIZ.cpp.

geometry_msgs::Quaternion VIZ::VizHelperRVIZ::quatToQuaternionMsg ( ISM::QuaternionPtr  quat)
static

Definition at line 36 of file VizHelperRVIZ.cpp.

Member Data Documentation

std::map< Eigen::Vector3i, bool, cmpVector3i > VIZ::VizHelperRVIZ::binDrawn
static

Definition at line 157 of file VizHelperRVIZ.hpp.


The documentation for this class was generated from the following files:


asr_ism_visualizations
Author(s): Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Meißner Pascal, Reckling Reno, Stöckle Patrick, Trautmann Jeremias
autogenerated on Fri Nov 8 2019 03:28:47