|
| 1 | +<?xml version="1.0"?> |
| 2 | +<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="camera"> |
| 3 | + |
| 4 | + <xacro:property name="pi" value="3.1415926535897931"/> |
| 5 | + |
| 6 | + |
| 7 | + <xacro:macro name="camera_sensor" params="xyz rpy parent"> |
| 8 | + <joint name="camera_sensor_joint" type="fixed"> |
| 9 | + <axis xyz="0 1 0" /> |
| 10 | + <origin xyz="${xyz}" rpy="${rpy}"/> |
| 11 | + <parent link="${parent}"/> |
| 12 | + <child link="camera_link"/> |
| 13 | + </joint> |
| 14 | + |
| 15 | + <link name="camera_link"> |
| 16 | + <collision> |
| 17 | + <origin xyz="0 0 0" rpy="0 0 0"/> |
| 18 | + <geometry> |
| 19 | + <box size="0.02 0.08 0.05"/> |
| 20 | + </geometry> |
| 21 | + </collision> |
| 22 | + <visual> |
| 23 | + <origin xyz="0 0 0" rpy="0 0 0"/> |
| 24 | + <geometry> |
| 25 | + <box size="0.02 0.08 0.05"/> |
| 26 | + </geometry> |
| 27 | + <material name="iRobot/Green"/> |
| 28 | + </visual> |
| 29 | + <inertial> |
| 30 | + <mass value="0.0001" /> |
| 31 | + <origin xyz="0 0 0" rpy="0 0 ${pi}"/> |
| 32 | + <inertia ixx="0.0000001" ixy="0" ixz="0" iyy="0.0000001" iyz="0" izz="0.0000001" /> |
| 33 | + </inertial> |
| 34 | + </link> |
| 35 | + |
| 36 | + |
| 37 | + |
| 38 | + <gazebo reference="camera_link"> |
| 39 | + <sensor type="camera" name="camera"> |
| 40 | + <update_rate>30.0</update_rate> |
| 41 | + <camera name="head"> |
| 42 | + <horizontal_fov>1.3962634</horizontal_fov> |
| 43 | + <image> |
| 44 | + <width>800</width> |
| 45 | + <height>600</height> |
| 46 | + <format>R8G8B8</format> |
| 47 | + </image> |
| 48 | + <clip> |
| 49 | + <near>0.02</near> |
| 50 | + <far>300</far> |
| 51 | + </clip> |
| 52 | + <noise> |
| 53 | + <type>gaussian</type> |
| 54 | + <mean>0.0</mean> |
| 55 | + <stddev>0.007</stddev> |
| 56 | + </noise> |
| 57 | + </camera> |
| 58 | + <plugin name="camera_controller" filename="libgazebo_ros_camera.so"> |
| 59 | + <alwaysOn>true</alwaysOn> |
| 60 | + <updateRate>0.0</updateRate> |
| 61 | + <cameraName>camera</cameraName> |
| 62 | + <imageTopicName>image_raw</imageTopicName> |
| 63 | + <cameraInfoTopicName>camera_info</cameraInfoTopicName> |
| 64 | + <frameName>camera_link</frameName> |
| 65 | + <hackBaseline>0.07</hackBaseline> |
| 66 | + <distortionK1>0.0</distortionK1> |
| 67 | + <distortionK2>0.0</distortionK2> |
| 68 | + <distortionK3>0.0</distortionK3> |
| 69 | + <distortionT1>0.0</distortionT1> |
| 70 | + <distortionT2>0.0</distortionT2> |
| 71 | + </plugin> |
| 72 | + </sensor> |
| 73 | + </gazebo> |
| 74 | + |
| 75 | + </xacro:macro> |
| 76 | + |
| 77 | +</robot> |
0 commit comments