Skip to content

Commit

Permalink
GstCameraPlugin: add GstCameraPlugin to all gimbals
Browse files Browse the repository at this point in the history
Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring committed Aug 7, 2024
1 parent 5418a54 commit 68aef85
Show file tree
Hide file tree
Showing 3 changed files with 24 additions and 6 deletions.
9 changes: 9 additions & 0 deletions models/gimbal_small_1d/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,15 @@
<always_on>1</always_on>
<update_rate>10</update_rate>
<visualize>1</visualize>

<plugin name="GstCameraPlugin"
filename="GstCameraPlugin">
<udp_host>127.0.0.1</udp_host>
<udp_port>5600</udp_port>
<use_basic_pipeline>true</use_basic_pipeline>
<use_cuda>false</use_cuda>
</plugin>

</sensor>
</link>
<joint name='tilt_joint' type='revolute'>
Expand Down
9 changes: 9 additions & 0 deletions models/gimbal_small_2d/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,15 @@
<always_on>1</always_on>
<update_rate>10</update_rate>
<visualize>1</visualize>

<plugin name="GstCameraPlugin"
filename="GstCameraPlugin">
<udp_host>127.0.0.1</udp_host>
<udp_port>5600</udp_port>
<use_basic_pipeline>true</use_basic_pipeline>
<use_cuda>false</use_cuda>
</plugin>

</sensor>
</link>
<joint name='tilt_joint' type='revolute'>
Expand Down
12 changes: 6 additions & 6 deletions models/gimbal_small_3d/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -211,12 +211,12 @@
<slew_rate>0.42514285714</slew_rate>
</plugin>

<plugin filename="GstCameraPlugin"
name="GstCameraPlugin">
<udpHost>127.0.0.1</udpHost>
<udpPort>5600</udpPort>
<imageTopic>/world/iris_runway/model/iris_with_gimbal/model/gimbal/link/pitch_link/sensor/camera/image</imageTopic>
<enableTopic>/enable_video_stream</enableTopic>
<plugin name="GstCameraPlugin"
filename="GstCameraPlugin">
<udp_host>127.0.0.1</udp_host>
<udp_port>5600</udp_port>
<use_basic_pipeline>true</use_basic_pipeline>
<use_cuda>false</use_cuda>
</plugin>

</sensor>
Expand Down

0 comments on commit 68aef85

Please sign in to comment.