Skip to content

Commit d09c82c

Browse files
authored
Add camera_info_manager_py (#335)
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
1 parent cd049d0 commit d09c82c

18 files changed

+1691
-0
lines changed

camera_info_manager_py/CHANGELOG.rst

+65
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2+
Changelog for package camera_info_manager_py
3+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4+
5+
6.0.1 (2024-11-22)
6+
------------------
7+
* Bump package version to synchronize with image_common
8+
* Contributors: Chris Iverach-Brereton
9+
10+
1.0.0 (2024-05-16)
11+
------------------
12+
* Ros2 (`#2 <https://github.com/clearpathrobotics/camera_info_manager_py/issues/2>`_)
13+
* Run magic converter
14+
* Ament_python package
15+
* Fix some imports
16+
* Remove references to cpp camera info manager.
17+
Disable tests
18+
* Linting
19+
* Fully Remove old tests
20+
* Add lint tests
21+
* Final tests
22+
* Remove pep257 from depends
23+
* Contributors: Michael Hosmar
24+
25+
0.3.1 (2021-11-18)
26+
------------------
27+
* changelog
28+
* Contributors: José Mastrangelo
29+
30+
0.3.0 (2021-11-18)
31+
------------------
32+
* added CPR maintainer
33+
* Release to Melodic and Noetic
34+
* Contributors: Jack O'Quin, José Mastrangelo, Lucas Walter, Martin Pecka
35+
36+
0.2.3 (2014-05-13)
37+
------------------
38+
* Only use rostest when testing enabled, thanks to Lukas Bulwahn.
39+
* Move repository to ros-perception.
40+
* Contributors: Jack O'Quin, Lukas Bulwahn
41+
42+
0.2.2 (2013-07-25)
43+
------------------
44+
* Add namespace parameter to constructor, so a driver can handle multiple cameras. Enhancement thanks to Martin Llofriu.
45+
* Make unit tests conditional on ``CATKIN_ENABLE_TESTING``.
46+
* Release to Groovy and Hydro.
47+
* Contributors: Jack O'Quin, mllofriu
48+
49+
0.2.1 (2013-04-14)
50+
------------------
51+
* Set null calibration even when URL invalid (#7).
52+
* Release to Groovy and Hydro.
53+
* Contributors: Jack O'Quin
54+
55+
0.2.0 (2013-03-28)
56+
------------------
57+
* Convert to catkin.
58+
* Remove roslib dependency.
59+
* Release to Groovy and Hydro.
60+
* Contributors: Jack O'Quin
61+
62+
0.1.0 (2012-12-05)
63+
------------------
64+
* Initial Python camera_info_manager release to Fuerte.
65+
* Contributors: Jack O'Quin
+34
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
1+
cmake_minimum_required(VERSION 3.8)
2+
project(camera_info_manager_py)
3+
find_package(ament_cmake REQUIRED)
4+
find_package(rclpy REQUIRED)
5+
find_package(sensor_msgs REQUIRED)
6+
7+
include_directories(include)
8+
9+
ament_export_dependencies(sensor_msgs)
10+
ament_package()
11+
12+
catkin_install_python(
13+
PROGRAMS
14+
src/camera_info_manager/camera_info_manager.py
15+
src/camera_info_manager/zoom_camera_info_manager.py
16+
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
17+
18+
# Unit test uses nose, but needs rostest to create a ROS environment.
19+
if (BUILD_TESTING)
20+
find_package(roscpp REQUIRED)
21+
find_package(camera_info_manager REQUIRED)
22+
23+
find_package(rostest REQUIRED)
24+
add_executable(generate_camera_info
25+
tests/generate_camera_info.cpp
26+
)
27+
# TODO(lucasw) Can the roscpp and camera_info_manager dependencies
28+
# get added to catkin_LIBRARIES somehow?
29+
target_link_libraries(generate_camera_info ${catkin_LIBRARIES}
30+
${roscpp_LIBRARIES} ${camera_info_manager_LIBRARIES})
31+
32+
add_rostest(tests/load_cpp_camera_info.test DEPENDENCIES generate_camera_info)
33+
add_rostest(tests/unit_test.test)
34+
endif(CATKIN_ENABLE_TESTING)
+3
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
Any contribution that you make to this repository will
2+
be under the BSD license 2.0, as dictated by that
3+
[license](https://opensource.org/licenses/BSD-3-Clause).

camera_info_manager_py/LICENSE

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

camera_info_manager_py/README.rst

+16
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
Overview
2+
========
3+
4+
This ROS_ package defines a Python camera_info_manager interface,
5+
providing `sensor_msgs/CameraInfo`_ support for camera drivers written
6+
in Python.
7+
8+
ROS wiki documentation: `camera_info_manager_py`_.
9+
10+
This interface is similar to that of the C++ `camera_info_manager`_
11+
package, but not identical.
12+
13+
.. _ROS: http://ros.org
14+
.. _`sensor_msgs/CameraInfo`: http://ros.org/doc/api/sensor_msgs/html/msg/CameraInfo.html
15+
.. _`camera_info_manager`: http://ros.org/wiki/camera_info_manager
16+
.. _`camera_info_manager_py`: http://ros.org/wiki/camera_info_manager_py
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
camera_info_manager
2+
-------------------
3+
4+
.. automodule:: camera_info_manager
5+
:members:
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
# Copyright 2024 Clearpath Robotics Inc.
2+
# All rights reserved.
3+
#
4+
# Software License Agreement (BSD License 2.0)
5+
#
6+
# Redistribution and use in source and binary forms, with or without
7+
# modification, are permitted provided that the following conditions
8+
# are met:
9+
#
10+
# * Redistributions of source code must retain the above copyright
11+
# notice, this list of conditions and the following disclaimer.
12+
# * Redistributions in binary form must reproduce the above
13+
# copyright notice, this list of conditions and the following
14+
# disclaimer in the documentation and/or other materials provided
15+
# with the distribution.
16+
# * Neither the name of Clearpath Robotics Inc. nor the names of its
17+
# contributors may be used to endorse or promote products derived
18+
# from this software without specific prior written permission.
19+
#
20+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21+
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22+
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23+
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24+
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25+
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26+
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27+
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28+
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29+
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30+
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31+
# POSSIBILITY OF SUCH DAMAGE.
32+
33+
34+
from .camera_info_manager import * # noqa: F401, F403, RUF100
35+
from .zoom_camera_info_manager import * # noqa: F401, F403, RUF100

0 commit comments

Comments
 (0)