Skip to content

Commit

Permalink
Add linter tests and fix errors (#30)
Browse files Browse the repository at this point in the history
* Fix include order for cpplint

Relates to ament/ament_lint#324

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Enable linter tests and fix errors

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron authored Jan 12, 2022
1 parent 846c25c commit c19bb2c
Show file tree
Hide file tree
Showing 4 changed files with 48 additions and 42 deletions.
5 changes: 3 additions & 2 deletions urdf/src/model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,6 @@
/* Author: Wim Meeussen */

#include "urdf/model.h"
#include <urdf_parser_plugin/parser.h>
#include <pluginlib/class_loader.hpp>

#include <cassert>
#include <fstream>
Expand All @@ -46,6 +44,9 @@
#include <utility>
#include <vector>

#include "urdf_parser_plugin/parser.h"
#include "pluginlib/class_loader.hpp"

// Windows has preprocessor defines for "max", which conflicts with
// several things (one of them being std::numeric_limits<T>::max()). Since
// we know we aren't going to use that macros, and this is a cpp (not header
Expand Down
8 changes: 8 additions & 0 deletions urdf_parser_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,14 @@ target_include_directories(urdf_parser_plugin INTERFACE
ament_target_dependencies(urdf_parser_plugin INTERFACE
"urdfdom_headers"
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
set(ament_cmake_cppcheck_LANGUAGE "c++")
set(ament_cmake_uncrustify_ADDITIONAL_ARGS LANGUAGE "C++")
ament_lint_auto_find_test_dependencies()
endif()

install(TARGETS urdf_parser_plugin EXPORT urdf_parser_plugin-export)
ament_export_targets(urdf_parser_plugin-export)
ament_export_dependencies(urdfdom_headers)
Expand Down
74 changes: 34 additions & 40 deletions urdf_parser_plugin/include/urdf_parser_plugin/parser.h
Original file line number Diff line number Diff line change
@@ -1,46 +1,40 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2013, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
// Copyright (c) 2013, Willow Garage, Inc.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the Willow Garage nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

/* Author: Ioan Sucan */

#ifndef URDF_PARSER_PLUGIN_H
#define URDF_PARSER_PLUGIN_H

#include <urdf_world/types.h>
#ifndef URDF_PARSER_PLUGIN__PARSER_H_
#define URDF_PARSER_PLUGIN__PARSER_H_

#include <string>

#include "urdf_world/types.h"

namespace urdf
{

Expand Down Expand Up @@ -70,7 +64,7 @@ class URDFParser
/// return a value greater than or equal to data.size().
virtual size_t might_handle(const std::string & data) = 0;
};

}

#endif
} // namespace urdf

#endif // URDF_PARSER_PLUGIN__PARSER_H_
3 changes: 3 additions & 0 deletions urdf_parser_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,9 @@
<build_depend>urdfdom_headers</build_depend>
<build_export_depend>urdfdom_headers</build_export_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down

0 comments on commit c19bb2c

Please sign in to comment.