Skip to content

Commit

Permalink
Remove the update_rate parameter; it's not supported by axis_camera
Browse files Browse the repository at this point in the history
  • Loading branch information
civerachb-cpr committed Nov 15, 2024
1 parent dc5837e commit a4bf685
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down
4 changes: 0 additions & 4 deletions clearpath_sensors_description/urdf/axis_camera.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,15 +8,13 @@
parent_link
*origin
model:=dome_ptz
update_rate:=15
topic:=image_raw
">
<xacro:if value="${model == 'dome_fixed'}">
<xacro:axis_dome_fixed
prefix="${name}"
parent="${parent_link}"
topic="${topic}"
update_rate="${update_rate}"
>
<xacro:insert_block name="origin" />
</xacro:axis_dome_fixed>
Expand All @@ -26,7 +24,6 @@
prefix="${name}"
parent="${parent_link}"
topic="${topic}"
update_rate="${update_rate}"
>
<xacro:insert_block name="origin" />
</xacro:axis_dome_ptz>
Expand All @@ -36,7 +33,6 @@
prefix="${name}"
parent="${parent_link}"
topic="${topic}"
update_rate="${update_rate}"
>
<xacro:insert_block name="origin" />
</xacro:axis_q62>
Expand Down

0 comments on commit a4bf685

Please sign in to comment.