diff --git a/.clang-format b/.clang-format deleted file mode 100644 index 5bde1c45..00000000 --- a/.clang-format +++ /dev/null @@ -1,66 +0,0 @@ ---- -BasedOnStyle: Google -AccessModifierOffset: -2 -ConstructorInitializerIndentWidth: 2 -AlignEscapedNewlinesLeft: false -AlignTrailingComments: true -AllowAllParametersOfDeclarationOnNextLine: false -AllowShortIfStatementsOnASingleLine: false -AllowShortLoopsOnASingleLine: false -AllowShortFunctionsOnASingleLine: None -AllowShortLoopsOnASingleLine: false -AlwaysBreakTemplateDeclarations: true -AlwaysBreakBeforeMultilineStrings: false -BreakBeforeBinaryOperators: false -BreakBeforeTernaryOperators: false -BreakConstructorInitializersBeforeComma: true -BinPackParameters: true -ColumnLimit: 100 -ConstructorInitializerAllOnOneLineOrOnePerLine: true -DerivePointerBinding: false -PointerBindsToType: true -ExperimentalAutoDetectBinPacking: false -IndentCaseLabels: true -MaxEmptyLinesToKeep: 1 -NamespaceIndentation: None -ObjCSpaceBeforeProtocolList: true -PenaltyBreakBeforeFirstCallParameter: 19 -PenaltyBreakComment: 60 -PenaltyBreakString: 100 -PenaltyBreakFirstLessLess: 1000 -PenaltyExcessCharacter: 1000 -PenaltyReturnTypeOnItsOwnLine: 70 -SpacesBeforeTrailingComments: 2 -Cpp11BracedListStyle: false -Standard: Auto -IndentWidth: 2 -TabWidth: 2 -UseTab: Never -IndentFunctionDeclarationAfterType: false -SpacesInParentheses: false -SpacesInAngles: false -SpaceInEmptyParentheses: false -SpacesInCStyleCastParentheses: false -SpaceAfterControlStatementKeyword: true -SpaceBeforeAssignmentOperators: true -ContinuationIndentWidth: 4 -SortIncludes: false -SpaceAfterCStyleCast: false - -# Configure each individual brace in BraceWrapping -BreakBeforeBraces: Custom - -# Control of individual brace wrapping cases -BraceWrapping: { - AfterClass: 'true' - AfterControlStatement: 'true' - AfterEnum : 'true' - AfterFunction : 'true' - AfterNamespace : 'true' - AfterStruct : 'true' - AfterUnion : 'true' - BeforeCatch : 'true' - BeforeElse : 'true' - IndentBraces : 'false' -} -... diff --git a/.clang-tidy b/.clang-tidy deleted file mode 100644 index 7fae3668..00000000 --- a/.clang-tidy +++ /dev/null @@ -1,50 +0,0 @@ ---- -Checks: '-*, - performance-*, - llvm-namespace-comment, - modernize-redundant-void-arg, - modernize-use-nullptr, - modernize-use-default, - modernize-use-override, - modernize-loop-convert, - readability-named-parameter, - readability-redundant-smartptr-get, - readability-redundant-string-cstr, - readability-simplify-boolean-expr, - readability-container-size-empty, - readability-identifier-naming, - ' -HeaderFilterRegex: '' -AnalyzeTemporaryDtors: false -CheckOptions: - - key: llvm-namespace-comment.ShortNamespaceLines - value: '10' - - key: llvm-namespace-comment.SpacesBeforeComments - value: '2' - - key: readability-braces-around-statements.ShortStatementLines - value: '2' - # type names - - key: readability-identifier-naming.ClassCase - value: CamelCase - - key: readability-identifier-naming.EnumCase - value: CamelCase - - key: readability-identifier-naming.UnionCase - value: CamelCase - # method names - - key: readability-identifier-naming.MethodCase - value: camelBack - # variable names - - key: readability-identifier-naming.VariableCase - value: lower_case - - key: readability-identifier-naming.ClassMemberSuffix - value: '_' - # const static or global variables are UPPER_CASE - - key: readability-identifier-naming.EnumConstantCase - value: UPPER_CASE - - key: readability-identifier-naming.StaticConstantCase - value: UPPER_CASE - - key: readability-identifier-naming.ClassConstantCase - value: UPPER_CASE - - key: readability-identifier-naming.GlobalVariableCase - value: UPPER_CASE -... diff --git a/.travis.yml b/.travis.yml index 7b6c851f..051d3f06 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,26 +1,23 @@ -# This config file for Travis CI utilizes https://github.com/ros-planning/moveit_ci package. -sudo: required -dist: xenial # distro used by Travis, moveit_ci uses the docker image's distro +language: generic services: - docker -language: cpp -compiler: gcc -cache: ccache + +cache: + directories: + - $HOME/.ccache + +git: + quiet: true env: global: - - ROS_DISTRO=eloquent - ROS_REPO=ros - - CXXFLAGS="-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unused-parameter -Wno-unused-function" - - WARNINGS_OK=false + - CCACHE_DIR=$HOME/.ccache + - UPSTREAM_WORKSPACE="rviz_visual_tools.repos" matrix: - - TEST="clang-format" # TODO(davetcoleman): enable catkin_lint in the future - - TEST=clang-tidy-fix - - TEST=clang-tidy-check - - ROS_DISTRO=eloquent - -before_script: - - git clone -q -b ros2 --depth=1 https://github.com/ros-planning/moveit_ci.git .moveit_ci + - ROS_DISTRO="eloquent" +install: + - git clone --quiet --depth 1 https://github.com/ros-industrial/industrial_ci.git .industrial_ci -b master script: - - .moveit_ci/travis.sh + - .industrial_ci/travis.sh diff --git a/CMakeLists.txt b/CMakeLists.txt index d82f6e51..674cb43f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -230,6 +230,10 @@ ament_export_libraries( ## TEST ## ########## if (BUILD_TESTING) + # ROS2 linters + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + # Run tests find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(${PROJECT_NAME}_rvt_test @@ -244,4 +248,4 @@ if (BUILD_TESTING) ) endif() -ament_package() \ No newline at end of file +ament_package() diff --git a/include/rviz_visual_tools/remote_control.hpp b/include/rviz_visual_tools/remote_control.hpp index bfd9fc42..01b078e5 100644 --- a/include/rviz_visual_tools/remote_control.hpp +++ b/include/rviz_visual_tools/remote_control.hpp @@ -47,6 +47,7 @@ // ROS #include #include +#include namespace rviz_visual_tools { @@ -121,7 +122,7 @@ class RemoteControl void setDisplayWaitingState(DisplayWaitingState displayWaitingState) { - displayWaitingState_ = displayWaitingState; + displayWaitingState_ = std::move(displayWaitingState); } private: diff --git a/include/rviz_visual_tools/rviz_visual_tools.hpp b/include/rviz_visual_tools/rviz_visual_tools.hpp index 25816d5c..1ea77f0d 100644 --- a/include/rviz_visual_tools/rviz_visual_tools.hpp +++ b/include/rviz_visual_tools/rviz_visual_tools.hpp @@ -84,7 +84,7 @@ static const double SMALL_SCALE = 0.001; static const double LARGE_SCALE = 100; // Note: when adding new colors to colors, also add them to getRandColor() function -enum colors +enum Colors { BLACK = 0, BROWN = 1, @@ -109,7 +109,7 @@ enum colors DEFAULT = 20 // i.e. 'do not change default color' }; -enum scales +enum Scales { XXXXSMALL = 1, XXXSMALL = 2, @@ -301,23 +301,23 @@ class RvizVisualTools * \brief Get a random color from the list of hardcoded enum color types * \return Random color from colors */ - static colors getRandColor(); + static Colors getRandColor(); /** * \brief Get the RGB value of standard colors * \param color - an enum pre-defined name of a color * \return the RGB message equivalent */ - std_msgs::msg::ColorRGBA getColor(colors color) const; + std_msgs::msg::ColorRGBA getColor(Colors color) const; /** \brief Used by interfaces that do not directly depend on Rviz Visual Tools, such as OMPL */ - static colors intToRvizColor(std::size_t color); + static Colors intToRvizColor(std::size_t color); /** \brief Used by interfaces that do not directly depend on Rviz Visual Tools, such as OMPL */ - static rviz_visual_tools::scales intToRvizScale(std::size_t scale); + static rviz_visual_tools::Scales intToRvizScale(std::size_t scale); /** \brief Convert an enum to its string name equivalent */ - static std::string scaleToString(scales scale); + static std::string scaleToString(Scales scale); /** * \brief Create a random color that is not too light @@ -343,7 +343,7 @@ class RvizVisualTools * \param marker_scale - amount to scale the scale for accounting for different types of markers * \return vector of 3 scales */ - geometry_msgs::msg::Vector3 getScale(scales scale, double marker_scale = 1.0) const; + geometry_msgs::msg::Vector3 getScale(Scales scale, double marker_scale = 1.0) const; /** * \brief Create a vector that points from point a to point b @@ -446,9 +446,9 @@ class RvizVisualTools * \param scale - size of the cone * \return true on success */ - bool publishCone(const Eigen::Isometry3d& pose, double angle, colors color = TRANSLUCENT, + bool publishCone(const Eigen::Isometry3d& pose, double angle, Colors color = TRANSLUCENT, double scale = 1.0); - bool publishCone(const geometry_msgs::msg::Pose& pose, double angle, colors color = TRANSLUCENT, + bool publishCone(const geometry_msgs::msg::Pose& pose, double angle, Colors color = TRANSLUCENT, double scale = 1.0); /** @@ -465,7 +465,7 @@ class RvizVisualTools * \return true on success */ bool publishABCDPlane(const double A, const double B, const double C, const double D, - colors color = TRANSLUCENT, double x_width = 1.0, double y_width = 1.0); + Colors color = TRANSLUCENT, double x_width = 1.0, double y_width = 1.0); /** * \brief Display the XY plane of a given pose @@ -474,9 +474,9 @@ class RvizVisualTools * \param scale - the size of the vizualized plane * \return true on success */ - bool publishXYPlane(const Eigen::Isometry3d& pose, colors color = TRANSLUCENT, + bool publishXYPlane(const Eigen::Isometry3d& pose, Colors color = TRANSLUCENT, double scale = 1.0); - bool publishXYPlane(const geometry_msgs::msg::Pose& pose, colors color = TRANSLUCENT, + bool publishXYPlane(const geometry_msgs::msg::Pose& pose, Colors color = TRANSLUCENT, double scale = 1.0); /** @@ -486,9 +486,9 @@ class RvizVisualTools * \param scale - the size of the vizualized plane * \return true on success */ - bool publishXZPlane(const Eigen::Isometry3d& pose, colors color = TRANSLUCENT, + bool publishXZPlane(const Eigen::Isometry3d& pose, Colors color = TRANSLUCENT, double scale = 1.0); - bool publishXZPlane(const geometry_msgs::msg::Pose& pose, colors color = TRANSLUCENT, + bool publishXZPlane(const geometry_msgs::msg::Pose& pose, Colors color = TRANSLUCENT, double scale = 1.0); /** @@ -498,9 +498,9 @@ class RvizVisualTools * \param scale - the size of the vizualized plane * \return true on success */ - bool publishYZPlane(const Eigen::Isometry3d& pose, colors color = TRANSLUCENT, + bool publishYZPlane(const Eigen::Isometry3d& pose, Colors color = TRANSLUCENT, double scale = 1.0); - bool publishYZPlane(const geometry_msgs::msg::Pose& pose, colors color = TRANSLUCENT, + bool publishYZPlane(const geometry_msgs::msg::Pose& pose, Colors color = TRANSLUCENT, double scale = 1.0); /** @@ -513,19 +513,19 @@ class RvizVisualTools * to incremental counter * \return true on success */ - bool publishSphere(const Eigen::Isometry3d& pose, colors color = BLUE, scales scale = MEDIUM, + bool publishSphere(const Eigen::Isometry3d& pose, Colors color = BLUE, Scales scale = MEDIUM, const std::string& ns = "Sphere", std::size_t id = 0); - bool publishSphere(const Eigen::Vector3d& point, colors color = BLUE, scales scale = MEDIUM, + bool publishSphere(const Eigen::Vector3d& point, Colors color = BLUE, Scales scale = MEDIUM, const std::string& ns = "Sphere", std::size_t id = 0); - bool publishSphere(const Eigen::Vector3d& point, colors color, double scale, + bool publishSphere(const Eigen::Vector3d& point, Colors color, double scale, const std::string& ns = "Sphere", std::size_t id = 0); - bool publishSphere(const geometry_msgs::msg::Point& point, colors color = BLUE, - scales scale = MEDIUM, const std::string& ns = "Sphere", std::size_t id = 0); - bool publishSphere(const geometry_msgs::msg::Pose& pose, colors color = BLUE, - scales scale = MEDIUM, const std::string& ns = "Sphere", std::size_t id = 0); - bool publishSphere(const geometry_msgs::msg::Pose& pose, colors color, double scale, + bool publishSphere(const geometry_msgs::msg::Point& point, Colors color = BLUE, + Scales scale = MEDIUM, const std::string& ns = "Sphere", std::size_t id = 0); + bool publishSphere(const geometry_msgs::msg::Pose& pose, Colors color = BLUE, + Scales scale = MEDIUM, const std::string& ns = "Sphere", std::size_t id = 0); + bool publishSphere(const geometry_msgs::msg::Pose& pose, Colors color, double scale, const std::string& ns = "Sphere", std::size_t id = 0); - bool publishSphere(const geometry_msgs::msg::Pose& pose, colors color, + bool publishSphere(const geometry_msgs::msg::Pose& pose, Colors color, const geometry_msgs::msg::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0); bool publishSphere(const geometry_msgs::msg::Pose& pose, const std_msgs::msg::ColorRGBA& color, @@ -537,7 +537,7 @@ class RvizVisualTools bool publishSphere(const Eigen::Vector3d& point, const std_msgs::msg::ColorRGBA& color, const geometry_msgs::msg::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0); - bool publishSphere(const geometry_msgs::msg::PoseStamped& pose, colors color, + bool publishSphere(const geometry_msgs::msg::PoseStamped& pose, Colors color, const geometry_msgs::msg::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0); @@ -549,15 +549,15 @@ class RvizVisualTools * \param ns - namespace of marker * \return true on success */ - bool publishSpheres(const EigenSTL::vector_Vector3d& points, colors color = BLUE, - scales scale = MEDIUM, const std::string& ns = "Spheres"); - bool publishSpheres(const EigenSTL::vector_Vector3d& points, colors color, double scale = 0.1, + bool publishSpheres(const EigenSTL::vector_Vector3d& points, Colors color = BLUE, + Scales scale = MEDIUM, const std::string& ns = "Spheres"); + bool publishSpheres(const EigenSTL::vector_Vector3d& points, Colors color, double scale = 0.1, const std::string& ns = "Spheres"); - bool publishSpheres(const std::vector& points, colors color = BLUE, - scales scale = MEDIUM, const std::string& ns = "Spheres"); - bool publishSpheres(const std::vector& points, colors color = BLUE, + bool publishSpheres(const std::vector& points, Colors color = BLUE, + Scales scale = MEDIUM, const std::string& ns = "Spheres"); + bool publishSpheres(const std::vector& points, Colors color = BLUE, double scale = 0.1, const std::string& ns = "Spheres"); - bool publishSpheres(const std::vector& points, colors color, + bool publishSpheres(const std::vector& points, Colors color, const geometry_msgs::msg::Vector3& scale, const std::string& ns = "Spheres"); /** @@ -568,8 +568,8 @@ class RvizVisualTools * \param ns - namespace of marker * \return true on success */ - bool publishSpheres(const EigenSTL::vector_Vector3d& points, const std::vector& colors, - scales scale = MEDIUM, const std::string& ns = "Spheres"); + bool publishSpheres(const EigenSTL::vector_Vector3d& points, const std::vector& colors, + Scales scale = MEDIUM, const std::string& ns = "Spheres"); bool publishSpheres(const std::vector& points, const std::vector& colors, const geometry_msgs::msg::Vector3& scale, const std::string& ns = "Spheres"); @@ -582,12 +582,12 @@ class RvizVisualTools * \param length - the length of the arrow tail, if zero, will auto set with scale * \return true on success */ - bool publishXArrow(const Eigen::Isometry3d& pose, colors color = RED, scales scale = MEDIUM, + bool publishXArrow(const Eigen::Isometry3d& pose, Colors color = RED, Scales scale = MEDIUM, double length = 0.0); - bool publishXArrow(const geometry_msgs::msg::Pose& pose, colors color = RED, - scales scale = MEDIUM, double length = 0.0); - bool publishXArrow(const geometry_msgs::msg::PoseStamped& pose, colors color = RED, - scales scale = MEDIUM, double length = 0.0); + bool publishXArrow(const geometry_msgs::msg::Pose& pose, Colors color = RED, + Scales scale = MEDIUM, double length = 0.0); + bool publishXArrow(const geometry_msgs::msg::PoseStamped& pose, Colors color = RED, + Scales scale = MEDIUM, double length = 0.0); /** * \brief Display an arrow along the y-axis of a pose @@ -597,12 +597,12 @@ class RvizVisualTools * \param length - the length of the arrow tail, if zero, will auto set with scale * \return true on success */ - bool publishYArrow(const Eigen::Isometry3d& pose, colors color = GREEN, scales scale = MEDIUM, + bool publishYArrow(const Eigen::Isometry3d& pose, Colors color = GREEN, Scales scale = MEDIUM, double length = 0.0); - bool publishYArrow(const geometry_msgs::msg::Pose& pose, colors color = GREEN, - scales scale = MEDIUM, double length = 0.0); - bool publishYArrow(const geometry_msgs::msg::PoseStamped& pose, colors color = GREEN, - scales scale = MEDIUM, double length = 0.0); + bool publishYArrow(const geometry_msgs::msg::Pose& pose, Colors color = GREEN, + Scales scale = MEDIUM, double length = 0.0); + bool publishYArrow(const geometry_msgs::msg::PoseStamped& pose, Colors color = GREEN, + Scales scale = MEDIUM, double length = 0.0); /** * \brief Display an arrow along the z-axis of a pose @@ -612,14 +612,14 @@ class RvizVisualTools * \param length - the length of the arrow tail, if zero, will auto set with scale * \return true on success */ - bool publishZArrow(const Eigen::Isometry3d& pose, colors color = BLUE, scales scale = MEDIUM, + bool publishZArrow(const Eigen::Isometry3d& pose, Colors color = BLUE, Scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); - bool publishZArrow(const geometry_msgs::msg::Pose& pose, colors color = BLUE, - scales scale = MEDIUM, double length = 0.0); - bool publishZArrow(const geometry_msgs::msg::PoseStamped& pose, colors color = BLUE, - scales scale = MEDIUM, double length = 0.0); - bool publishZArrow(const geometry_msgs::msg::PoseStamped& pose, colors color = BLUE, - scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); + bool publishZArrow(const geometry_msgs::msg::Pose& pose, Colors color = BLUE, + Scales scale = MEDIUM, double length = 0.0); + bool publishZArrow(const geometry_msgs::msg::PoseStamped& pose, Colors color = BLUE, + Scales scale = MEDIUM, double length = 0.0); + bool publishZArrow(const geometry_msgs::msg::PoseStamped& pose, Colors color = BLUE, + Scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); /** * \brief Display an arrow along the x-axis of a pose @@ -631,14 +631,14 @@ class RvizVisualTools * \param end - the ending point of the arrow * \return true on success */ - bool publishArrow(const Eigen::Isometry3d& pose, colors color = BLUE, scales scale = MEDIUM, + bool publishArrow(const Eigen::Isometry3d& pose, Colors color = BLUE, Scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); - bool publishArrow(const geometry_msgs::msg::Pose& pose, colors color = BLUE, - scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); - bool publishArrow(const geometry_msgs::msg::PoseStamped& pose, colors color = BLUE, - scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); + bool publishArrow(const geometry_msgs::msg::Pose& pose, Colors color = BLUE, + Scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); + bool publishArrow(const geometry_msgs::msg::PoseStamped& pose, Colors color = BLUE, + Scales scale = MEDIUM, double length = 0.0, std::size_t id = 0); bool publishArrow(const geometry_msgs::msg::Point& start, const geometry_msgs::msg::Point& end, - colors color = BLUE, scales scale = MEDIUM, std::size_t id = 0); + Colors color = BLUE, Scales scale = MEDIUM, std::size_t id = 0); /** * \brief Display a rectangular cuboid @@ -648,9 +648,9 @@ class RvizVisualTools * \return true on success */ bool publishCuboid(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, - colors color = BLUE); + Colors color = BLUE); bool publishCuboid(const geometry_msgs::msg::Point& point1, - const geometry_msgs::msg::Point& point2, colors color = BLUE, + const geometry_msgs::msg::Point& point2, Colors color = BLUE, const std::string& ns = "Cuboid", std::size_t id = 0); /** @@ -663,9 +663,9 @@ class RvizVisualTools * \return true on success */ bool publishCuboid(const geometry_msgs::msg::Pose& pose, double depth, double width, - double height, colors color = BLUE); + double height, Colors color = BLUE); bool publishCuboid(const Eigen::Isometry3d& pose, double depth, double width, double height, - colors color = BLUE); + Colors color = BLUE); /** * \brief Display a marker of line @@ -676,19 +676,19 @@ class RvizVisualTools * \return true on success */ bool publishLine(const Eigen::Isometry3d& point1, const Eigen::Isometry3d& point2, - colors color = BLUE, scales scale = MEDIUM); + Colors color = BLUE, Scales scale = MEDIUM); bool publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, - colors color = BLUE, scales scale = MEDIUM); - bool publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, colors color, + Colors color = BLUE, Scales scale = MEDIUM); + bool publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, Colors color, double radius); bool publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, - const std_msgs::msg::ColorRGBA& color, scales scale = MEDIUM); + const std_msgs::msg::ColorRGBA& color, Scales scale = MEDIUM); bool publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, const std_msgs::msg::ColorRGBA& color, double radius); bool publishLine(const geometry_msgs::msg::Point& point1, const geometry_msgs::msg::Point& point2, - colors color = BLUE, scales scale = MEDIUM); + Colors color = BLUE, Scales scale = MEDIUM); bool publishLine(const geometry_msgs::msg::Point& point1, const geometry_msgs::msg::Point& point2, - const std_msgs::msg::ColorRGBA& color, scales scale = MEDIUM); + const std_msgs::msg::ColorRGBA& color, Scales scale = MEDIUM); bool publishLine(const geometry_msgs::msg::Point& point1, const geometry_msgs::msg::Point& point2, const std_msgs::msg::ColorRGBA& color, const geometry_msgs::msg::Vector3& scale); @@ -701,8 +701,8 @@ class RvizVisualTools * \return true on success */ bool publishLines(const EigenSTL::vector_Vector3d& aPoints, - const EigenSTL::vector_Vector3d& bPoints, const std::vector& colors, - scales scale = MEDIUM); + const EigenSTL::vector_Vector3d& bPoints, const std::vector& colors, + Scales scale = MEDIUM); bool publishLines(const std::vector& aPoints, const std::vector& bPoints, const std::vector& colors, @@ -717,8 +717,8 @@ class RvizVisualTools * \param ns - namespace of marker * \return true on success */ - bool publishLineStrip(const std::vector& path, colors color = RED, - scales scale = MEDIUM, const std::string& ns = "Path"); + bool publishLineStrip(const std::vector& path, Colors color = RED, + Scales scale = MEDIUM, const std::string& ns = "Path"); /** * \brief Display a marker of a series of connected cylinders @@ -728,19 +728,19 @@ class RvizVisualTools * \param ns - namespace of marker * \return true on success */ - bool publishPath(const std::vector& path, colors color = RED, - scales scale = MEDIUM, const std::string& ns = "Path"); - bool publishPath(const std::vector& path, colors color, scales scale, + bool publishPath(const std::vector& path, Colors color = RED, + Scales scale = MEDIUM, const std::string& ns = "Path"); + bool publishPath(const std::vector& path, Colors color, Scales scale, const std::string& ns = "Path"); - bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color, scales scale, + 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, + bool publishPath(const EigenSTL::vector_Vector3d& path, Colors color, Scales scale, const std::string& ns = "Path"); - bool publishPath(const std::vector& path, colors color = RED, + bool publishPath(const std::vector& path, Colors color = RED, double radius = 0.01, const std::string& ns = "Path"); - bool publishPath(const EigenSTL::vector_Vector3d& path, colors color = RED, double radius = 0.01, + bool publishPath(const EigenSTL::vector_Vector3d& path, Colors color = RED, double radius = 0.01, const std::string& ns = "Path"); - bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color = RED, + bool publishPath(const EigenSTL::vector_Isometry3d& path, Colors color = RED, double radius = 0.01, const std::string& ns = "Path"); /** @@ -752,7 +752,7 @@ class RvizVisualTools * \return true on success * \note path and colors vectors must be the same size */ - bool publishPath(const EigenSTL::vector_Vector3d& path, const std::vector& colors, + bool publishPath(const EigenSTL::vector_Vector3d& path, const std::vector& colors, double radius = 0.01, const std::string& ns = "Path"); bool publishPath(const EigenSTL::vector_Vector3d& path, @@ -767,8 +767,8 @@ class RvizVisualTools * \param ns - namespace of marker * \return true on success */ - bool publishPolygon(const geometry_msgs::msg::Polygon& polygon, colors color = RED, - scales scale = MEDIUM, const std::string& ns = "Polygon"); + bool publishPolygon(const geometry_msgs::msg::Polygon& polygon, Colors color = RED, + Scales scale = MEDIUM, const std::string& ns = "Polygon"); /** * \brief Publish transformed wireframe cuboid. Useful eg to show an oriented bounding box. @@ -783,7 +783,7 @@ class RvizVisualTools * \return true on success */ bool publishWireframeCuboid(const Eigen::Isometry3d& pose, double depth, double width, - double height, colors color = BLUE, + double height, Colors color = BLUE, const std::string& ns = "Wireframe Cuboid", std::size_t id = 0); /** @@ -798,7 +798,7 @@ class RvizVisualTools * \return true on success */ bool publishWireframeCuboid(const Eigen::Isometry3d& pose, const Eigen::Vector3d& min_point, - const Eigen::Vector3d& max_point, colors color = BLUE, + const Eigen::Vector3d& max_point, Colors color = BLUE, const std::string& ns = "Wireframe Cuboid", std::size_t id = 0); /** @@ -812,10 +812,10 @@ class RvizVisualTools * \return true on success */ bool publishWireframeRectangle(const Eigen::Isometry3d& pose, double height, double width, - colors color = BLUE, scales scale = MEDIUM, std::size_t id = 0); + Colors color = BLUE, Scales scale = MEDIUM, std::size_t id = 0); bool publishWireframeRectangle(const Eigen::Isometry3d& pose, const Eigen::Vector3d& p1_in, const Eigen::Vector3d& p2_in, const Eigen::Vector3d& p3_in, - const Eigen::Vector3d& p4_in, colors color, scales scale); + const Eigen::Vector3d& p4_in, Colors color, Scales scale); /** * \brief Display a marker of a coordinate frame axis with a text label describing it * \param pose - the location to publish the marker with respect to the base frame @@ -825,9 +825,9 @@ class RvizVisualTools * \return true on success */ bool publishAxisLabeled(const Eigen::Isometry3d& pose, const std::string& label, - scales scale = MEDIUM, colors color = WHITE); + Scales scale = MEDIUM, Colors color = WHITE); bool publishAxisLabeled(const geometry_msgs::msg::Pose& pose, const std::string& label, - scales scale = MEDIUM, colors color = WHITE); + Scales scale = MEDIUM, Colors color = WHITE); /** * \brief Display a red/green/blue coordinate frame axis @@ -838,9 +838,9 @@ class RvizVisualTools * \param ns - namespace * \return true on success */ - bool publishAxis(const geometry_msgs::msg::Pose& pose, scales scale = MEDIUM, + bool publishAxis(const geometry_msgs::msg::Pose& pose, Scales scale = MEDIUM, const std::string& ns = "Axis"); - bool publishAxis(const Eigen::Isometry3d& pose, scales scale = MEDIUM, + bool publishAxis(const Eigen::Isometry3d& pose, Scales scale = MEDIUM, const std::string& ns = "Axis"); bool publishAxis(const geometry_msgs::msg::Pose& pose, double length, double radius = 0.01, const std::string& ns = "Axis"); @@ -869,7 +869,7 @@ class RvizVisualTools * \param ns - namespace * \return true on success */ - bool publishAxisPath(const EigenSTL::vector_Isometry3d& path, scales scale = MEDIUM, + bool publishAxisPath(const EigenSTL::vector_Isometry3d& path, Scales scale = MEDIUM, const std::string& ns = "Axis Path"); bool publishAxisPath(const EigenSTL::vector_Isometry3d& path, double length = 0.1, double radius = 0.01, const std::string& ns = "Axis Path"); @@ -883,9 +883,9 @@ class RvizVisualTools * \return true on success */ bool publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, - colors color = BLUE, scales scale = MEDIUM, + Colors color = BLUE, Scales scale = MEDIUM, const std::string& ns = "Cylinder"); - bool publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, colors color, + bool publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, Colors color, double radius = 0.01, const std::string& ns = "Cylinder"); bool publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, const std_msgs::msg::ColorRGBA& color, double radius = 0.01, @@ -899,9 +899,9 @@ class RvizVisualTools * \param radius - geometry of cylinder * \return true on success */ - bool publishCylinder(const Eigen::Isometry3d& pose, colors color = BLUE, double height = 0.1, + bool publishCylinder(const Eigen::Isometry3d& pose, Colors color = BLUE, double height = 0.1, double radius = 0.01, const std::string& ns = "Cylinder"); - bool publishCylinder(const geometry_msgs::msg::Pose& pose, colors color = BLUE, + bool publishCylinder(const geometry_msgs::msg::Pose& pose, Colors color = BLUE, double height = 0.1, double radius = 0.01, const std::string& ns = "Cylinder"); bool publishCylinder(const geometry_msgs::msg::Pose& pose, const std_msgs::msg::ColorRGBA& color, @@ -920,10 +920,10 @@ class RvizVisualTools * \return true on success */ bool publishMesh(const Eigen::Isometry3d& pose, const std::string& file_name, - colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", + Colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", std::size_t id = 0); bool publishMesh(const geometry_msgs::msg::Pose& pose, const std::string& file_name, - colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", + Colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", std::size_t id = 0); /** @@ -938,10 +938,10 @@ class RvizVisualTools * \return true on success */ bool publishMesh(const Eigen::Isometry3d& pose, const shape_msgs::msg::Mesh& mesh, - colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", + Colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", std::size_t id = 0); bool publishMesh(const geometry_msgs::msg::Pose& pose, const shape_msgs::msg::Mesh& mesh, - colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", + Colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", std::size_t id = 0); /** @@ -952,7 +952,7 @@ class RvizVisualTools * \return true on success */ // TODO(mlautman): port graph_msgs - // bool publishGraph(const graph_msgs::msg::GeometryGraph& graph, colors color, double radius); + // bool publishGraph(const graph_msgs::msg::GeometryGraph& graph, Colors color, double radius); /** * \brief Display a marker of a text @@ -963,13 +963,13 @@ class RvizVisualTools * \param static_id - if true, only one text can be published at a time * \return true on success */ - bool publishText(const Eigen::Isometry3d& pose, const std::string& text, colors color = WHITE, - scales scale = MEDIUM, bool static_id = true); - bool publishText(const Eigen::Isometry3d& pose, const std::string& text, colors color, + bool publishText(const Eigen::Isometry3d& pose, const std::string& text, Colors color = WHITE, + Scales scale = MEDIUM, bool static_id = true); + bool publishText(const Eigen::Isometry3d& pose, const std::string& text, Colors color, const geometry_msgs::msg::Vector3 scale, bool static_id = true); bool publishText(const geometry_msgs::msg::Pose& pose, const std::string& text, - colors color = WHITE, scales scale = MEDIUM, bool static_id = true); - bool publishText(const geometry_msgs::msg::Pose& pose, const std::string& text, colors color, + Colors color = WHITE, Scales scale = MEDIUM, bool static_id = true); + bool publishText(const geometry_msgs::msg::Pose& pose, const std::string& text, Colors color, const geometry_msgs::msg::Vector3 scale, bool static_id = true); /** @@ -1228,7 +1228,7 @@ class RvizVisualTools bool psychedelic_mode_ = false; // Chose random colors from this list - static const std::array ALL_RAND_COLORS; + static const std::array ALL_RAND_COLORS; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW // http://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html diff --git a/package.xml b/package.xml index af2a8226..28b3bec2 100644 --- a/package.xml +++ b/package.xml @@ -1,10 +1,11 @@ - + rviz_visual_tools 3.7.0 Utility functions for displaying and debugging data in Rviz via published markers Mike Lautman + Mike Lautman BSD @@ -12,11 +13,8 @@ https://github.com/PickNikRobotics/rviz_visual_tools/issues https://github.com/PickNikRobotics/rviz_visual_tools/ - Mike Lautman - ament_cmake eigen3_cmake_module - eigen3_cmake_module rclcpp @@ -54,7 +52,8 @@ ament_cmake_gtest ament_lint_auto - ament_lint_common + ament_cmake_lint_cmake + ament_cmake_clang_format ament_cmake diff --git a/rviz_visual_tools.repos b/rviz_visual_tools.repos index 070727ed..eb8d6bb7 100644 --- a/rviz_visual_tools.repos +++ b/rviz_visual_tools.repos @@ -1,5 +1,5 @@ repositories: -# rviz_visual_tools: -# type: git -# url: https://github.com/PickNikRobotics/rviz_visual_tools.git -# version: eloquent-devel + joint_state_publisher: + type: git + url: https://github.com/ros/joint_state_publisher + version: ros2 diff --git a/src/rviz_visual_tools.cpp b/src/rviz_visual_tools.cpp index bade4efb..56fc7eda 100644 --- a/src/rviz_visual_tools.cpp +++ b/src/rviz_visual_tools.cpp @@ -61,7 +61,7 @@ namespace rviz_visual_tools { const std::string LOGNAME = "visual_tools"; -const std::array RvizVisualTools::ALL_RAND_COLORS = { +const std::array RvizVisualTools::ALL_RAND_COLORS = { RED, GREEN, BLUE, GREY, DARK_GREY, WHITE, ORANGE, YELLOW, BROWN, PINK, LIME_GREEN, PURPLE, CYAN, MAGENTA }; @@ -406,13 +406,13 @@ void RvizVisualTools::setLifetime(double lifetime) text_marker_.lifetime = marker_lifetime_; } -colors RvizVisualTools::getRandColor() +Colors RvizVisualTools::getRandColor() { const int rand_num = iRand(0, ALL_RAND_COLORS.size() - 1); return ALL_RAND_COLORS[rand_num]; } -std_msgs::msg::ColorRGBA RvizVisualTools::getColor(colors color) const +std_msgs::msg::ColorRGBA RvizVisualTools::getColor(Colors color) const { std_msgs::msg::ColorRGBA result; @@ -557,7 +557,7 @@ std_msgs::msg::ColorRGBA RvizVisualTools::getColor(colors color) const return result; } -colors RvizVisualTools::intToRvizColor(std::size_t color) +Colors RvizVisualTools::intToRvizColor(std::size_t color) { // clang-format off switch (color) @@ -588,7 +588,7 @@ colors RvizVisualTools::intToRvizColor(std::size_t color) return DEFAULT; } -scales RvizVisualTools::intToRvizScale(std::size_t scale) +Scales RvizVisualTools::intToRvizScale(std::size_t scale) { // clang-format off switch (scale) @@ -610,7 +610,7 @@ scales RvizVisualTools::intToRvizScale(std::size_t scale) return MEDIUM; // dumy value } -std::string RvizVisualTools::scaleToString(scales scale) +std::string RvizVisualTools::scaleToString(Scales scale) { // clang-format off switch (scale) @@ -718,7 +718,7 @@ std_msgs::msg::ColorRGBA RvizVisualTools::getColorScale(double value) const return result; } -geometry_msgs::msg::Vector3 RvizVisualTools::getScale(scales scale, double marker_scale) const +geometry_msgs::msg::Vector3 RvizVisualTools::getScale(Scales scale, double marker_scale) const { geometry_msgs::msg::Vector3 result; double val(0.0); @@ -1011,13 +1011,13 @@ bool RvizVisualTools::publishMarkers(visualization_msgs::msg::MarkerArray& marke return true; } -bool RvizVisualTools::publishCone(const Eigen::Isometry3d& pose, double angle, colors color, +bool RvizVisualTools::publishCone(const Eigen::Isometry3d& pose, double angle, Colors color, double scale) { return publishCone(convertPose(pose), angle, color, scale); } -bool RvizVisualTools::publishCone(const geometry_msgs::msg::Pose& pose, double angle, colors color, +bool RvizVisualTools::publishCone(const geometry_msgs::msg::Pose& pose, double angle, Colors color, double scale) { triangle_marker_.header.stamp = clock_interface_->get_clock()->now(); @@ -1060,7 +1060,7 @@ bool RvizVisualTools::publishCone(const geometry_msgs::msg::Pose& pose, double a } bool RvizVisualTools::publishABCDPlane(const double A, const double B, const double C, - const double D, colors color, double x_width, double y_width) + const double D, Colors color, double x_width, double y_width) { // The coefficients A,B,C give the normal to the plane. Eigen::Vector3d n(A, B, C); @@ -1083,12 +1083,12 @@ bool RvizVisualTools::publishABCDPlane(const double A, const double B, const dou return true; } -bool RvizVisualTools::publishXYPlane(const Eigen::Isometry3d& pose, colors color, double scale) +bool RvizVisualTools::publishXYPlane(const Eigen::Isometry3d& pose, Colors color, double scale) { return publishXYPlane(convertPose(pose), color, scale); } -bool RvizVisualTools::publishXYPlane(const geometry_msgs::msg::Pose& pose, colors color, +bool RvizVisualTools::publishXYPlane(const geometry_msgs::msg::Pose& pose, Colors color, double scale) { triangle_marker_.header.stamp = clock_interface_->get_clock()->now(); @@ -1130,12 +1130,12 @@ bool RvizVisualTools::publishXYPlane(const geometry_msgs::msg::Pose& pose, color return publishMarker(triangle_marker_); } -bool RvizVisualTools::publishXZPlane(const Eigen::Isometry3d& pose, colors color, double scale) +bool RvizVisualTools::publishXZPlane(const Eigen::Isometry3d& pose, Colors color, double scale) { return publishXZPlane(convertPose(pose), color, scale); } -bool RvizVisualTools::publishXZPlane(const geometry_msgs::msg::Pose& pose, colors color, +bool RvizVisualTools::publishXZPlane(const geometry_msgs::msg::Pose& pose, Colors color, double scale) { triangle_marker_.header.stamp = clock_interface_->get_clock()->now(); @@ -1177,12 +1177,12 @@ bool RvizVisualTools::publishXZPlane(const geometry_msgs::msg::Pose& pose, color return publishMarker(triangle_marker_); } -bool RvizVisualTools::publishYZPlane(const Eigen::Isometry3d& pose, colors color, double scale) +bool RvizVisualTools::publishYZPlane(const Eigen::Isometry3d& pose, Colors color, double scale) { return publishYZPlane(convertPose(pose), color, scale); } -bool RvizVisualTools::publishYZPlane(const geometry_msgs::msg::Pose& pose, colors color, +bool RvizVisualTools::publishYZPlane(const geometry_msgs::msg::Pose& pose, Colors color, double scale) { triangle_marker_.header.stamp = clock_interface_->get_clock()->now(); @@ -1224,13 +1224,13 @@ bool RvizVisualTools::publishYZPlane(const geometry_msgs::msg::Pose& pose, color return publishMarker(triangle_marker_); } -bool RvizVisualTools::publishSphere(const Eigen::Isometry3d& pose, colors color, scales scale, +bool RvizVisualTools::publishSphere(const Eigen::Isometry3d& pose, Colors color, Scales scale, const std::string& ns, std::size_t id) { return publishSphere(convertPose(pose), color, scale, ns, id); } -bool RvizVisualTools::publishSphere(const Eigen::Vector3d& point, colors color, scales scale, +bool RvizVisualTools::publishSphere(const Eigen::Vector3d& point, Colors color, Scales scale, const std::string& ns, std::size_t id) { geometry_msgs::msg::Pose pose_msg; @@ -1238,7 +1238,7 @@ bool RvizVisualTools::publishSphere(const Eigen::Vector3d& point, colors color, return publishSphere(pose_msg, color, scale, ns, id); } -bool RvizVisualTools::publishSphere(const Eigen::Vector3d& point, colors color, double scale, +bool RvizVisualTools::publishSphere(const Eigen::Vector3d& point, Colors color, double scale, const std::string& ns, std::size_t id) { geometry_msgs::msg::Pose pose_msg = getIdentityPose(); @@ -1246,21 +1246,21 @@ bool RvizVisualTools::publishSphere(const Eigen::Vector3d& point, colors color, return publishSphere(pose_msg, color, scale, ns, id); } -bool RvizVisualTools::publishSphere(const geometry_msgs::msg::Point& point, colors color, - scales scale, const std::string& ns, std::size_t id) +bool RvizVisualTools::publishSphere(const geometry_msgs::msg::Point& point, Colors color, + Scales scale, const std::string& ns, std::size_t id) { geometry_msgs::msg::Pose pose_msg = getIdentityPose(); pose_msg.position = point; return publishSphere(pose_msg, color, scale, ns, id); } -bool RvizVisualTools::publishSphere(const geometry_msgs::msg::Pose& pose, colors color, - scales scale, const std::string& ns, std::size_t id) +bool RvizVisualTools::publishSphere(const geometry_msgs::msg::Pose& pose, Colors color, + Scales scale, const std::string& ns, std::size_t id) { return publishSphere(pose, color, getScale(scale), ns, id); } -bool RvizVisualTools::publishSphere(const geometry_msgs::msg::Pose& pose, colors color, +bool RvizVisualTools::publishSphere(const geometry_msgs::msg::Pose& pose, Colors color, double scale, const std::string& ns, std::size_t id) { geometry_msgs::msg::Vector3 scale_msg; @@ -1270,7 +1270,7 @@ bool RvizVisualTools::publishSphere(const geometry_msgs::msg::Pose& pose, colors return publishSphere(pose, color, scale_msg, ns, id); } -bool RvizVisualTools::publishSphere(const geometry_msgs::msg::Pose& pose, colors color, +bool RvizVisualTools::publishSphere(const geometry_msgs::msg::Pose& pose, Colors color, const geometry_msgs::msg::Vector3 scale, const std::string& ns, std::size_t id) { @@ -1322,7 +1322,7 @@ bool RvizVisualTools::publishSphere(const geometry_msgs::msg::Pose& pose, return publishMarker(sphere_marker_); } -bool RvizVisualTools::publishSphere(const geometry_msgs::msg::PoseStamped& pose, colors color, +bool RvizVisualTools::publishSphere(const geometry_msgs::msg::PoseStamped& pose, Colors color, const geometry_msgs::msg::Vector3 scale, const std::string& ns, std::size_t id) { @@ -1350,41 +1350,41 @@ bool RvizVisualTools::publishSphere(const geometry_msgs::msg::PoseStamped& pose, return true; } -bool RvizVisualTools::publishXArrow(const Eigen::Isometry3d& pose, colors color, scales scale, +bool RvizVisualTools::publishXArrow(const Eigen::Isometry3d& pose, Colors color, Scales scale, double length) { return publishArrow(convertPose(pose), color, scale, length); } -bool RvizVisualTools::publishXArrow(const geometry_msgs::msg::Pose& pose, colors color, - scales scale, double length) +bool RvizVisualTools::publishXArrow(const geometry_msgs::msg::Pose& pose, Colors color, + Scales scale, double length) { return publishArrow(pose, color, scale, length); } -bool RvizVisualTools::publishXArrow(const geometry_msgs::msg::PoseStamped& pose, colors color, - scales scale, double length) +bool RvizVisualTools::publishXArrow(const geometry_msgs::msg::PoseStamped& pose, Colors color, + Scales scale, double length) { return publishArrow(pose, color, scale, length); } -bool RvizVisualTools::publishYArrow(const Eigen::Isometry3d& pose, colors color, scales scale, +bool RvizVisualTools::publishYArrow(const Eigen::Isometry3d& pose, Colors color, Scales scale, double length) { Eigen::Isometry3d arrow_pose = pose * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()); return publishArrow(convertPose(arrow_pose), color, scale, length); } -bool RvizVisualTools::publishYArrow(const geometry_msgs::msg::Pose& pose, colors color, - scales scale, double length) +bool RvizVisualTools::publishYArrow(const geometry_msgs::msg::Pose& pose, Colors color, + Scales scale, double length) { Eigen::Isometry3d arrow_pose = convertPose(pose) * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()); return publishArrow(convertPose(arrow_pose), color, scale, length); } -bool RvizVisualTools::publishYArrow(const geometry_msgs::msg::PoseStamped& pose, colors color, - scales scale, double length) +bool RvizVisualTools::publishYArrow(const geometry_msgs::msg::PoseStamped& pose, Colors color, + Scales scale, double length) { Eigen::Isometry3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()); @@ -1393,23 +1393,23 @@ bool RvizVisualTools::publishYArrow(const geometry_msgs::msg::PoseStamped& pose, return publishArrow(new_pose, color, scale, length); } -bool RvizVisualTools::publishZArrow(const Eigen::Isometry3d& pose, colors color, scales scale, +bool RvizVisualTools::publishZArrow(const Eigen::Isometry3d& pose, Colors color, Scales scale, double length, std::size_t id) { Eigen::Isometry3d arrow_pose = pose * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); return publishArrow(convertPose(arrow_pose), color, scale, length, id); } -bool RvizVisualTools::publishZArrow(const geometry_msgs::msg::Pose& pose, colors color, - scales scale, double length) +bool RvizVisualTools::publishZArrow(const geometry_msgs::msg::Pose& pose, Colors color, + Scales scale, double length) { Eigen::Isometry3d arrow_pose = convertPose(pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); return publishArrow(convertPose(arrow_pose), color, scale, length); } -bool RvizVisualTools::publishZArrow(const geometry_msgs::msg::PoseStamped& pose, colors color, - scales scale, double length) +bool RvizVisualTools::publishZArrow(const geometry_msgs::msg::PoseStamped& pose, Colors color, + Scales scale, double length) { Eigen::Isometry3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); @@ -1418,8 +1418,8 @@ bool RvizVisualTools::publishZArrow(const geometry_msgs::msg::PoseStamped& pose, return publishArrow(new_pose, color, scale, length); } -bool RvizVisualTools::publishZArrow(const geometry_msgs::msg::PoseStamped& pose, colors color, - scales scale, double length, std::size_t id) +bool RvizVisualTools::publishZArrow(const geometry_msgs::msg::PoseStamped& pose, Colors color, + Scales scale, double length, std::size_t id) { Eigen::Isometry3d arrow_pose = convertPose(pose.pose) * Eigen::AngleAxisd(-M_PI / 2, Eigen::Vector3d::UnitY()); @@ -1428,13 +1428,13 @@ bool RvizVisualTools::publishZArrow(const geometry_msgs::msg::PoseStamped& pose, return publishArrow(new_pose, color, scale, length, id); } -bool RvizVisualTools::publishArrow(const Eigen::Isometry3d& pose, colors color, scales scale, +bool RvizVisualTools::publishArrow(const Eigen::Isometry3d& pose, Colors color, Scales scale, double length, std::size_t id) { return publishArrow(convertPose(pose), color, scale, length, id); } -bool RvizVisualTools::publishArrow(const geometry_msgs::msg::Pose& pose, colors color, scales scale, +bool RvizVisualTools::publishArrow(const geometry_msgs::msg::Pose& pose, Colors color, Scales scale, double length, std::size_t id) { // Set the frame ID and timestamp. @@ -1468,8 +1468,8 @@ bool RvizVisualTools::publishArrow(const geometry_msgs::msg::Pose& pose, colors return publishMarker(arrow_marker_); } -bool RvizVisualTools::publishArrow(const geometry_msgs::msg::PoseStamped& pose, colors color, - scales scale, double length, std::size_t id) +bool RvizVisualTools::publishArrow(const geometry_msgs::msg::PoseStamped& pose, Colors color, + Scales scale, double length, std::size_t id) { // Set the frame ID and timestamp. arrow_marker_.header = pose.header; @@ -1505,7 +1505,7 @@ bool RvizVisualTools::publishArrow(const geometry_msgs::msg::PoseStamped& pose, } bool RvizVisualTools::publishArrow(const geometry_msgs::msg::Point& start, - const geometry_msgs::msg::Point& end, colors color, scales scale, + const geometry_msgs::msg::Point& end, Colors color, Scales scale, std::size_t id) { // Set the frame ID and timestamp. @@ -1539,13 +1539,13 @@ bool RvizVisualTools::publishArrow(const geometry_msgs::msg::Point& start, } bool RvizVisualTools::publishAxisLabeled(const Eigen::Isometry3d& pose, const std::string& label, - scales scale, colors color) + Scales scale, Colors color) { return publishAxisLabeled(convertPose(pose), label, scale, color); } bool RvizVisualTools::publishAxisLabeled(const geometry_msgs::msg::Pose& pose, - const std::string& label, scales scale, colors color) + const std::string& label, Scales scale, Colors color) { publishAxis(pose, scale, label); @@ -1554,18 +1554,18 @@ bool RvizVisualTools::publishAxisLabeled(const geometry_msgs::msg::Pose& pose, pose_shifted.position.x -= 0.05; pose_shifted.position.y -= 0.05; pose_shifted.position.z -= 0.05; - publishText(pose_shifted, label, color, static_cast(static_cast(scale) + 1), false); + publishText(pose_shifted, label, color, static_cast(static_cast(scale) + 1), false); return true; } -bool RvizVisualTools::publishAxis(const geometry_msgs::msg::Pose& pose, scales scale, +bool RvizVisualTools::publishAxis(const geometry_msgs::msg::Pose& pose, Scales scale, const std::string& ns) { double radius = getScale(scale).x; return publishAxis(pose, radius * 10.0, radius, ns); } -bool RvizVisualTools::publishAxis(const Eigen::Isometry3d& pose, scales scale, +bool RvizVisualTools::publishAxis(const Eigen::Isometry3d& pose, Scales scale, const std::string& ns) { double radius = getScale(scale).x; @@ -1613,7 +1613,7 @@ bool RvizVisualTools::publishAxisInternal(const Eigen::Isometry3d& pose, double return true; } -bool RvizVisualTools::publishAxisPath(const EigenSTL::vector_Isometry3d& path, scales scale, +bool RvizVisualTools::publishAxisPath(const EigenSTL::vector_Isometry3d& path, Scales scale, const std::string& ns) { // Create the cylinders @@ -1639,14 +1639,14 @@ bool RvizVisualTools::publishAxisPath(const EigenSTL::vector_Isometry3d& path, d } bool RvizVisualTools::publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, - colors color, scales scale, const std::string& ns) + Colors color, Scales scale, const std::string& ns) { double radius = getScale(scale).x; return publishCylinder(point1, point2, getColor(color), radius, ns); } bool RvizVisualTools::publishCylinder(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, - colors color, double radius, const std::string& ns) + Colors color, double radius, const std::string& ns) { return publishCylinder(point1, point2, getColor(color), radius, ns); } @@ -1674,13 +1674,13 @@ bool RvizVisualTools::publishCylinder(const Eigen::Vector3d& point1, const Eigen return publishCylinder(convertPose(pose), color, height, radius, ns); } -bool RvizVisualTools::publishCylinder(const Eigen::Isometry3d& pose, colors color, double height, +bool RvizVisualTools::publishCylinder(const Eigen::Isometry3d& pose, Colors color, double height, double radius, const std::string& ns) { return publishCylinder(convertPose(pose), color, height, radius, ns); } -bool RvizVisualTools::publishCylinder(const geometry_msgs::msg::Pose& pose, colors color, +bool RvizVisualTools::publishCylinder(const geometry_msgs::msg::Pose& pose, Colors color, double height, double radius, const std::string& ns) { return publishCylinder(pose, getColor(color), height, radius, ns); @@ -1711,13 +1711,13 @@ bool RvizVisualTools::publishCylinder(const geometry_msgs::msg::Pose& pose, } bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const std::string& file_name, - colors color, double scale, const std::string& ns, std::size_t id) + Colors color, double scale, const std::string& ns, std::size_t id) { return publishMesh(convertPose(pose), file_name, color, scale, ns, id); } bool RvizVisualTools::publishMesh(const geometry_msgs::msg::Pose& pose, - const std::string& file_name, colors color, double scale, + const std::string& file_name, Colors color, double scale, const std::string& ns, std::size_t id) { // Set the timestamp @@ -1756,13 +1756,13 @@ bool RvizVisualTools::publishMesh(const geometry_msgs::msg::Pose& pose, } bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const shape_msgs::msg::Mesh& mesh, - colors color, double scale, const std::string& ns, std::size_t id) + Colors color, double scale, const std::string& ns, std::size_t id) { return publishMesh(convertPose(pose), mesh, color, scale, ns, id); } bool RvizVisualTools::publishMesh(const geometry_msgs::msg::Pose& pose, - const shape_msgs::msg::Mesh& mesh, colors color, double scale, + const shape_msgs::msg::Mesh& mesh, Colors color, double scale, const std::string& ns, std::size_t id) { triangle_marker_.header.stamp = clock_interface_->get_clock()->now(); @@ -1802,7 +1802,7 @@ bool RvizVisualTools::publishMesh(const geometry_msgs::msg::Pose& pose, } // TODO(mlautman): port graph_msgs -// bool RvizVisualTools::publishGraph(const graph_msgs::msg::GeometryGraph& graph, colors color, +// bool RvizVisualTools::publishGraph(const graph_msgs::msg::GeometryGraph& graph, Colors color, // double radius) // { // // Track which pairs of nodes we've already connected since graph is @@ -1836,13 +1836,13 @@ bool RvizVisualTools::publishMesh(const geometry_msgs::msg::Pose& pose, // } bool RvizVisualTools::publishCuboid(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, - colors color) + Colors color) { return publishCuboid(convertPoint(point1), convertPoint(point2), color); } bool RvizVisualTools::publishCuboid(const geometry_msgs::msg::Point& point1, - const geometry_msgs::msg::Point& point2, colors color, + const geometry_msgs::msg::Point& point2, Colors color, const std::string& ns, std::size_t id) { // Set the timestamp @@ -1891,13 +1891,13 @@ bool RvizVisualTools::publishCuboid(const geometry_msgs::msg::Point& point1, } bool RvizVisualTools::publishCuboid(const Eigen::Isometry3d& pose, double depth, double width, - double height, colors color) + double height, Colors color) { return publishCuboid(convertPose(pose), depth, width, height, color); } bool RvizVisualTools::publishCuboid(const geometry_msgs::msg::Pose& pose, double depth, - double width, double height, colors color) + double width, double height, Colors color) { cuboid_marker_.header.stamp = clock_interface_->get_clock()->now(); @@ -1938,18 +1938,18 @@ bool RvizVisualTools::publishCuboid(const geometry_msgs::msg::Pose& pose, double } bool RvizVisualTools::publishLine(const Eigen::Isometry3d& point1, const Eigen::Isometry3d& point2, - colors color, scales scale) + Colors color, Scales scale) { return publishLine(convertPoseToPoint(point1), convertPoseToPoint(point2), color, scale); } bool RvizVisualTools::publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, - colors color, scales scale) + Colors color, Scales scale) { return publishLine(convertPoint(point1), convertPoint(point2), color, scale); } bool RvizVisualTools::publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, - colors color, double radius) + Colors color, double radius) { geometry_msgs::msg::Vector3 scale; scale.x = radius * global_scale_; @@ -1959,7 +1959,7 @@ bool RvizVisualTools::publishLine(const Eigen::Vector3d& point1, const Eigen::Ve } bool RvizVisualTools::publishLine(const Eigen::Vector3d& point1, const Eigen::Vector3d& point2, - const std_msgs::msg::ColorRGBA& color, scales scale) + const std_msgs::msg::ColorRGBA& color, Scales scale) { return publishLine(convertPoint(point1), convertPoint(point2), color, scale); } @@ -1975,15 +1975,15 @@ bool RvizVisualTools::publishLine(const Eigen::Vector3d& point1, const Eigen::Ve } bool RvizVisualTools::publishLine(const geometry_msgs::msg::Point& point1, - const geometry_msgs::msg::Point& point2, colors color, - scales scale) + const geometry_msgs::msg::Point& point2, Colors color, + Scales scale) { return publishLine(point1, point2, getColor(color), scale); } bool RvizVisualTools::publishLine(const geometry_msgs::msg::Point& point1, const geometry_msgs::msg::Point& point2, - const std_msgs::msg::ColorRGBA& color, scales scale) + const std_msgs::msg::ColorRGBA& color, Scales scale) { return publishLine(point1, point2, color, getScale(scale)); } @@ -2012,7 +2012,7 @@ bool RvizVisualTools::publishLine(const geometry_msgs::msg::Point& point1, bool RvizVisualTools::publishLines(const EigenSTL::vector_Vector3d& aPoints, const EigenSTL::vector_Vector3d& bPoints, - const std::vector& colors, scales scale) + const std::vector& colors, Scales scale) { assertm(aPoints.size() == bPoints.size() && bPoints.size() == colors.size(), "Mismatching vector sizes: " @@ -2076,7 +2076,7 @@ bool RvizVisualTools::publishLines(const std::vector& } bool RvizVisualTools::publishLineStrip(const std::vector& path, - colors color, scales scale, const std::string& ns) + Colors color, Scales scale, const std::string& ns) { if (path.size() < 2) { @@ -2113,8 +2113,8 @@ bool RvizVisualTools::publishLineStrip(const std::vector& path, colors color, - scales scale, const std::string& ns) +bool RvizVisualTools::publishPath(const std::vector& path, Colors color, + Scales scale, const std::string& ns) { std::vector point_path(path.size()); for (std::size_t i = 0; i < path.size(); ++i) @@ -2125,25 +2125,25 @@ bool RvizVisualTools::publishPath(const std::vector& p return publishPath(point_path, color, getScale(scale).x, ns); } -bool RvizVisualTools::publishPath(const std::vector& path, colors color, - scales scale, const std::string& ns) +bool RvizVisualTools::publishPath(const std::vector& path, Colors color, + Scales scale, const std::string& ns) { return publishPath(path, color, getScale(scale).x, ns); } -bool RvizVisualTools::publishPath(const EigenSTL::vector_Isometry3d& path, colors color, - scales scale, const std::string& ns) +bool RvizVisualTools::publishPath(const EigenSTL::vector_Isometry3d& path, Colors color, + Scales scale, const std::string& ns) { return publishPath(path, color, getScale(scale).x, ns); } -bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, colors color, scales scale, +bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, Colors color, Scales scale, const std::string& ns) { return publishPath(path, color, getScale(scale).x, ns); } -bool RvizVisualTools::publishPath(const std::vector& path, colors color, +bool RvizVisualTools::publishPath(const std::vector& path, Colors color, double radius, const std::string& ns) { if (path.size() < 2) @@ -2163,7 +2163,7 @@ bool RvizVisualTools::publishPath(const std::vector& return true; } -bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, colors color, +bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, Colors color, double radius, const std::string& ns) { if (path.size() < 2) @@ -2183,7 +2183,7 @@ bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, colors return true; } -bool RvizVisualTools::publishPath(const EigenSTL::vector_Isometry3d& path, colors color, +bool RvizVisualTools::publishPath(const EigenSTL::vector_Isometry3d& path, Colors color, double radius, const std::string& ns) { if (path.size() < 2) @@ -2204,7 +2204,7 @@ bool RvizVisualTools::publishPath(const EigenSTL::vector_Isometry3d& path, color } bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, - const std::vector& colors, double radius, + const std::vector& colors, double radius, const std::string& ns) { if (path.size() < 2) @@ -2261,8 +2261,8 @@ bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, return true; } -bool RvizVisualTools::publishPolygon(const geometry_msgs::msg::Polygon& polygon, colors color, - scales scale, const std::string& ns) +bool RvizVisualTools::publishPolygon(const geometry_msgs::msg::Polygon& polygon, Colors color, + Scales scale, const std::string& ns) { std::vector points; geometry_msgs::msg::Point temp; @@ -2286,7 +2286,7 @@ bool RvizVisualTools::publishPolygon(const geometry_msgs::msg::Polygon& polygon, } bool RvizVisualTools::publishWireframeCuboid(const Eigen::Isometry3d& pose, double depth, - double width, double height, colors color, + double width, double height, Colors color, const std::string& ns, std::size_t id) { Eigen::Vector3d min_point, max_point; @@ -2297,7 +2297,7 @@ bool RvizVisualTools::publishWireframeCuboid(const Eigen::Isometry3d& pose, doub bool RvizVisualTools::publishWireframeCuboid(const Eigen::Isometry3d& pose, const Eigen::Vector3d& min_point, - const Eigen::Vector3d& max_point, colors color, + const Eigen::Vector3d& max_point, Colors color, const std::string& ns, std::size_t id) { // Extract 8 cuboid vertices @@ -2406,7 +2406,7 @@ bool RvizVisualTools::publishWireframeCuboid(const Eigen::Isometry3d& pose, } bool RvizVisualTools::publishWireframeRectangle(const Eigen::Isometry3d& pose, double height, - double width, colors color, scales scale, + double width, Colors color, Scales scale, std::size_t id) { if (id == 0) @@ -2469,7 +2469,7 @@ bool RvizVisualTools::publishWireframeRectangle(const Eigen::Isometry3d& pose, d bool RvizVisualTools::publishWireframeRectangle( const Eigen::Isometry3d& pose, const Eigen::Vector3d& p1_in, const Eigen::Vector3d& p2_in, - const Eigen::Vector3d& p3_in, const Eigen::Vector3d& p4_in, colors color, scales scale) + const Eigen::Vector3d& p3_in, const Eigen::Vector3d& p4_in, Colors color, Scales scale) { Eigen::Vector3d p1; Eigen::Vector3d p2; @@ -2522,8 +2522,8 @@ bool RvizVisualTools::publishWireframeRectangle( return publishMarker(line_list_marker_); } -bool RvizVisualTools::publishSpheres(const EigenSTL::vector_Vector3d& points, colors color, - scales scale, const std::string& ns) +bool RvizVisualTools::publishSpheres(const EigenSTL::vector_Vector3d& points, Colors color, + Scales scale, const std::string& ns) { std::vector points_msg; @@ -2535,7 +2535,7 @@ bool RvizVisualTools::publishSpheres(const EigenSTL::vector_Vector3d& points, co return publishSpheres(points_msg, color, scale, ns); } -bool RvizVisualTools::publishSpheres(const EigenSTL::vector_Vector3d& points, colors color, +bool RvizVisualTools::publishSpheres(const EigenSTL::vector_Vector3d& points, Colors color, double scale, const std::string& ns) { std::vector points_msg; @@ -2549,7 +2549,7 @@ bool RvizVisualTools::publishSpheres(const EigenSTL::vector_Vector3d& points, co } bool RvizVisualTools::publishSpheres(const std::vector& points, - colors color, double scale, const std::string& ns) + Colors color, double scale, const std::string& ns) { geometry_msgs::msg::Vector3 scale_vector; scale_vector.x = scale * global_scale_; @@ -2559,13 +2559,13 @@ bool RvizVisualTools::publishSpheres(const std::vector& points, - colors color, scales scale, const std::string& ns) + Colors color, Scales scale, const std::string& ns) { return publishSpheres(points, color, getScale(scale), ns); } bool RvizVisualTools::publishSpheres(const std::vector& points, - colors color, const geometry_msgs::msg::Vector3& scale, + Colors color, const geometry_msgs::msg::Vector3& scale, const std::string& ns) { spheres_marker_.header.stamp = builtin_interfaces::msg::Time(); @@ -2592,7 +2592,7 @@ bool RvizVisualTools::publishSpheres(const std::vector& colors, scales scale, + const std::vector& colors, Scales scale, const std::string& ns) { assertm(points.size() == colors.size(), "Mismatching vector sizes: points and colors"); @@ -2631,26 +2631,26 @@ bool RvizVisualTools::publishSpheres(const std::vector colors; + std::vector colors; unsigned index(0); for (double i = 0; i < 1.0; i += step) { @@ -453,14 +453,14 @@ class RvizVisualToolsDemo : public rclcpp::Node } /** \brief Compare sizes of markers using all MEDIUM-scale markers */ - void testSize(double& x_location, scales scale) + void testSize(double& x_location, Scales scale) { // Create pose Eigen::Isometry3d pose1 = Eigen::Isometry3d::Identity(); Eigen::Isometry3d pose2 = Eigen::Isometry3d::Identity(); // Reusable vector of 2 colors - std::vector colors; + std::vector colors; colors.push_back(RED); colors.push_back(GREEN); @@ -599,7 +599,7 @@ class RvizVisualToolsDemo : public rclcpp::Node pose2.translation().x() = x_location; // Sphere - for (scales scale = XXXXSMALL; scale <= XXXXLARGE; /*inline*/) + for (Scales scale = XXXXSMALL; scale <= XXXXLARGE; /*inline*/) { pose1.translation().y() += visual_tools_->getScale(scale).x + 0.1; @@ -617,7 +617,7 @@ class RvizVisualToolsDemo : public rclcpp::Node visual_tools_->publishText(pose2, "Size " + visual_tools_->scaleToString(scale), WHITE, scale, false); - scale = static_cast(static_cast(scale) + 1); + scale = static_cast(static_cast(scale) + 1); } // Display test