|
static std::vector< geometry_msgs::Point > | calculateAxesPoints (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) |
|