Skip to content

Commit d9648a2

Browse files
authored
Added common linters to camera_calibration_parsers (#317)
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
1 parent 5505ad8 commit d9648a2

File tree

12 files changed

+300
-310
lines changed

12 files changed

+300
-310
lines changed

camera_calibration_parsers/CMakeLists.txt

Lines changed: 3 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -88,19 +88,9 @@ install(
8888
ament_export_dependencies(rclcpp sensor_msgs yaml_cpp_vendor)
8989

9090
if(BUILD_TESTING)
91-
#TODO(mjcarroll) switch back to this once I can fix copyright check
92-
#find_package(ament_lint_auto REQUIRED)
93-
#ament_lint_auto_find_test_dependencies()
94-
95-
find_package(ament_cmake_cppcheck REQUIRED)
96-
find_package(ament_cmake_cpplint REQUIRED)
97-
find_package(ament_cmake_lint_cmake REQUIRED)
98-
find_package(ament_cmake_uncrustify REQUIRED)
99-
#TODO(mjcarroll) Headers need to be .hpp for this to work properly.
100-
#ament_cppcheck()
101-
ament_cpplint()
102-
ament_lint_cmake()
103-
ament_uncrustify()
91+
find_package(ament_lint_auto REQUIRED)
92+
ament_lint_auto_find_test_dependencies()
93+
10494
find_package(ament_cmake_gtest)
10595

10696
ament_add_gtest(${PROJECT_NAME}-parse_ini test/test_parse_ini.cpp)

camera_calibration_parsers/include/camera_calibration_parsers/parse.hpp

Lines changed: 29 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -1,36 +1,32 @@
1-
/*********************************************************************
2-
* Software License Agreement (BSD License)
3-
*
4-
* Copyright (c) 2009, Willow Garage, Inc.
5-
* All rights reserved.
6-
*
7-
* Redistribution and use in source and binary forms, with or without
8-
* modification, are permitted provided that the following conditions
9-
* are met:
10-
*
11-
* * Redistributions of source code must retain the above copyright
12-
* notice, this list of conditions and the following disclaimer.
13-
* * Redistributions in binary form must reproduce the above
14-
* copyright notice, this list of conditions and the following
15-
* disclaimer in the documentation and/or other materials provided
16-
* with the distribution.
17-
* * Neither the name of the Willow Garage nor the names of its
18-
* contributors may be used to endorse or promote products derived
19-
* from this software without specific prior written permission.
20-
*
21-
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22-
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23-
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24-
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25-
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26-
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27-
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28-
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29-
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30-
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31-
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32-
* POSSIBILITY OF SUCH DAMAGE.
33-
*********************************************************************/
1+
// Copyright (c) 2009, Willow Garage, Inc.
2+
// All rights reserved.
3+
//
4+
// Redistribution and use in source and binary forms, with or without
5+
// modification, are permitted provided that the following conditions are met:
6+
//
7+
// * Redistributions of source code must retain the above copyright
8+
// notice, this list of conditions and the following disclaimer.
9+
//
10+
// * Redistributions in binary form must reproduce the above copyright
11+
// notice, this list of conditions and the following disclaimer in the
12+
// documentation and/or other materials provided with the distribution.
13+
//
14+
// * Neither the name of the copyright holder nor the names of its
15+
// contributors may be used to endorse or promote products derived from
16+
// this software without specific prior written permission.
17+
//
18+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28+
// POSSIBILITY OF SUCH DAMAGE.
29+
3430

3531
#ifndef CAMERA_CALIBRATION_PARSERS__PARSE_HPP_
3632
#define CAMERA_CALIBRATION_PARSERS__PARSE_HPP_

camera_calibration_parsers/include/camera_calibration_parsers/parse_ini.hpp

Lines changed: 28 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -1,36 +1,31 @@
1-
/*********************************************************************
2-
* Software License Agreement (BSD License)
3-
*
4-
* Copyright (c) 2009, Willow Garage, Inc.
5-
* All rights reserved.
6-
*
7-
* Redistribution and use in source and binary forms, with or without
8-
* modification, are permitted provided that the following conditions
9-
* are met:
10-
*
11-
* * Redistributions of source code must retain the above copyright
12-
* notice, this list of conditions and the following disclaimer.
13-
* * Redistributions in binary form must reproduce the above
14-
* copyright notice, this list of conditions and the following
15-
* disclaimer in the documentation and/or other materials provided
16-
* with the distribution.
17-
* * Neither the name of the Willow Garage nor the names of its
18-
* contributors may be used to endorse or promote products derived
19-
* from this software without specific prior written permission.
20-
*
21-
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22-
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23-
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24-
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25-
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26-
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27-
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28-
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29-
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30-
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31-
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32-
* POSSIBILITY OF SUCH DAMAGE.
33-
*********************************************************************/
1+
// Copyright (c) 2009, Willow Garage, Inc.
2+
// All rights reserved.
3+
//
4+
// Redistribution and use in source and binary forms, with or without
5+
// modification, are permitted provided that the following conditions are met:
6+
//
7+
// * Redistributions of source code must retain the above copyright
8+
// notice, this list of conditions and the following disclaimer.
9+
//
10+
// * Redistributions in binary form must reproduce the above copyright
11+
// notice, this list of conditions and the following disclaimer in the
12+
// documentation and/or other materials provided with the distribution.
13+
//
14+
// * Neither the name of the copyright holder nor the names of its
15+
// contributors may be used to endorse or promote products derived from
16+
// this software without specific prior written permission.
17+
//
18+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28+
// POSSIBILITY OF SUCH DAMAGE.
3429

3530
#ifndef CAMERA_CALIBRATION_PARSERS__PARSE_INI_HPP_
3631
#define CAMERA_CALIBRATION_PARSERS__PARSE_INI_HPP_

camera_calibration_parsers/include/camera_calibration_parsers/parse_yml.hpp

Lines changed: 29 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -1,36 +1,32 @@
1-
/*********************************************************************
2-
* Software License Agreement (BSD License)
3-
*
4-
* Copyright (c) 2009, Willow Garage, Inc.
5-
* All rights reserved.
6-
*
7-
* Redistribution and use in source and binary forms, with or without
8-
* modification, are permitted provided that the following conditions
9-
* are met:
10-
*
11-
* * Redistributions of source code must retain the above copyright
12-
* notice, this list of conditions and the following disclaimer.
13-
* * Redistributions in binary form must reproduce the above
14-
* copyright notice, this list of conditions and the following
15-
* disclaimer in the documentation and/or other materials provided
16-
* with the distribution.
17-
* * Neither the name of the Willow Garage nor the names of its
18-
* contributors may be used to endorse or promote products derived
19-
* from this software without specific prior written permission.
20-
*
21-
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22-
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23-
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24-
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25-
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26-
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27-
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28-
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29-
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30-
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31-
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32-
* POSSIBILITY OF SUCH DAMAGE.
33-
*********************************************************************/
1+
// Software License Agreement (BSD License)
2+
// Copyright (c) 2009, Willow Garage, Inc.
3+
// All rights reserved.
4+
//
5+
// Redistribution and use in source and binary forms, with or without
6+
// modification, are permitted provided that the following conditions are met:
7+
//
8+
// * Redistributions of source code must retain the above copyright
9+
// notice, this list of conditions and the following disclaimer.
10+
//
11+
// * Redistributions in binary form must reproduce the above copyright
12+
// notice, this list of conditions and the following disclaimer in the
13+
// documentation and/or other materials provided with the distribution.
14+
//
15+
// * Neither the name of the copyright holder nor the names of its
16+
// contributors may be used to endorse or promote products derived from
17+
// this software without specific prior written permission.
18+
//
19+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29+
// POSSIBILITY OF SUCH DAMAGE.
3430

3531
#ifndef CAMERA_CALIBRATION_PARSERS__PARSE_YML_HPP_
3632
#define CAMERA_CALIBRATION_PARSERS__PARSE_YML_HPP_

camera_calibration_parsers/setup.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,10 @@
11
# ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD
22

33
from distutils.core import setup
4+
45
from catkin_pkg.python_setup import generate_distutils_setup
56

7+
68
# fetch values from package.xml
79
setup_args = generate_distutils_setup(
810
packages=['camera_calibration_parsers'],

camera_calibration_parsers/src/camera_calibration_parsers/__init__.py

Lines changed: 33 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,40 @@
1+
# Copyright 2016
2+
# All rights reserved.
3+
#
4+
# Redistribution and use in source and binary forms, with or without
5+
# modification, are permitted provided that the following conditions are met:
6+
#
7+
# * Redistributions of source code must retain the above copyright
8+
# notice, this list of conditions and the following disclaimer.
9+
#
10+
# * Redistributions in binary form must reproduce the above copyright
11+
# notice, this list of conditions and the following disclaimer in the
12+
# documentation and/or other materials provided with the distribution.
13+
#
14+
# * Neither the name of the copyright holder nor the names of its
15+
# contributors may be used to endorse or promote products derived from
16+
# this software without specific prior written permission.
17+
#
18+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22+
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23+
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24+
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25+
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26+
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27+
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28+
# POSSIBILITY OF SUCH DAMAGE.
29+
130
from camera_calibration_parsers.camera_calibration_parsers_wrapper import __readCalibrationWrapper
231
from sensor_msgs.msg import CameraInfo
332

33+
434
def readCalibration(file_name):
5-
"""Read .ini or .yaml calibration file and return (camera name and cameraInfo message).
6-
35+
"""
36+
Read .ini or .yaml calibration file and return (camera name and cameraInfo message).
37+
738
@param file_name: camera calibration file name
839
@type file_name: str
940
@return: (camera name, cameraInfo message) or None on Error

camera_calibration_parsers/src/convert.cpp

Lines changed: 28 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -1,37 +1,31 @@
1-
/*********************************************************************
2-
* Software License Agreement (BSD License)
3-
*
4-
* Copyright (c) 2009, Willow Garage, Inc.
5-
* All rights reserved.
6-
*
7-
* Redistribution and use in source and binary forms, with or without
8-
* modification, are permitted provided that the following conditions
9-
* are met:
10-
*
11-
* * Redistributions of source code must retain the above copyright
12-
* notice, this list of conditions and the following disclaimer.
13-
* * Redistributions in binary form must reproduce the above
14-
* copyright notice, this list of conditions and the following
15-
* disclaimer in the documentation and/or other materials provided
16-
* with the distribution.
17-
* * Neither the name of the Willow Garage nor the names of its
18-
* contributors may be used to endorse or promote products derived
19-
* from this software without specific prior written permission.
20-
*
21-
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22-
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23-
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24-
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25-
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26-
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27-
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28-
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29-
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30-
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31-
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32-
* POSSIBILITY OF SUCH DAMAGE.
33-
*********************************************************************/
34-
1+
// Copyright (c) 2009, Willow Garage, Inc.
2+
// All rights reserved.
3+
//
4+
// Redistribution and use in source and binary forms, with or without
5+
// modification, are permitted provided that the following conditions are met:
6+
//
7+
// * Redistributions of source code must retain the above copyright
8+
// notice, this list of conditions and the following disclaimer.
9+
//
10+
// * Redistributions in binary form must reproduce the above copyright
11+
// notice, this list of conditions and the following disclaimer in the
12+
// documentation and/or other materials provided with the distribution.
13+
//
14+
// * Neither the name of the copyright holder nor the names of its
15+
// contributors may be used to endorse or promote products derived from
16+
// this software without specific prior written permission.
17+
//
18+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28+
// POSSIBILITY OF SUCH DAMAGE.
3529

3630
#include <cstdio>
3731
#include <string>

0 commit comments

Comments
 (0)