clearpath_config.sensors.sensors module
- class clearpath_config.sensors.sensors.Camera(model: str)
Bases:
object
- FLIR_BLACKFLY = 'flir_blackfly'
- INTEL_REALSENSE = 'intel_realsense'
- MODEL = {'flir_blackfly': <class 'clearpath_config.sensors.types.cameras.FlirBlackfly'>, 'intel_realsense': <class 'clearpath_config.sensors.types.cameras.IntelRealsense'>, 'stereolabs_zed': <class 'clearpath_config.sensors.types.cameras.StereolabsZed'>}
- STEREOLABS_ZED = 'stereolabs_zed'
- classmethod assert_model(model: str) None
- class clearpath_config.sensors.sensors.GlobalPositioningSystem(model: str)
Bases:
object
- GARMIN_18X = 'garmin_18x'
- MICROSTRAIN_GQ7 = 'microstrain_gq7'
- MODEL = {'garmin_18x': <class 'clearpath_config.sensors.types.gps.Garmin18x'>, 'microstrain_gq7': <class 'clearpath_config.sensors.types.gps.MicrostrainGQ7'>, 'novatel_smart6': <class 'clearpath_config.sensors.types.gps.NovatelSmart6'>, 'novatel_smart7': <class 'clearpath_config.sensors.types.gps.NovatelSmart7'>, 'swiftnav_duro': <class 'clearpath_config.sensors.types.gps.SwiftNavDuro'>}
- NOVATEL_SMART6 = 'novatel_smart6'
- NOVATEL_SMART7 = 'novatel_smart7'
- SWIFTNAV_DURO = 'swiftnav_duro'
- classmethod assert_model(model: str) None
- class clearpath_config.sensors.sensors.InertialMeasurementUnit(model: str)
Bases:
object
- CHROBOTICS_UM6 = 'chrobotics_um6'
- MICROSTRAIN_IMU = 'microstrain_imu'
- MODEL = {'chrobotics_um6': <class 'clearpath_config.sensors.types.imu.CHRoboticsUM6'>, 'microstrain_imu': <class 'clearpath_config.sensors.types.imu.Microstrain'>, 'redshift_um7': <class 'clearpath_config.sensors.types.imu.RedshiftUM7'>}
- REDSHIFT_UM7 = 'redshift_um7'
- classmethod assert_model(model: str) None
- class clearpath_config.sensors.sensors.Lidar2D(model: str)
Bases:
object
- HOKUYO_UST = 'hokuyo_ust'
- MODEL = {'hokuyo_ust': <class 'clearpath_config.sensors.types.lidars_2d.HokuyoUST'>, 'sick_lms1xx': <class 'clearpath_config.sensors.types.lidars_2d.SickLMS1XX'>}
- SICK_LMS1XX = 'sick_lms1xx'
- classmethod assert_model(model: str) None
- class clearpath_config.sensors.sensors.Lidar3D(model: str)
Bases:
object
- MODEL = {'velodyne_lidar': <class 'clearpath_config.sensors.types.lidars_3d.VelodyneLidar'>}
- VELODYNE_LIDAR = 'velodyne_lidar'
- classmethod assert_model(model: str) None
- class clearpath_config.sensors.sensors.Sensor(_type: str, _model: str)
Bases:
object
- CAMERA = 'camera'
- GPS = 'gps'
- IMU = 'imu'
- LIDAR2D = 'lidar2d'
- LIDAR3D = 'lidar3d'
- TYPE = {'camera': <class 'clearpath_config.sensors.sensors.Camera'>, 'gps': <class 'clearpath_config.sensors.sensors.GlobalPositioningSystem'>, 'imu': <class 'clearpath_config.sensors.sensors.InertialMeasurementUnit'>, 'lidar2d': <class 'clearpath_config.sensors.sensors.Lidar2D'>, 'lidar3d': <class 'clearpath_config.sensors.sensors.Lidar3D'>}
- classmethod assert_type(_type: str) None
- class clearpath_config.sensors.sensors.SensorConfig(config: dict = {}, camera: List[BaseCamera] = [], gps: List[BaseGPS] = [], imu: List[BaseIMU] = [], lidar2d: List[BaseLidar2D] = [], lidar3d: List[BaseLidar3D] = [])
Bases:
BaseConfig
- CAMERA = 'camera'
- CAMERA_INDEX = 0
- DEFAULTS = {'camera': [], 'gps': [], 'imu': [], 'lidar2d': [], 'lidar3d': []}
- GPS = 'gps'
- GPS_INDEX = 0
- IMU = 'imu'
- IMU_INDEX = 0
- KEYS = {'camera': 'sensors.camera', 'gps': 'sensors.gps', 'imu': 'sensors.imu', 'lidar2d': 'sensors.lidar2d', 'lidar3d': 'sensors.lidar3d'}
- LIDAR2D = 'lidar2d'
- LIDAR2D_INDEX = 0
- LIDAR3D = 'lidar3d'
- LIDAR3D_INDEX = 0
- SENSORS = 'sensors'
- TEMPLATE = {'sensors': {'camera': 'camera', 'gps': 'gps', 'imu': 'imu', 'lidar2d': 'lidar2d', 'lidar3d': 'lidar3d'}}
- add_blackfly(blackfly: FlirBlackfly | None = None, connection_type: str = 'USB3', encoding: str = 'BayerRG8', fps: int = 30, serial: str = '0', urdf_enabled: bool = True, launch_enabled: bool = True, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0]) None
- add_camera(camera: BaseCamera | None = None, model: str | None = None, fps: int = 30, serial: str = '0', 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]) None
- add_duro(duro: SwiftNavDuro | None = None, frame_id: str = 'link', ip: str = '192.168.131.30', port: int = 55555, urdf_enabled: bool = True, launch_enabled: bool = True, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0]) None
- add_gps(gps: BaseGPS | None = None, model: str | None = None, frame_id: str = 'link', urdf_enabled: bool = True, launch_enabled: bool = True, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0]) None
- add_imu(imu: BaseIMU | None = None, model: str | None = None, frame_id: str = 'link', port: str = '/dev/clearpath/imu', use_enu: bool = True, urdf_enabled: bool = True, launch_enabled: bool = True, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0]) None
- add_lidar2d(lidar2d: BaseLidar2D | None = None, model: str | None = None, frame_id: str = 'laser', ip: str = '192.168.131.20', port: int = 6000, min_angle: float = -3.141592653589793, max_angle: float = 3.141592653589793, urdf_enabled: bool = True, launch_enabled: bool = True, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0]) None
- add_lidar3d(lidar3d: BaseLidar3D | None = None, model: str | None = None, frame_id: str = 'laser', ip: str = '192.168.131.25', port: int = '2368', urdf_enabled: bool = True, launch_enabled: bool = True, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0]) None
- add_lms1xx(lms1xx: SickLMS1XX | None = None, frame_id: str = 'laser', ip: str = '192.168.131.20', port: int = 2111, min_angle: float = -2.391, max_angle: float = 2.391, urdf_enabled: bool = True, launch_enabled: bool = True, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0]) None
- add_microstrain(imu: Microstrain | None = None, frame_id: str = 'link', port: str = '/dev/microstrain_main', use_enu: bool = True, urdf_enabled: bool = True, launch_enabled: bool = True, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0]) None
- add_realsense(realsense: IntelRealsense | None = None, 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]) None
- add_ust(ust: HokuyoUST | None = None, frame_id: str = 'laser', ip: str = '192.168.131.20', port: int = 10940, min_angle: float = -3.141592653589793, max_angle: float = 3.141592653589793, urdf_enabled: bool = True, launch_enabled: bool = True, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0]) None
- add_velodyne(velodyne: VelodyneLidar | None = None, frame_id: str = 'laser', ip: str = '192.168.131.25', port: int = 2368, device_type: str = 'VLP16', urdf_enabled: bool = True, launch_enabled: bool = True, parent: str = 'default_mount', xyz: List[float] = [0.0, 0.0, 0.0], rpy: List[float] = [0.0, 0.0, 0.0]) None
- property camera: OrderedListConfig
- get_all_blackfly() List[FlirBlackfly]
- get_all_cameras() List[BaseCamera]
- get_all_cameras_by_model(model: str) List[BaseCamera]
- get_all_duro() List[SwiftNavDuro]
- get_all_lidar_2d() List[BaseLidar2D]
- get_all_lidar_2d_by_model(model: str) List[BaseLidar2D]
- get_all_lidar_3d() List[BaseLidar3D]
- get_all_lidar_3d_by_model(model: str) List[BaseLidar3D]
- get_all_lms1xx() List[SickLMS1XX]
- get_all_microstrain() List[Microstrain]
- get_all_realsense() List[IntelRealsense]
- get_all_sensors() List[BaseSensor]
- get_all_velodyne() List[VelodyneLidar]
- get_camera(idx: int) BaseCamera
- get_lidar_2d(idx: int) BaseLidar2D
- get_lidar_3d(idx: int) BaseLidar3D
- property gps: OrderedListConfig
- property imu: OrderedListConfig
- property lidar2d: OrderedListConfig
- property lidar3d: OrderedListConfig
- remove_camera(camera: BaseCamera | int) None
- remove_lidar_2d(lidar_2d: BaseLidar2D | int) None
- remove_lidar_3d(lidar_3d: BaseLidar3D | int) None
- set_all_camera(cameras: List[BaseCamera]) None
- set_all_lidar_2d(all_lidar_2d: List[BaseLidar2D]) None
- set_all_lidar_3d(all_lidar_3d: List[BaseLidar3D]) None
- set_camera(camera: BaseCamera) None
- set_lidar_2d(lidar_2d: BaseLidar2D) None
- set_lidar_3d(lidar_3d: BaseLidar3D) None
- update(serial_number=False) None
Update any variables based on inputs.
- class clearpath_config.sensors.sensors.SensorListConfig
Bases:
OrderedListConfig
[BaseSensor
]- to_dict() List[dict]