clearpath_config.sensors.types.cameras module

class clearpath_config.sensors.types.cameras.AxisCamera(idx: int = None, name: str = None, topic: str = 'image', fps: int = 20, serial: str = '', device_type: str = 'dome_fixed', hostname: str = '192.168.10.0', http_port: int = 80, username: str = 'root', password: str = '', use_encrypted_password: bool = True, camera_info_url: str = '', camera: int = 1, width: int = 640, height: int = 480, enable_ptz: bool = True, min_pan: float = -3.141592653589793, max_pan: float = 3.141592653589793, min_tilt: float = -1.5707963267948966, max_tilt: float = 1.5707963267948966, min_zoom: float = 1, max_zoom: float = 24, max_pan_speed: float = 2.61, max_tilt_speed: float = 2.61, enable_ir: bool = False, enable_wiper: bool = False, enable_defog: bool = False, enable_ptz_teleop: bool = False, button_enable_pan_tilt: int = -1, button_enable_zoom: int = -1, axis_pan: int = -1, axis_tilt: int = -1, invert_tilt: bool = False, axis_zoom_in: int = -1, axis_zoom_out: int = -1, zoom_in_offset: float = 0.0, zoom_out_offset: float = 0.0, zoom_in_scale: float = 1.0, zoom_out_scale: float = 1.0, scale_pan: float = 1.0, scale_tilt: float = 1.0, scale_zoom: float = 1.0, urdf_enabled: bool = True, launch_enabled: bool = True, ros_parameters: dict = {}, ros_parameters_template: dict = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseCamera

PTZ and fixed cameras that use the axis_camera driver.

AXIS_PAN = -1
AXIS_TILT = -1
AXIS_ZOOM_IN = -1
AXIS_ZOOM_OUT = -1
BUTTON_ENABLE_PAN_TILT = -1
BUTTON_ENABLE_ZOOM = -1
CAMERA = 1
CAMERA_INFO_URL = ''
DEFAULT = 'dome_fixed'
DEVICE_TYPE = 'dome_ptz'
DEVICE_TYPES = ('q62', 'dome_ptz', 'dome_fixed')
DOME_FIXED = 'dome_fixed'
DOME_PTZ = 'dome_ptz'
ENABLE_DEFOG = False
ENABLE_IR = False
ENABLE_PTZ = True
ENABLE_PTZ_TELEOP = False
ENABLE_WPER = False
FPS = 20
HEIGHT = 480
HOSTNAME = '192.168.10.0'
HTTP_PORT = 80
INVERT_TILT = False
MAX_PAN = 3.141592653589793
MAX_PAN_SPEED = 2.61
MAX_TILT = 1.5707963267948966
MAX_TILT_SPEED = 2.61
MAX_ZOOM = 24
MIN_PAN = -3.141592653589793
MIN_TILT = -1.5707963267948966
MIN_ZOOM = 1
PASSWORD = ''
Q62 = 'q62'
class ROS_PARAMETER_KEYS

Bases: object

AXIS_PAN = 'axis_camera.axis_pan'
AXIS_TILT = 'axis_camera.axis_tilt'
AXIS_ZOOM_IN = 'axis_camera.axis_zoom_in'
AXIS_ZOOM_OUT = 'axis_camera.axis_zoom_out'
BUTTON_ENABLE_PAN_TILT = 'axis_camera.button_enable_pan_tilt'
BUTTON_ENABLE_ZOOM = 'axis_camera.button_enable_zoom'
CAMERA = 'axis_camera.camera'
CAMERA_INFO_URL = 'axis_camera.camera_info_url'
DEVICE_TYPE = 'axis_camera.device_type'
ENABLE_DEFOG = 'axis_camera.defog'
ENABLE_IR = 'axis_camera.ir'
ENABLE_PTZ = 'axis_camera.ptz'
ENABLE_PTZ_TELEOP = 'axis_camera.ptz_teleop'
ENABLE_WIPER = 'axis_camera.wiper'
FPS = 'axis_camera.fps'
HEIGHT = 'axis_camera.height'
HOSTNAME = 'axis_camera.hostname'
HTTP_PORT = 'axis_camera.http_port'
INVERT_TILT = 'axis_camera.invert_tilt'
MAX_PAN = 'axis_camera.max_pan'
MAX_PAN_SPEED = 'axis_camera.max_pan_speed'
MAX_TILT = 'axis_camera.max_tilt'
MAX_TILT_SPEED = 'axis_camera.max_tilt_speed'
MAX_ZOOM = 'axis_camera.max_zoom'
MIN_PAN = 'axis_camera.min_pan'
MIN_TILT = 'axis_camera.min_tilt'
MIN_ZOOM = 'axis_camera.min_zoom'
PASSWORD = 'axis_camera.password'
SCALE_PAN = 'axis_camera.scale_pan'
SCALE_TILT = 'axis_camera.scale_tilt'
SCALE_ZOOM = 'axis_camera.scale_zoom'
SERIAL = 'axis_camera.serial'
TF_PREFIX = 'axis_camera.tf_prefix'
USERNAME = 'axis_camera.username'
USE_ENCRYPTED_PASSWORD = 'axis_camera.use_encrypted_password'
WIDTH = 'axis_camera.width'
ZOOM_IN_OFFSET = 'axis_camera.zoom_in_offset'
ZOOM_IN_SCALE = 'axis_camera.zoom_in_scale'
ZOOM_OUT_OFFSET = 'axis_camera.zoom_out_offset'
ZOOM_OUT_SCALE = 'axis_camera.zoom_out_scale'
SCALE_PAN = 1.0
SCALE_TILT = 1.0
SCALE_ZOOM = 1.0
SENSOR_MODEL = 'axis_camera'
SERIAL = ''
TF_PREFIX = 'axis'
class TOPICS

Bases: object

AUTOFOCUS = 'autofocus'
AUTOIRIS = 'autoiris'
BRIGHTNESS = 'brightness'
COLOR_CAMERA_INFO = 'color_camera_info'
COLOR_IMAGE = 'color_image'
FOCUS = 'focus'
IRIS = 'iris'
JOINT_STATES = 'joint_states'
NAME = {'color_camera_info': 'color/camera_info', 'color_image': 'color/image/compressed'}
PTZ_STATE = 'ptz_state'
TYPE = {'color_camera_info': 'sensor_msgs/msg/CameraInfo', 'color_image': 'sensor_msgs/msg/CompressedImage'}
USERNAME = 'root'
USE_ENCRYPTED_PASSWORD = True
WIDTH = 640
ZOOM_IN_OFFSET = 0.0
ZOOM_IN_SCALE = 1.0
ZOOM_OUT_OFFSET = 0.0
ZOOM_OUT_SCALE = 1.0
property axis_pan: int
property axis_tilt: int
property axis_zoom_in: int
property axis_zoom_out: int
property button_enable_pan_tilt: int
property button_enable_zoom: int
property camera: int
property camera_info_url: str
property device_type: str
property enable_defog: bool
property enable_ir: bool
property enable_ptz: bool
property enable_ptz_teleop: bool
property enable_wiper: bool
property height: int
property hostname: str
property http_port: int
property invert_tilt: bool
property max_pan: float
property max_pan_speed: float
property max_tilt: float
property max_tilt_speed: float
property max_zoom: float
property min_pan: float
property min_tilt: float
property min_zoom: float
property password: str
property scale_pan: float
property scale_tilt: float
property scale_zoom: float
property tf_prefix: str
property use_encrypted_password: bool
property username: str
property width: int
property zoom_in_offset: float
property zoom_in_scale: float
property zoom_out_offset: float
property zoom_out_scale: float
class clearpath_config.sensors.types.cameras.BaseCamera(idx: int = None, name: str = None, topic: str = 'image', fps: int = 30, serial: str = '0', urdf_enabled: bool = True, launch_enabled: bool = True, ros_parameters: dict = {}, ros_parameters_template: dict = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseSensor

FPS = 30
class ROS_PARAMETER_KEYS

Bases: object

FPS = 'node_name.fps'
SERIAL = 'node_name.serial'
SENSOR_MODEL = 'base'
SENSOR_TYPE = 'camera'
SERIAL = '0'
TOPIC = 'image'
class TOPICS

Bases: object

COLOR_CAMERA_INFO = 'color_camera_info'
COLOR_IMAGE = 'color_image'
NAME = {'color_camera_info': 'color/camera_info', 'color_image': 'color/image'}
TYPE = {'color_camera_info': 'sensor_msgs/msg/CameraInfo', 'color_image': 'sensor_msgs/msg/Image'}
property camera_name: str
property fps: int
from_dict(d: dict) None
property republishers: list
property serial: str
to_dict() dict
class clearpath_config.sensors.types.cameras.FlirBlackfly(idx: int = None, name: str = None, topic: str = 'image', fps: float = 30, serial: str = '0', connection_type: str = 'USB3', encoding: str = 'BayerRG8', urdf_enabled: bool = True, launch_enabled: bool = True, ros_parameters: str = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseCamera

BAYER_BG12 = 'BayerBG12p'
BAYER_BG12_PACKED = 'BayerBG12Packed'
BAYER_BG16 = 'BayerBG16'
BAYER_BG8 = 'BayerBG8'
BAYER_GB12 = 'BayerGB12p'
BAYER_GB12_PACKED = 'BayerGB12Packed'
BAYER_GB16 = 'BayerGB16'
BAYER_GB8 = 'BayerGB8'
BAYER_GR12 = 'BayerGR12p'
BAYER_GR12_PACKED = 'BayerGR12Packed'
BAYER_GR16 = 'BayerGR16'
BAYER_GR8 = 'BayerGR8'
BAYER_RG12 = 'BayerRG12p'
BAYER_RG12_PACKED = 'BayerRG12Packed'
BAYER_RG16 = 'BayerRG16'
BAYER_RG8 = 'BayerRG8'
BGRA_8 = 'BGRa8'
BGR_8 = 'BGR8'
CONNECTION_TYPE = 'USB3'
CONNECTION_TYPES = ('USB3', 'GigE')
ENCODINGS = ('Mono8', 'Mono16', 'Mono12p', 'Mono12Packed', 'YUV411Packed', 'YUV422Packed', 'YUV444Packed', 'YCbCr8', 'YCbCr422_8', 'YCbCr411_8', 'BGR8', 'BGRa8', 'RGB8Packed', 'BayerGR8', 'BayerRG8', 'BayerGB8', 'BayerBG8', 'BayerGR16', 'BayerRG16', 'BayerGB16', 'BayerBG16', 'BayerGR12p', 'BayerRG12p', 'BayerGB12p', 'BayerBG12p', 'BayerGR12Packed', 'BayerRG12Packed', 'BayerGB12Packed', 'BayerBG12Packed')
GIGE_CONNECTION = 'GigE'
MONO_12 = 'Mono12p'
MONO_12_PACKED = 'Mono12Packed'
MONO_16 = 'Mono16'
MONO_8 = 'Mono8'
RGB_8_PACKED = 'RGB8Packed'
class ROS_PARAMETER_KEYS

Bases: object

ENCODING = 'flir_blackfly.pixel_format'
FPS = 'flir_blackfly.frame_rate'
SERIAL = 'flir_blackfly.serial_number'
SENSOR_MODEL = 'flir_blackfly'
USB3_CONNECTION = 'USB3'
YCBCR_411_8 = 'YCbCr411_8'
YCBCR_422_8 = 'YCbCr422_8'
YCBCR_8 = 'YCbCr8'
YUV_411_PACKED = 'YUV411Packed'
YUV_422_PACKED = 'YUV422Packed'
YUV_444_PACKED = 'YUV444Packed'
property connection_type: str
property encoding: str
property fps: float
class clearpath_config.sensors.types.cameras.IntelRealsense(idx: int = None, name: str = None, topic: str = 'image', serial: str = '0', device_type: str = 'd435', color_enabled: bool = True, color_fps: bool = 30, color_width: int = 640, color_height: int = 480, depth_enabled: bool = True, depth_fps: int = 30, depth_width: int = 640, depth_height: int = 480, pointcloud_enabled: bool = True, urdf_enabled: bool = True, launch_enabled: bool = True, ros_parameters: dict = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseCamera

COLOR_ENABLED = True
COLOR_FPS = 30
COLOR_HEIGHT = 480
COLOR_WIDTH = 640
D415 = 'd415'
D435 = 'd435'
D435i = 'd435i'
DEPTH_ENABLED = True
DEPTH_FPS = 30
DEPTH_HEIGHT = 480
DEPTH_WIDTH = 640
DEVICE_TYPE = 'd435'
DEVICE_TYPES = ('d415', 'd435', 'd435i')
POINTCLOUD_ENABLED = True
class ROS_PARAMETER_KEYS

Bases: object

CAMERA_NAME = 'intel_realsense.camera_name'
COLOR_ENABLE = 'intel_realsense.enable_color'
DEPTH_ENABLE = 'intel_realsense.enable_depth'
DEPTH_PROFILE = 'intel_realsense.depth_module.depth_profile'
DEVICE_TYPE = 'intel_realsense.device_type'
FPS = 'intel_realsense.rgb_camera.color_profile'
POINTCLOUD_ENABLE = 'intel_realsense.pointcloud.enable'
SERIAL = 'intel_realsense.serial_no'
SENSOR_MODEL = 'intel_realsense'
class TOPICS

Bases: object

COLOR_CAMERA_INFO = 'color_camera_info'
COLOR_IMAGE = 'color_image'
DEPTH_CAMERA_INFO = 'depth_camera_info'
DEPTH_IMAGE = 'depth_image'
IMU = 'imu'
NAME = {'color_camera_info': 'color/camera_info', 'color_image': 'color/image', 'depth_camera_info': 'depth/camera_info', 'depth_image': 'depth/image', 'imu': 'imu', 'points': 'points'}
POINTCLOUD = 'points'
TYPE = {'color_camera_info': 'sensor_msgs/msg/CameraInfo', 'color_image': 'sensor_msgs/msg/Image', 'depth_camera_info': 'sensor_msgs/msg/CameraInfo', 'depth_image': 'sensor_msgs/msg/Image', 'imu': 'sensor_msgs/msg/Imu', 'points': 'sensor_msgs/msg/PointCloud2'}
assert_pixel_length(length: int) None
static clean_profile(profile: str | list) list
property color_enabled: bool
property color_fps: int
property color_height: int
property color_profile: str
property color_width: int
property depth_enabled: bool
property depth_fps: int
property depth_height: int
property depth_profile: str
property depth_width: int
property device_type: str
property pointcloud_enabled: bool
class clearpath_config.sensors.types.cameras.LuxonisOAKD(idx: int = None, name: str = None, topic: str = 'image', fps: int = 30.0, stereo_fps: int = 30.0, serial: str = '0', device_type: str = 'pro', urdf_enabled: bool = True, launch_enabled: bool = True, ros_parameters: dict = {}, ros_parameters_template: dict = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseCamera

DEVICE_TYPE = 'pro'
DEVICE_TYPES = ('pro', 'lite')
FPS = 30.0
HEIGHT = 720
LITE = 'lite'
PRO = 'pro'
class ROS_PARAMETER_KEYS

Bases: object

FPS = 'oakd.rgb.i_fps'
HEIGHT = 'oakd.rgb.i_height'
SERIAL = 'oakd.rgb.i_usb_port_id'
STEREO_FPS = 'oakd.stereo.i_fps'
WIDTH = 'oakd.rgb.i_width'
SENSOR_MODEL = 'luxonis_oakd'
SERIAL = 0
class TOPICS

Bases: object

COLOR_CAMERA_INFO = 'color_camera_info'
COLOR_IMAGE = 'color_image'
IMU = 'imu'
NAME = {'color_camera_info': 'color/camera_info', 'color_image': 'color/image', 'imu': 'imu', 'points': 'points', 'stereo_camera_info': 'stereo/camera_info', 'stereo_image': 'stereo/image'}
POINTCLOUD = 'points'
STEREO_CAMERA_INFO = 'stereo_camera_info'
STEREO_IMAGE = 'stereo_image'
TYPE = {'color_camera_info': 'sensor_msgs/msg/CameraInfo', 'color_image': 'sensor_msgs/msg/Image', 'imu': 'sensor_msgs/msg/Imu', 'points': 'sensor_msgs/msg/PointCloud2', 'stereo_camera_info': 'sensor_msgs/msg/CameraInfo', 'stereo_image': 'sensor_msgs/msg/Image'}
WIDTH = 1280
property fps: float
property height: int
property stereo_fps: float
property width: int
class clearpath_config.sensors.types.cameras.Republisher(config: dict)

Bases: object

class Base(config: dict)

Bases: object

INPUT = 'input'
INPUT_DEFAULT = 'in'
OUTPUT = 'output'
OUTPUT_DEFAULT = 'out'
from_dict(config: dict) None
property input: str
property output: str
to_dict() dict
class Compress(config: dict)

Bases: Base

INPUT_DEFAULT = 'color'
OUTPUT_DEFAULT = 'compressed'
TYPE = 'compress'
class Rectify(config: dict)

Bases: Base

INPUT_DEFAULT = 'color'
OUTPUT_DEFAULT = 'rectified'
TYPE = 'rectify'
class Resize(config: dict)

Bases: Base

INPUT_DEFAULT = 'color'
OUTPUT_DEFAULT = 'resize'
TYPE = 'resize'
TYPE = 'type'
TYPES = {'compress': <class 'clearpath_config.sensors.types.cameras.Republisher.Compress'>, 'rectify': <class 'clearpath_config.sensors.types.cameras.Republisher.Rectify'>, 'resize': <class 'clearpath_config.sensors.types.cameras.Republisher.Resize'>, 'theora': <class 'clearpath_config.sensors.types.cameras.Republisher.Theora'>}
class Theora(config: dict)

Bases: Base

INPUT_DEFAULT = 'color'
OUTPUT_DEFAULT = 'theora'
TYPE = 'theora'
class clearpath_config.sensors.types.cameras.StereolabsZed(idx: int = None, name: str = None, topic: str = 'image', fps: int = 30, serial: str = '0', device_type: str = 'zed2', resolution: str = 'AUTO', urdf_enabled: bool = True, launch_enabled: bool = True, ros_parameters: dict = {}, ros_parameters_template: dict = {}, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0])

Bases: BaseCamera

DEVICE_TYPE = 'zed2'
DEVICE_TYPES = ('zed', 'zedm', 'zed2', 'zed2i', 'zedx', 'zedxm', 'virtual')
RESOLUTION_DEFAULT = 'AUTO'
RESOLUTION_PRESETS = ('AUTO', 'HD2K', 'HD1080', 'HD720', 'VGA')
class ROS_PARAMETER_KEYS

Bases: object

CAMERA_MODEL = 'stereolabs_zed.general.camera_model'
CAMERA_NAME = 'stereolabs_zed.general.camera_name'
FPS = 'stereolabs_zed.general.grab_frame_rate'
RESOLUTION = 'stereolabs_zed.general.grab_resolution'
SERIAL = 'stereolabs_zed.general.serial_number'
SENSOR_MODEL = 'stereolabs_zed'
SERIAL = 0
class TOPICS

Bases: object

COLOR_CAMERA_INFO = 'color_camera_info'
COLOR_IMAGE = 'color_image'
DEPTH_CAMERA_INFO = 'depth_camera_info'
DEPTH_IMAGE = 'depth_image'
IMU = 'imu'
NAME = {'color_camera_info': 'color/camera_info', 'color_image': 'color/image', 'depth_camera_info': 'depth/camera_info', 'depth_image': 'depth/image', 'imu': 'imu', 'points': 'points'}
POINTCLOUD = 'points'
TYPE = {'color_camera_info': 'sensor_msgs/msg/CameraInfo', 'color_image': 'sensor_msgs/msg/Image', 'depth_camera_info': 'sensor_msgs/msg/CameraInfo', 'depth_image': 'sensor_msgs/msg/Image', 'imu': 'sensor_msgs/msg/Imu', 'points': 'sensor_msgs/msg/PointCloud2'}
VIRTUAL = 'virtual'
ZED = 'zed'
ZED2 = 'zed2'
ZED2I = 'zed2i'
ZEDM = 'zedm'
ZEDX = 'zedx'
ZEDXM = 'zedxm'
static assert_is_supported()

Override this method to temporarily disable accessories that are not currently supported.

When disabling an accessory, raise a clearpath_config.common.types.exception.UnsupportedAccessoryException with a suitable mesage (e.g. ‘SpamEggs driver is not yet released for ROS 2 Jazzy’)

@return None

@exception Raises a clearpath_config.common.types.exception.UnsupportedAccessoryException

if the accessory is not supported

property device_type: str
property resolution: str
property serial: int