Skip to content
Snippets Groups Projects
atlas.urdf 77.2 KiB
Newer Older
Guilhem Saurel's avatar
Guilhem Saurel committed
    <origin rpy="0 0 0" xyz="0.03 0 0.015"/>
    <parent link="hokuyo_link"/>
    <child link="head_hokuyo_frame"/>
  </joint>
  <link name="head_hokuyo_frame">
    <inertial>
      <mass value="1e-5"/>
      <!-- collocate with parent link and remove mass from it -->
      <origin rpy="0 0 0" xyz="0.042428 0.0004084 0.0108165"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
    </inertial>
  </link>
  <gazebo reference="head_hokuyo_frame">
    <sensor name="head_hokuyo_sensor" type="gpu_ray">
      <pose>0 0 0 0 0 0</pose>
      <visualize>false</visualize>
      <update_rate>40</update_rate>
      <ray>
        <scan>
          <horizontal>
            <samples>1081</samples>
            <resolution>1</resolution>
            <min_angle>-2.356194</min_angle>
            <max_angle>2.356194</max_angle>
          </horizontal>
        </scan>
        <range>
          <min>0.10</min>
          <max>30.0</max>
          <resolution>0.01</resolution>
        </range>
        <noise>
          <type>gaussian</type>
          <!-- Noise parameters based on published spec for Hokuyo laser
               achieving "+-30mm" accuracy at range < 10m.  A mean of 0.0m and
               stddev of 0.01m will put 99.7% of samples within 0.03m of the true
               reading. -->
          <mean>0.0</mean>
          <stddev>0.01</stddev>
        </noise>
      </ray>
      <plugin filename="libgazebo_ros_gpu_laser.so" name="gazebo_ros_head_hokuyo_controller">
        <topicName>/multisense/lidar_scan</topicName>
        <frameName>head_hokuyo_frame</frameName>
      </plugin>
    </sensor>
  </gazebo>
  <joint name="left_camera_frame_joint" type="fixed">
    <!-- optical frame collocated with tilting DOF -->
    <origin xyz="0.0 0.035 -0.002"/>
    <parent link="head"/>
    <child link="left_camera_frame"/>
  </joint>
  <link name="left_camera_frame">
    <inertial>
      <mass value="1e-5"/>
      <!-- collocate with parent link and remove mass from it -->
      <origin xyz="-0.075493 0.035033383 0.02574"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
    </inertial>
  </link>
  <joint name="left_camera_optical_frame_joint" type="fixed">
    <origin rpy="-1.5708 0.0 -1.5708" xyz="0 0 0"/>
    <parent link="left_camera_frame"/>
    <child link="left_camera_optical_frame"/>
  </joint>
  <link name="left_camera_optical_frame"/>
  <gazebo reference="left_camera_frame">
    <sensor name="stereo_camera" type="multicamera">
      <!-- see MultiSenseSLPlugin.h for available modes -->
      <update_rate>10.0</update_rate>
      <camera name="left">
        <!-- Spec sheet says 80deg X 45deg @ 1024x544pix.  Based on feedback
             from teams, we're instead doing 80deg X 80deg @ 800x800pix. -->
        <horizontal_fov>1.3962634</horizontal_fov>
        <image>
          <width>1024</width>
          <height>544</height>
          <format>R8G8B8</format>
        </image>
        <clip>
          <near>0.02</near>
          <far>300</far>
        </clip>
        <noise>
          <type>gaussian</type>
          <!-- Noise is sampled independently per pixel on each frame.  
               That pixel's noise value is added to each of its color
               channels, which at that point lie in the range [0,1].
               The stddev value of 0.007 is based on experimental data 
               from a camera in a Sandia hand pointed at a static scene
               in a couple of different lighting conditions.  -->
          <mean>0.0</mean>
          <stddev>0.007</stddev>
        </noise>
      </camera>
      <camera name="right">
        <pose>0 -0.07 0 0 0 0</pose>
        <!-- Spec sheet says 80deg X 45deg @ 1024x544pix. -->
        <horizontal_fov>1.3962634</horizontal_fov>
        <image>
          <width>1024</width>
          <height>544</height>
          <format>R8G8B8</format>
        </image>
        <clip>
          <near>0.02</near>
          <far>300</far>
        </clip>
        <noise>
          <type>gaussian</type>
          <!-- Noise is sampled independently per pixel on each frame.  
               That pixel's noise value is added to each of its color
               channels, which at that point lie in the range [0,1].
               The stddev value of 0.007 is based on experimental data 
               from a camera in a Sandia hand pointed at a static scene
               in a couple of different lighting conditions.  -->
          <mean>0.0</mean>
          <stddev>0.007</stddev>
        </noise>
      </camera>
      <plugin filename="libgazebo_ros_multicamera.so" name="stereo_camera_controller">
        <alwaysOn>true</alwaysOn>
        <updateRate>0.0</updateRate>
        <cameraName>multisense/camera</cameraName>
        <imageTopicName>image_raw</imageTopicName>
        <cameraInfoTopicName>camera_info</cameraInfoTopicName>
        <frameName>left_camera_optical_frame</frameName>
        <!--<rightFrameName>right_camera_optical_frame</rightFrameName>-->
        <hackBaseline>0.07</hackBaseline>
        <distortionK1>0.0</distortionK1>
        <distortionK2>0.0</distortionK2>
        <distortionK3>0.0</distortionK3>
        <distortionT1>0.0</distortionT1>
        <distortionT2>0.0</distortionT2>
      </plugin>
    </sensor>
  </gazebo>
  <joint name="right_camera_frame_joint" type="fixed">
    <origin xyz="0.0 -0.035 -0.002"/>
    <parent link="head"/>
    <child link="right_camera_frame"/>
  </joint>
  <link name="right_camera_frame">
    <inertial>
      <mass value="1e-5"/>
      <!-- collocate with parent link and remove mass from it -->
      <origin xyz="-0.075493 -0.034966617 0.02574"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
    </inertial>
  </link>
  <joint name="right_camera_optical_frame_joint" type="fixed">
    <origin rpy="-1.5708 0.0 -1.5708" xyz="0 0 0"/>
    <parent link="right_camera_frame"/>
    <child link="right_camera_optical_frame"/>
  </joint>
  <link name="right_camera_optical_frame"/>
  <joint name="center_top_led_frame_joint" type="fixed">
    <origin xyz="0.01125 0.0 0.0105"/>
    <parent link="head"/>
    <child link="center_top_led_frame"/>
  </joint>
  <link name="center_top_led_frame">
    <inertial>
      <mass value="1e-5"/>
      <!-- collocate with parent link and remove mass from it -->
      <origin rpy="0 0 0" xyz="-0.064243 0.000033383 0.03824"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
    </inertial>
  </link>
  <joint name="center_bottom_led_frame_joint" type="fixed">
    <origin xyz="0.01125 0.0 -0.0155"/>
    <parent link="head"/>
    <child link="center_bottom_led_frame"/>
  </joint>
  <link name="center_bottom_led_frame">
    <inertial>
      <mass value="1e-5"/>
      <!-- collocate with parent link and remove mass from it -->
      <origin rpy="0 0 0" xyz="-0.064243 0.000033383 0.01224"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
    </inertial>
  </link>
  <joint name="left_led_frame_joint" type="fixed">
    <origin rpy="0 -0.15 0.53" xyz="-0.01443 0.07452 0.050346"/>
    <parent link="head"/>
    <child link="left_led_frame"/>
  </joint>
  <link name="left_led_frame">
    <inertial>
      <mass value="1e-5"/>
      <!-- collocate with parent link and remove mass from it -->
      <origin xyz="-0.089923 0.074553383 0.078086"/>
Guilhem Saurel's avatar
Guilhem Saurel committed
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
    </inertial>
  </link>
  <joint name="right_led_frame_joint" type="fixed">
    <origin rpy="0 -0.15 -0.53" xyz="-0.01443 -0.07452 0.050346"/>
    <parent link="head"/>
    <child link="right_led_frame"/>
  </joint>
  <link name="right_led_frame">
    <inertial>
      <mass value="1e-5"/>
      <!-- collocate with parent link and remove mass from it -->
      <origin xyz="-0.089923 -0.074486617 0.07908"/>
Guilhem Saurel's avatar
Guilhem Saurel committed
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
    </inertial>
  </link>
  <gazebo>
    <plugin filename="libMultiSenseSLPlugin.so" name="multisense_plugin"/>
  </gazebo>
  <link name="head_imu_link">
    <inertial>
      <mass value="1e-5"/>
      <!-- collocate with parent link and remove mass from it -->
      <origin rpy="0 0 0" xyz="-0.122993 0.035033383 0.02774"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
    </visual>
  </link>
  <joint name="head_imu_joint" type="fixed">
    <parent link="head"/>
    <child link="head_imu_link"/>
    <!-- putting it at the same z-level as the stereo -->
    <origin rpy="0 0 0" xyz="-0.0475 0.035 0.0"/>
  </joint>
  <gazebo reference="head_imu_link">
    <!-- this is expected to be reparented to head with appropriate offset
         when head_imu_link is reduced by fixed joint reduction -->
    <!-- todo: this is working with gazebo 1.4, need to write a unit test -->
    <sensor name="head_imu_sensor" type="imu">
      <always_on>1</always_on>
      <update_rate>1000.0</update_rate>
      <imu>
        <noise>
          <type>gaussian</type>
          <!-- Noise parameters from Boston Dynamics
               (http://gazebosim.org/wiki/Sensor_noise):
                 rates (rad/s): mean=0, stddev=2e-4
                 accels (m/s/s): mean=0, stddev=1.7e-2
                 rate bias (rad/s): 5e-6 - 1e-5
                 accel bias (m/s/s): 1e-1
               Experimentally, simulation provide rates with noise of
               about 1e-3 rad/s and accels with noise of about 1e-1 m/s/s.
               So we don't expect to see the noise unless number of inner iterations
               are increased.

               We will add bias.  In this model, bias is sampled once for rates
               and once for accels at startup; the sign (negative or positive)
               of each bias is then switched with equal probability.  Thereafter,
               the biases are fixed additive offsets.  We choose
               bias means and stddevs to produce biases close to the provided
               data. -->
          <rate>
            <mean>0.0</mean>
            <stddev>2e-4</stddev>
            <bias_mean>0.0000075</bias_mean>
            <bias_stddev>0.0000008</bias_stddev>
          </rate>
          <accel>
            <mean>0.0</mean>
            <stddev>1.7e-2</stddev>
            <bias_mean>0.1</bias_mean>
            <bias_stddev>0.001</bias_stddev>
          </accel>
        </noise>
      </imu>
    </sensor>
  </gazebo>
</robot>