diff --git a/camera_info_manager_py/camera_info_manager/camera_info_manager.py b/camera_info_manager_py/camera_info_manager/camera_info_manager.py index 1360e289..f4080373 100644 --- a/camera_info_manager_py/camera_info_manager/camera_info_manager.py +++ b/camera_info_manager_py/camera_info_manager/camera_info_manager.py @@ -41,6 +41,7 @@ """ +import array import errno import locale import os @@ -48,12 +49,22 @@ from ament_index_python import get_package_share_directory from ament_index_python import PackageNotFoundError +import numpy as np import rclpy from rclpy.node import Node from sensor_msgs.msg import CameraInfo from sensor_msgs.srv import SetCameraInfo import yaml + +def _ndarray_representer(dumper: yaml.Dumper, array: np.ndarray) -> yaml.Node: + """Make yaml output a numpy array as though it were a simple list.""" + return dumper.represent_list(array.tolist()) + + +yaml.SafeDumper.add_representer(np.ndarray, _ndarray_representer) +yaml.SafeDumper.add_representer(array.array, yaml.representer.Representer.represent_list) + default_camera_info_url = 'file://${ROS_HOME}/camera_info/${NAME}.yaml' # parseURL() type codes: URL_empty = 0 # empty string @@ -326,7 +337,7 @@ def loadCameraInfo(self): """ self._loadCalibration(self.url, self.cname) - def setCameraInfo(self, req): + def setCameraInfo(self, req, rsp): """ Set camera info request callback. @@ -339,7 +350,6 @@ def setCameraInfo(self, req): """ self.node.get_logger().debug('SetCameraInfo received for ' + self.cname) self.camera_info = req.camera_info - rsp = SetCameraInfo.Response() rsp.success = saveCalibration(req.camera_info, self.url, self.cname) if not rsp.success: rsp.status_message = 'Error storing camera calibration.'