Skip to content

Commit

Permalink
regenerating pepper.urdf based on last changes
Browse files Browse the repository at this point in the history
  • Loading branch information
Natalia Lyubova committed Mar 3, 2017
1 parent 11e37bf commit d42886e
Showing 1 changed file with 41 additions and 5 deletions.
46 changes: 41 additions & 5 deletions pepper_description/urdf/pepper1.0_generated_urdf/pepper.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -2118,6 +2118,41 @@
</plugin>
</sensor>
</gazebo>
<gazebo reference="CameraDepth_frame">
<sensor name="CameraDepth_frame_sensor" type="depth">
<always_on>true</always_on>
<update_rate>20.0</update_rate>
<camera>
<horizontal_fov>1.01229096616</horizontal_fov>
<image>
<format>B8G8R8</format>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.4</near>
<far>8.0</far>
</clip>
</camera>
<plugin filename="libgazebo_ros_openni_kinect.so" name="CameraDepth_frame_controller">
<alwaysOn>true</alwaysOn>
<updateRate>20.0</updateRate>
<cameraName>pepper_robot/camera</cameraName>
<imageTopicName>ir/image_raw</imageTopicName>
<cameraInfoTopicName>depth/camera_info</cameraInfoTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<frameName>CameraDepth_optical_frame</frameName>
<pointCloudCutoff>0.4</pointCloudCutoff>
<pointCloudCutoffMax>8.0</pointCloudCutoffMax>
<!-- <distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2> -->
</plugin>
</sensor>
</gazebo>
<!--
BUMPERS
Expand All @@ -2137,7 +2172,7 @@
<collision>BumperB_frame_collision</collision>
</contact>
<plugin filename="libgazebo_ros_bumper.so" name="gazebo_pepper_BumperB">
<robotNamespace>pepper_robot</robotNamespace>
<robotNamespace>/pepper_robot</robotNamespace>
<alwaysOn>true</alwaysOn>
<bumperTopicName>Bumper/Back</bumperTopicName>
<frameName>BumperB_frame</frameName>
Expand All @@ -2161,7 +2196,7 @@
<collision>BumperFL_frame_collision</collision>
</contact>
<plugin filename="libgazebo_ros_bumper.so" name="gazebo_pepper_BumperFL">
<robotNamespace>pepper_robot</robotNamespace>
<robotNamespace>/pepper_robot</robotNamespace>
<alwaysOn>true</alwaysOn>
<bumperTopicName>Bumper/FrontLeft</bumperTopicName>
<frameName>BumperFL_frame</frameName>
Expand All @@ -2185,7 +2220,7 @@
<collision>BumperFR_frame_collision</collision>
</contact>
<plugin filename="libgazebo_ros_bumper.so" name="gazebo_pepper_BumperFR">
<robotNamespace>pepper_robot</robotNamespace>
<robotNamespace>/pepper_robot</robotNamespace>
<alwaysOn>true</alwaysOn>
<bumperTopicName>Bumper/FrontRight</bumperTopicName>
<frameName>BumperFR_frame</frameName>
Expand Down Expand Up @@ -2224,7 +2259,7 @@
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
<robotNamespace>pepper_robot</robotNamespace>
<robotNamespace>/pepper_robot</robotNamespace>
<gaussianNoise>0.05</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>20</updateRate>
Expand Down Expand Up @@ -2265,7 +2300,7 @@
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
<robotNamespace>pepper_robot</robotNamespace>
<robotNamespace>/pepper_robot</robotNamespace>
<gaussianNoise>0.05</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>20</updateRate>
Expand All @@ -2279,6 +2314,7 @@
</sensor>
</gazebo>
-->
<!-- Drive controller -->
<gazebo>
<plugin filename="libgazebo_ros_diff_drive.so" name="differential_drive_controller">
<alwaysOn>true</alwaysOn>
Expand Down

0 comments on commit d42886e

Please sign in to comment.