Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added a namespace argument to publishLines(). #169

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
60 changes: 33 additions & 27 deletions include/rviz_visual_tools/rviz_visual_tools.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,10 @@
#include <vector>

// Eigen
#include <Eigen/Geometry>
#include <eigen_stl_containers/eigen_stl_vector_container.h>

#include <Eigen/Geometry>

// Rviz
#include <visualization_msgs/Marker.h>
#include <visualization_msgs/MarkerArray.h>
Expand All @@ -57,12 +58,12 @@
#include <boost/shared_ptr.hpp>

// Messages
#include <shape_msgs/Mesh.h>
#include <std_msgs/ColorRGBA.h>
#include <graph_msgs/GeometryGraph.h>
#include <geometry_msgs/Polygon.h>
#include <geometry_msgs/PoseArray.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Polygon.h>
#include <graph_msgs/GeometryGraph.h>
#include <shape_msgs/Mesh.h>
#include <std_msgs/ColorRGBA.h>
#include <trajectory_msgs/JointTrajectory.h>

// rviz_visual_tools
Expand Down Expand Up @@ -502,15 +503,15 @@ class RvizVisualTools
* \return true on success
*/
bool publishSpheres(const EigenSTL::vector_Vector3d& points, colors color = BLUE, scales scale = MEDIUM,
const std::string& ns = "Spheres");
const std::string& ns = "Spheres", std::size_t id = 0);
bool publishSpheres(const EigenSTL::vector_Vector3d& points, colors color, double scale = 0.1,
const std::string& ns = "Spheres");
const std::string& ns = "Spheres", std::size_t id = 0);
bool publishSpheres(const std::vector<geometry_msgs::Point>& points, colors color = BLUE, scales scale = MEDIUM,
const std::string& ns = "Spheres");
const std::string& ns = "Spheres", std::size_t id = 0);
bool publishSpheres(const std::vector<geometry_msgs::Point>& points, colors color = BLUE, double scale = 0.1,
const std::string& ns = "Spheres");
const std::string& ns = "Spheres", std::size_t id = 0);
bool publishSpheres(const std::vector<geometry_msgs::Point>& points, colors color,
const geometry_msgs::Vector3& scale, const std::string& ns = "Spheres");
const geometry_msgs::Vector3& scale, const std::string& ns = "Spheres", std::size_t id = 0);

/**
* \brief Display a marker of a series of spheres, with the possibility of different colors
Expand All @@ -521,9 +522,9 @@ class RvizVisualTools
* \return true on success
*/
bool publishSpheres(const EigenSTL::vector_Vector3d& points, const std::vector<colors>& colors, scales scale = MEDIUM,
const std::string& ns = "Spheres");
const std::string& ns = "Spheres", std::size_t id = 0);
bool publishSpheres(const std::vector<geometry_msgs::Point>& points, const std::vector<std_msgs::ColorRGBA>& colors,
const geometry_msgs::Vector3& scale, const std::string& ns = "Spheres");
const geometry_msgs::Vector3& scale, const std::string& ns = "Spheres", std::size_t id = 0);

/**
* \brief Display an arrow along the x-axis of a pose
Expand Down Expand Up @@ -649,12 +650,15 @@ class RvizVisualTools
* \param bPoints - x,y,z of end of line, as a vector
* \param colors - an enum pre-defined name of a color
* \param scale - an enum pre-defined name of a size
* \param ns - namespace of marker
* \return true on success
*/
bool publishLines(const EigenSTL::vector_Vector3d& aPoints, const EigenSTL::vector_Vector3d& bPoints,
const std::vector<colors>& colors, scales scale = MEDIUM);
const std::vector<colors>& colors, scales scale = MEDIUM, const std::string& ns = "Line Array",
std::size_t id = 0);
bool publishLines(const std::vector<geometry_msgs::Point>& aPoints, const std::vector<geometry_msgs::Point>& bPoints,
const std::vector<std_msgs::ColorRGBA>& colors, const geometry_msgs::Vector3& scale);
const std::vector<std_msgs::ColorRGBA>& colors, const geometry_msgs::Vector3& scale,
const std::string& ns = "Line Array", std::size_t id = 0);

/**
* \brief Display a series of connected lines using the LINE_STRIP method - deprecated because visual bugs
Expand All @@ -676,17 +680,19 @@ class RvizVisualTools
* \return true on success
*/
bool publishPath(const std::vector<geometry_msgs::Pose>& path, colors color = RED, scales scale = MEDIUM,
const std::string& ns = "Path");
const std::string& ns = "Path", std::size_t id = 0);
bool publishPath(const std::vector<geometry_msgs::Point>& path, colors color, scales scale,
const std::string& ns = "Path");
bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color, scales scale, const std::string& ns = "Path");
bool publishPath(const EigenSTL::vector_Vector3d& path, colors color, scales scale, const std::string& ns = "Path");
const std::string& ns = "Path", std::size_t id = 0);
bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color, scales scale, const std::string& ns = "Path",
std::size_t id = 0);
bool publishPath(const EigenSTL::vector_Vector3d& path, colors color, scales scale, const std::string& ns = "Path",
std::size_t id = 0);
bool publishPath(const std::vector<geometry_msgs::Point>& path, colors color = RED, double radius = 0.01,
const std::string& ns = "Path");
const std::string& ns = "Path", std::size_t id = 0);
bool publishPath(const EigenSTL::vector_Vector3d& path, colors color = RED, double radius = 0.01,
const std::string& ns = "Path");
const std::string& ns = "Path", std::size_t id = 0);
bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color = RED, double radius = 0.01,
const std::string& ns = "Path");
const std::string& ns = "Path", std::size_t id = 0);

/**
* \brief Display a marker of a series of connected colored cylinders
Expand Down Expand Up @@ -819,11 +825,11 @@ class RvizVisualTools
* \return true on success
*/
bool publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, colors color = BLUE,
scales scale = MEDIUM, const std::string& ns = "Cylinder");
scales scale = MEDIUM, const std::string& ns = "Cylinder", std::size_t id = 0);
bool publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, colors color, double radius = 0.01,
const std::string& ns = "Cylinder");
const std::string& ns = "Cylinder", std::size_t id = 0);
bool publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, const std_msgs::ColorRGBA& color,
double radius = 0.01, const std::string& ns = "Cylinder");
double radius = 0.01, const std::string& ns = "Cylinder", std::size_t id = 0);

/**
* \brief Display a marker of a cylinder
Expand All @@ -834,11 +840,11 @@ class RvizVisualTools
* \return true on success
*/
bool publishCylinder(const Eigen::Isometry3d& pose, colors color = BLUE, double height = 0.1, double radius = 0.01,
const std::string& ns = "Cylinder");
const std::string& ns = "Cylinder", std::size_t id = 0);
bool publishCylinder(const geometry_msgs::Pose& pose, colors color = BLUE, double height = 0.1, double radius = 0.01,
const std::string& ns = "Cylinder");
const std::string& ns = "Cylinder", std::size_t id = 0);
bool publishCylinder(const geometry_msgs::Pose& pose, const std_msgs::ColorRGBA& color, double height = 0.1,
double radius = 0.01, const std::string& ns = "Cylinder");
double radius = 0.01, const std::string& ns = "Cylinder", std::size_t id = 0);

/**
* \brief Display a mesh from file
Expand Down
Loading