diff --git a/clearpath_generator_common/clearpath_generator_common/description/sensors.py b/clearpath_generator_common/clearpath_generator_common/description/sensors.py index 8e08d00..8fe4dd0 100644 --- a/clearpath_generator_common/clearpath_generator_common/description/sensors.py +++ b/clearpath_generator_common/clearpath_generator_common/description/sensors.py @@ -152,14 +152,12 @@ def __init__(self, sensor: BaseCamera) -> None: class AxisCameraDescription(CameraDescription): MODEL = 'model' - UPDATE_RATE = 'update_rate' def __init__(self, sensor: AxisCamera) -> None: super().__init__(sensor) self.parameters.update({ - self.MODEL: sensor.device_type, - self.UPDATE_RATE: sensor.fps, + self.MODEL: sensor.device_type }) class IntelRealsenseDescription(CameraDescription): diff --git a/clearpath_sensors_description/urdf/axis_camera.urdf.xacro b/clearpath_sensors_description/urdf/axis_camera.urdf.xacro index 0fc73fc..6dc154e 100644 --- a/clearpath_sensors_description/urdf/axis_camera.urdf.xacro +++ b/clearpath_sensors_description/urdf/axis_camera.urdf.xacro @@ -8,7 +8,6 @@ parent_link *origin model:=dome_ptz - update_rate:=15 topic:=image_raw "> @@ -16,7 +15,6 @@ prefix="${name}" parent="${parent_link}" topic="${topic}" - update_rate="${update_rate}" > @@ -26,7 +24,6 @@ prefix="${name}" parent="${parent_link}" topic="${topic}" - update_rate="${update_rate}" > @@ -36,7 +33,6 @@ prefix="${name}" parent="${parent_link}" topic="${topic}" - update_rate="${update_rate}" >