UGV Camera and World Gen Boxes
This commit is contained in:
@@ -115,11 +115,53 @@
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<!-- Forward-facing camera for obstacle detection -->
|
||||
<link name="front_camera_link">
|
||||
<pose>0.42 0 0.22 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>0.05</mass>
|
||||
<inertia>
|
||||
<ixx>0.00001</ixx><ixy>0</ixy><ixz>0</ixz>
|
||||
<iyy>0.00001</iyy><iyz>0</iyz><izz>0.00001</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<visual name="camera_visual">
|
||||
<geometry><box><size>0.03 0.03 0.03</size></box></geometry>
|
||||
<material>
|
||||
<ambient>0.1 0.1 0.1 1</ambient>
|
||||
<diffuse>0.1 0.1 0.1 1</diffuse>
|
||||
</material>
|
||||
</visual>
|
||||
<sensor name="front_camera" type="camera">
|
||||
<always_on>1</always_on>
|
||||
<update_rate>10</update_rate>
|
||||
<visualize>1</visualize>
|
||||
<topic>/ugv/camera/forward</topic>
|
||||
<camera>
|
||||
<horizontal_fov>1.3962634</horizontal_fov>
|
||||
<image>
|
||||
<width>640</width>
|
||||
<height>480</height>
|
||||
<format>R8G8B8</format>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.1</near>
|
||||
<far>50</far>
|
||||
</clip>
|
||||
</camera>
|
||||
</sensor>
|
||||
</link>
|
||||
|
||||
<joint name="aruco_joint" type="fixed">
|
||||
<parent>base_link</parent>
|
||||
<child>aruco_tag</child>
|
||||
</joint>
|
||||
|
||||
<joint name="front_camera_joint" type="fixed">
|
||||
<parent>base_link</parent>
|
||||
<child>front_camera_link</child>
|
||||
</joint>
|
||||
|
||||
<joint name="front_left_wheel_joint" type="revolute">
|
||||
<parent>base_link</parent>
|
||||
<child>front_left_wheel</child>
|
||||
|
||||
Reference in New Issue
Block a user