Skip to content

Commit b454935

Browse files
authored
Switch to moveit_ci, apply clang-format (#124)
* Switch to moveit_ci, apply clang-format * Update .travis.yml * Update .travis.yml
1 parent 3ea03e7 commit b454935

File tree

7 files changed

+130
-73
lines changed

7 files changed

+130
-73
lines changed

.clang-format

Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
1+
---
2+
BasedOnStyle: Google
3+
AccessModifierOffset: -2
4+
ConstructorInitializerIndentWidth: 2
5+
AlignEscapedNewlinesLeft: false
6+
AlignTrailingComments: true
7+
AllowAllParametersOfDeclarationOnNextLine: false
8+
AllowShortIfStatementsOnASingleLine: false
9+
AllowShortLoopsOnASingleLine: false
10+
AllowShortFunctionsOnASingleLine: None
11+
AllowShortLoopsOnASingleLine: false
12+
AlwaysBreakTemplateDeclarations: true
13+
AlwaysBreakBeforeMultilineStrings: false
14+
BreakBeforeBinaryOperators: false
15+
BreakBeforeTernaryOperators: false
16+
BreakConstructorInitializersBeforeComma: true
17+
BinPackParameters: true
18+
ColumnLimit: 120
19+
ConstructorInitializerAllOnOneLineOrOnePerLine: true
20+
DerivePointerBinding: false
21+
PointerBindsToType: true
22+
ExperimentalAutoDetectBinPacking: false
23+
IndentCaseLabels: true
24+
MaxEmptyLinesToKeep: 1
25+
NamespaceIndentation: None
26+
ObjCSpaceBeforeProtocolList: true
27+
PenaltyBreakBeforeFirstCallParameter: 19
28+
PenaltyBreakComment: 60
29+
PenaltyBreakString: 100
30+
PenaltyBreakFirstLessLess: 1000
31+
PenaltyExcessCharacter: 1000
32+
PenaltyReturnTypeOnItsOwnLine: 70
33+
SpacesBeforeTrailingComments: 2
34+
Cpp11BracedListStyle: false
35+
Standard: Auto
36+
IndentWidth: 2
37+
TabWidth: 2
38+
UseTab: Never
39+
IndentFunctionDeclarationAfterType: false
40+
SpacesInParentheses: false
41+
SpacesInAngles: false
42+
SpaceInEmptyParentheses: false
43+
SpacesInCStyleCastParentheses: false
44+
SpaceAfterControlStatementKeyword: true
45+
SpaceBeforeAssignmentOperators: true
46+
ContinuationIndentWidth: 4
47+
SortIncludes: false
48+
SpaceAfterCStyleCast: false
49+
50+
# Configure each individual brace in BraceWrapping
51+
BreakBeforeBraces: Custom
52+
53+
# Control of individual brace wrapping cases
54+
BraceWrapping: {
55+
AfterClass: 'true'
56+
AfterControlStatement: 'true'
57+
AfterEnum : 'true'
58+
AfterFunction : 'true'
59+
AfterNamespace : 'true'
60+
AfterStruct : 'true'
61+
AfterUnion : 'true'
62+
BeforeCatch : 'true'
63+
BeforeElse : 'true'
64+
IndentBraces : 'false'
65+
}
66+
...

.gitignore

Lines changed: 0 additions & 1 deletion
This file was deleted.

.travis.yml

Lines changed: 22 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -1,32 +1,26 @@
1-
# while this doesn't require sudo we don't want to run within a Docker container
2-
sudo: true
3-
dist: trusty
4-
language: python
5-
python:
6-
- "3.4"
1+
# This config file for Travis CI utilizes https://github.com/ros-planning/moveit_ci package.
2+
sudo: required
3+
dist: xenial # distro used by Travis, moveit_ci uses the docker image's distro
4+
services:
5+
- docker
6+
language: cpp
7+
compiler: gcc
8+
cache: ccache
9+
710
env:
811
global:
9-
- JOB_PATH=/tmp/devel_job
12+
- DOCKER_IMAGE=moveit/moveit:master-source
13+
- CXXFLAGS="-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unused-parameter -Wno-unused-function"
14+
- WARNINGS_OK=false
1015
matrix:
11-
- ROS_DISTRO_NAME=kinetic OS_NAME=ubuntu OS_CODE_NAME=xenial ARCH=amd64
12-
install:
13-
# either install the latest released version of ros_buildfarm
14-
- pip install ros_buildfarm
15-
# checkout catkin for catkin_test_results script
16-
- git clone https://github.com/ros/catkin /tmp/catkin
17-
# run devel job for a ROS repository with the same name as this repo
18-
- export REPOSITORY_NAME=`basename $TRAVIS_BUILD_DIR`
19-
# use the code already checked out by Travis
20-
- mkdir -p $JOB_PATH/catkin_workspace/src
21-
- cp -R $TRAVIS_BUILD_DIR $JOB_PATH/catkin_workspace/src/
22-
# generate the script to run a devel job for that target and repo
23-
- generate_devel_script.py https://raw.githubusercontent.com/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
24-
- cd $JOB_PATH
25-
- cat devel_job.sh
26-
# run the actual job which involves Docker
27-
- sh devel_job.sh -y
16+
- TEST="clang-format" # TODO(davetcoleman): enable catkin_lint in the future
17+
#- TEST=clang-tidy-fix # TODO(davetcoleman): enable in the future
18+
- DOCKER_IMAGE=moveit/moveit:melodic-source
19+
- DOCKER_IMAGE=moveit/moveit:master-source
20+
- DOCKER_IMAGE=moveit/moveit:kinetic-ci TEST_BLACKLIST=moveit_ros_perception
21+
22+
before_script:
23+
- git clone -q --depth=1 https://github.com/ros-planning/moveit_ci.git .moveit_ci
24+
2825
script:
29-
# get summary of test results
30-
- /tmp/catkin/bin/catkin_test_results $JOB_PATH/catkin_workspace/test_results --all
31-
notifications:
32-
email: false
26+
- .moveit_ci/travis.sh

include/rviz_visual_tools/rviz_visual_tools.h

Lines changed: 22 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -71,14 +71,14 @@
7171

7272
// Import/export for windows dll's and visibility for gcc shared libraries.
7373

74-
#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
75-
#ifdef rviz_visual_tools_EXPORTS // we are building a shared lib/dll
76-
#define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_EXPORT
77-
#else // we are using shared lib/dll
78-
#define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_IMPORT
79-
#endif
80-
#else // ros is being built around static libraries
81-
#define RVIZ_VISUAL_TOOLS_DECL
74+
#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
75+
#ifdef rviz_visual_tools_EXPORTS // we are building a shared lib/dll
76+
#define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_EXPORT
77+
#else // we are using shared lib/dll
78+
#define RVIZ_VISUAL_TOOLS_DECL ROS_HELPER_IMPORT
79+
#endif
80+
#else // ros is being built around static libraries
81+
#define RVIZ_VISUAL_TOOLS_DECL
8282
#endif
8383

8484
namespace rviz_visual_tools
@@ -197,7 +197,8 @@ class RvizVisualTools
197197
* \param marker_topic - rostopic to publish markers to - your Rviz display should match
198198
* \param nh - optional ros node handle - defaults to "~"
199199
*/
200-
explicit RvizVisualTools(std::string base_frame, std::string marker_topic = RVIZ_MARKER_TOPIC, ros::NodeHandle nh = ros::NodeHandle("~"));
200+
explicit RvizVisualTools(std::string base_frame, std::string marker_topic = RVIZ_MARKER_TOPIC,
201+
ros::NodeHandle nh = ros::NodeHandle("~"));
201202
/**
202203
* \brief Deconstructor
203204
*/
@@ -426,8 +427,8 @@ class RvizVisualTools
426427
* \param y_width - Y-size of the visualized plane [meters]
427428
* \return true on success
428429
*/
429-
bool publishABCDPlane(const double A, const double B, const double C, const double D,
430-
colors color=TRANSLUCENT, double x_width = 1.0, double y_width = 1.0);
430+
bool publishABCDPlane(const double A, const double B, const double C, const double D, colors color = TRANSLUCENT,
431+
double x_width = 1.0, double y_width = 1.0);
431432

432433
/**
433434
* \brief Display the XY plane of a given pose
@@ -485,8 +486,8 @@ class RvizVisualTools
485486
const std::string& ns = "Sphere", std::size_t id = 0);
486487
bool publishSphere(const geometry_msgs::Pose& pose, const std_msgs::ColorRGBA& color,
487488
const geometry_msgs::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0);
488-
bool publishSphere(const Eigen::Isometry3d& pose, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale,
489-
const std::string& ns = "Sphere", std::size_t id = 0);
489+
bool publishSphere(const Eigen::Isometry3d& pose, const std_msgs::ColorRGBA& color,
490+
const geometry_msgs::Vector3 scale, const std::string& ns = "Sphere", std::size_t id = 0);
490491
bool publishSphere(const Eigen::Vector3d& point, const std_msgs::ColorRGBA& color, const geometry_msgs::Vector3 scale,
491492
const std::string& ns = "Sphere", std::size_t id = 0);
492493
bool publishSphere(const geometry_msgs::PoseStamped& pose, colors color, const geometry_msgs::Vector3 scale,
@@ -668,10 +669,8 @@ class RvizVisualTools
668669
const std::string& ns = "Path");
669670
bool publishPath(const std::vector<geometry_msgs::Point>& path, colors color, scales scale,
670671
const std::string& ns = "Path");
671-
bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color, scales scale,
672-
const std::string& ns = "Path");
673-
bool publishPath(const EigenSTL::vector_Vector3d& path, colors color, scales scale,
674-
const std::string& ns = "Path");
672+
bool publishPath(const EigenSTL::vector_Isometry3d& path, colors color, scales scale, const std::string& ns = "Path");
673+
bool publishPath(const EigenSTL::vector_Vector3d& path, colors color, scales scale, const std::string& ns = "Path");
675674
bool publishPath(const std::vector<geometry_msgs::Point>& path, colors color = RED, double radius = 0.01,
676675
const std::string& ns = "Path");
677676
bool publishPath(const EigenSTL::vector_Vector3d& path, colors color = RED, double radius = 0.01,
@@ -861,8 +860,8 @@ class RvizVisualTools
861860
*/
862861
bool publishMesh(const Eigen::Isometry3d& pose, const shape_msgs::Mesh& mesh, colors color = CLEAR, double scale = 1,
863862
const std::string& ns = "mesh", std::size_t id = 0);
864-
bool publishMesh(const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color = CLEAR, double scale = 1,
865-
const std::string& ns = "mesh", std::size_t id = 0);
863+
bool publishMesh(const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color = CLEAR,
864+
double scale = 1, const std::string& ns = "mesh", std::size_t id = 0);
866865

867866
/**
868867
* \brief Display a graph
@@ -993,9 +992,9 @@ class RvizVisualTools
993992
@param convention - default is rviz_visual_tools::XYZ
994993
*/
995994
static Eigen::Isometry3d convertFromXYZRPY(double tx, double ty, double tz, double rx, double ry, double rz,
996-
EulerConvention convention); // ZYX is ROS standard
995+
EulerConvention convention); // ZYX is ROS standard
997996
static Eigen::Isometry3d convertFromXYZRPY(const std::vector<double>& transform6,
998-
EulerConvention convention); // ZYX is ROS standard
997+
EulerConvention convention); // ZYX is ROS standard
999998

1000999
// TODO(davetcoleman): add opposite conversion that uses Eigen::Vector3d rpy = pose.rotation().eulerAngles(0, 1, 2);
10011000

@@ -1006,8 +1005,8 @@ class RvizVisualTools
10061005
* \param output vector of size 6 in order xyz rpy
10071006
*/
10081007
static void convertToXYZRPY(const Eigen::Isometry3d& pose, std::vector<double>& xyzrpy);
1009-
static void convertToXYZRPY(const Eigen::Isometry3d& pose, double& x, double& y, double& z, double& roll, double& pitch,
1010-
double& yaw);
1008+
static void convertToXYZRPY(const Eigen::Isometry3d& pose, double& x, double& y, double& z, double& roll,
1009+
double& pitch, double& yaw);
10111010
/**
10121011
* \brief Create a random pose within bounds of random_pose_bounds_
10131012
* \param Pose to fill in

src/rviz_visual_tools.cpp

Lines changed: 19 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,6 @@
5151

5252
namespace rviz_visual_tools
5353
{
54-
5554
const std::string LOGNAME = "visual_tools";
5655

5756
// DEPRECATED, remove in Melodic after Dec 2018 release or so
@@ -325,8 +324,9 @@ bool RvizVisualTools::waitForSubscriber(const ros::Publisher& pub, double wait_t
325324
if (!blocking && ros::Time::now() > max_time) // Check if timed out
326325
{
327326
ROS_WARN_STREAM_NAMED(LOGNAME, "Topic '" << pub.getTopic() << "' unable to connect to any subscribers within "
328-
<< wait_time << " sec. It is possible initially published visual messages "
329-
"will be lost.");
327+
<< wait_time
328+
<< " sec. It is possible initially published visual messages "
329+
"will be lost.");
330330
return false;
331331
}
332332
ros::spinOnce();
@@ -487,8 +487,8 @@ std_msgs::ColorRGBA RvizVisualTools::getColor(colors color) const
487487
break;
488488
case DEFAULT:
489489
ROS_WARN_STREAM_NAMED(LOGNAME, "The 'DEFAULT' color should probably not "
490-
"be used with getColor(). Defaulting to "
491-
"blue.");
490+
"be used with getColor(). Defaulting to "
491+
"blue.");
492492
case BLUE:
493493
default:
494494
result.r = 0.1;
@@ -968,15 +968,15 @@ bool RvizVisualTools::publishCone(const geometry_msgs::Pose& pose, double angle,
968968
return publishMarker(triangle_marker_);
969969
}
970970

971-
bool RvizVisualTools::publishABCDPlane(const double A, const double B, const double C, const double D,
972-
colors color, double x_width, double y_width)
971+
bool RvizVisualTools::publishABCDPlane(const double A, const double B, const double C, const double D, colors color,
972+
double x_width, double y_width)
973973
{
974974
// The coefficients A,B,C give the normal to the plane.
975975
Eigen::Vector3d n(A, B, C);
976976

977977
// Graphic is centered at this point
978978
double distance = D / n.norm();
979-
Eigen::Vector3d center = - distance * n.normalized();
979+
Eigen::Vector3d center = -distance * n.normalized();
980980

981981
Eigen::Isometry3d pose;
982982
pose.translation() = center;
@@ -986,7 +986,7 @@ bool RvizVisualTools::publishABCDPlane(const double A, const double B, const dou
986986
Eigen::Quaterniond q = Eigen::Quaterniond::FromTwoVectors(z_0, n);
987987
pose.linear() = q.toRotationMatrix();
988988

989-
double height = 0.001; // very thin
989+
double height = 0.001; // very thin
990990
publishCuboid(pose, x_width, y_width, height, color);
991991

992992
return true;
@@ -1585,8 +1585,8 @@ bool RvizVisualTools::publishCylinder(const geometry_msgs::Pose& pose, const std
15851585
return publishMarker(cylinder_marker_);
15861586
}
15871587

1588-
bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const std::string& file_name, colors color, double scale,
1589-
const std::string& ns, std::size_t id)
1588+
bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const std::string& file_name, colors color,
1589+
double scale, const std::string& ns, std::size_t id)
15901590
{
15911591
return publishMesh(convertPose(pose), file_name, color, scale, ns, id);
15921592
}
@@ -1629,13 +1629,13 @@ bool RvizVisualTools::publishMesh(const geometry_msgs::Pose& pose, const std::st
16291629
return publishMarker(mesh_marker_);
16301630
}
16311631

1632-
bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const shape_msgs::Mesh& mesh, colors color,
1632+
bool RvizVisualTools::publishMesh(const Eigen::Isometry3d& pose, const shape_msgs::Mesh& mesh, colors color,
16331633
double scale, const std::string& ns, std::size_t id)
16341634
{
16351635
return publishMesh(convertPose(pose), mesh, color, scale, ns, id);
16361636
}
16371637

1638-
bool RvizVisualTools::publishMesh(const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color,
1638+
bool RvizVisualTools::publishMesh(const geometry_msgs::Pose& pose, const shape_msgs::Mesh& mesh, colors color,
16391639
double scale, const std::string& ns, std::size_t id)
16401640
{
16411641
triangle_marker_.header.stamp = ros::Time::now();
@@ -1652,7 +1652,7 @@ bool RvizVisualTools::publishMesh(const geometry_msgs::Pose& pose, const shape_m
16521652
// Set the mesh
16531653
triangle_marker_.points.clear();
16541654
for (const shape_msgs::MeshTriangle& triangle : mesh.triangles)
1655-
for (const uint32_t & index : triangle.vertex_indices)
1655+
for (const uint32_t& index : triangle.vertex_indices)
16561656
triangle_marker_.points.push_back(mesh.vertices[index]);
16571657

16581658
// Set the pose
@@ -2060,7 +2060,7 @@ bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, const s
20602060
if (path.size() != colors.size())
20612061
{
20622062
ROS_ERROR_STREAM_NAMED(LOGNAME, "Skipping path because " << path.size() << " different from " << colors.size()
2063-
<< ".");
2063+
<< ".");
20642064
return false;
20652065
}
20662066

@@ -2085,7 +2085,7 @@ bool RvizVisualTools::publishPath(const EigenSTL::vector_Vector3d& path, const s
20852085
if (path.size() != colors.size())
20862086
{
20872087
ROS_ERROR_STREAM_NAMED(LOGNAME, "Skipping path because " << path.size() << " different from " << colors.size()
2088-
<< ".");
2088+
<< ".");
20892089
return false;
20902090
}
20912091

@@ -2238,8 +2238,8 @@ bool RvizVisualTools::publishWireframeCuboid(const Eigen::Isometry3d& pose, cons
22382238
return publishMarker(line_list_marker_);
22392239
}
22402240

2241-
bool RvizVisualTools::publishWireframeRectangle(const Eigen::Isometry3d& pose, double height, double width, colors color,
2242-
scales scale, std::size_t id)
2241+
bool RvizVisualTools::publishWireframeRectangle(const Eigen::Isometry3d& pose, double height, double width,
2242+
colors color, scales scale, std::size_t id)
22432243
{
22442244
if (id == 0)
22452245
{ // Provide a new id every call to this function
@@ -2611,7 +2611,7 @@ geometry_msgs::Point RvizVisualTools::convertPoint(const Eigen::Vector3d& point)
26112611
}
26122612

26132613
Eigen::Isometry3d RvizVisualTools::convertFromXYZRPY(double tx, double ty, double tz, double rx, double ry, double rz,
2614-
EulerConvention convention)
2614+
EulerConvention convention)
26152615
{
26162616
Eigen::Isometry3d result;
26172617

src/rviz_visual_tools_demo.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -427,7 +427,7 @@ class RvizVisualToolsDemo
427427
A = x_plane;
428428
B = y_plane;
429429
// D takes this value to satisfy Ax+By+D=0
430-
D = - (x_plane * x_plane + y_plane * y_plane);
430+
D = -(x_plane * x_plane + y_plane * y_plane);
431431
visual_tools_->publishABCDPlane(A, B, C, D, rvt::MAGENTA, x_width, y_width);
432432
x_location += step;
433433
}

tests/rvt_test.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,6 @@
4949
class RVTTest
5050
{
5151
public:
52-
5352
bool initialize()
5453
{
5554
visual_tools_.reset(new rviz_visual_tools::RvizVisualTools("base", "/rviz_visual_tools"));

0 commit comments

Comments
 (0)