forgot this
This commit is contained in:
49
src/sherpa/urdf/components/camera.xacro
Normal file
49
src/sherpa/urdf/components/camera.xacro
Normal file
@@ -0,0 +1,49 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:macro name="camera" params="name parent xyz rpy frequency fov topic">
|
||||||
|
|
||||||
|
<link name="${name}_link">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.01"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.001"
|
||||||
|
ixy="0.0"
|
||||||
|
ixz="0.0"
|
||||||
|
iyy="0.001"
|
||||||
|
iyz="0.0"
|
||||||
|
izz="0.001"
|
||||||
|
/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
<joint name="${name}_joint" type="fixed">
|
||||||
|
<parent link="${parent}_link"/>
|
||||||
|
<child link="${name}_link"/>
|
||||||
|
<origin xyz="${xyz}" rpy="${rpy}"/>
|
||||||
|
</joint>
|
||||||
|
<gazebo reference="${name}_link">
|
||||||
|
<sensor name="${name}" type="camera">
|
||||||
|
<update_rate>${frequency}</update_rate>
|
||||||
|
<topic>${topic}</topic>
|
||||||
|
<gz_frame_id>${name}_link</gz_frame_id>
|
||||||
|
<camera name="${name}">
|
||||||
|
<horizontal_fov>${(fov/360) * (2*3.1415)}</horizontal_fov>
|
||||||
|
<image>
|
||||||
|
<width>800</width>
|
||||||
|
<height>800</height>
|
||||||
|
<format>R8G8B8</format>
|
||||||
|
</image>
|
||||||
|
<clip>
|
||||||
|
<near>0.02</near>
|
||||||
|
<far>300</far>
|
||||||
|
</clip>
|
||||||
|
<noise>
|
||||||
|
<type>gaussian</type>
|
||||||
|
<mean>0</mean>
|
||||||
|
<stddev>0.007</stddev>
|
||||||
|
</noise>
|
||||||
|
</camera>
|
||||||
|
</sensor>
|
||||||
|
</gazebo>
|
||||||
|
</xacro:macro>
|
||||||
|
</robot>
|
||||||
Reference in New Issue
Block a user