Skip to content
Open
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 14 additions & 2 deletions camera_info_manager_py/camera_info_manager/camera_info_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
import locale
import os
from pathlib import Path
import array

from ament_index_python import get_package_share_directory
from ament_index_python import PackageNotFoundError
Expand All @@ -53,6 +54,18 @@
from sensor_msgs.msg import CameraInfo
from sensor_msgs.srv import SetCameraInfo
import yaml
import numpy as np


def ndarray_representer(dumper: yaml.Dumper, array: np.ndarray) -> yaml.Node:
"""
This makes 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:
Expand Down Expand Up @@ -326,7 +339,7 @@ def loadCameraInfo(self):
"""
self._loadCalibration(self.url, self.cname)

def setCameraInfo(self, req):
def setCameraInfo(self, req, rsp):
"""
Set camera info request callback.

Expand All @@ -339,7 +352,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.'
Expand Down