-
Notifications
You must be signed in to change notification settings - Fork 773
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Adding depth camera world to use in test to make depth camera have ri…
…ght timestamp #408- appears to be working (though only looking at horizon) but getting these sdf errors: Error [SDF.cc:789] Missing element description for [pointCloudTopicName] Error [SDF.cc:789] Missing element description for [depthImageCameraInfoTopicName] Error [SDF.cc:789] Missing element description for [pointCloudCutoff]
- Loading branch information
Showing
1 changed file
with
136 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,136 @@ | ||
<?xml version="1.0" ?> | ||
<sdf version="1.4"> | ||
|
||
<world name="default"> | ||
<include> | ||
<uri>model://ground_plane</uri> | ||
</include> | ||
|
||
<!-- Global light source --> | ||
<include> | ||
<uri>model://sun</uri> | ||
</include> | ||
|
||
<!-- Focus camera on tall pendulum --> | ||
<gui fullscreen='0'> | ||
<camera name='user_camera'> | ||
<pose>4.927360 -4.376610 3.740080 0.000000 0.275643 2.356190</pose> | ||
<view_controller>orbit</view_controller> | ||
</camera> | ||
</gui> | ||
|
||
<model name="model_1"> | ||
<static>false</static> | ||
<pose>0.0 2.0 2.0 0.0 0.0 0.0</pose> | ||
<link name="link_1"> | ||
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose> | ||
<inertial> | ||
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose> | ||
<inertia> | ||
<ixx>1.0</ixx> | ||
<ixy>0.0</ixy> | ||
<ixz>0.0</ixz> | ||
<iyy>1.0</iyy> | ||
<iyz>0.0</iyz> | ||
<izz>1.0</izz> | ||
</inertia> | ||
<mass>10.0</mass> | ||
</inertial> | ||
<visual name="visual_sphere"> | ||
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose> | ||
<geometry> | ||
<sphere> | ||
<radius>0.5</radius> | ||
</sphere> | ||
</geometry> | ||
<material> | ||
<ambient>0.03 0.5 0.5 1.0</ambient> | ||
<script>Gazebo/Green</script> | ||
</material> | ||
<cast_shadows>true</cast_shadows> | ||
<laser_retro>100.0</laser_retro> | ||
</visual> | ||
<collision name="collision_sphere"> | ||
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose> | ||
<max_contacts>250</max_contacts> | ||
<geometry> | ||
<sphere> | ||
<radius>0.5</radius> | ||
</sphere> | ||
</geometry> | ||
<surface> | ||
<friction> | ||
<ode> | ||
<mu>0.5</mu> | ||
<mu2>0.2</mu2> | ||
<fdir1>1.0 0 0</fdir1> | ||
<slip1>0</slip1> | ||
<slip2>0</slip2> | ||
</ode> | ||
</friction> | ||
<bounce> | ||
<restitution_coefficient>0</restitution_coefficient> | ||
<threshold>1000000.0</threshold> | ||
</bounce> | ||
<contact> | ||
<ode> | ||
<soft_cfm>0</soft_cfm> | ||
<soft_erp>0.2</soft_erp> | ||
<kp>1e15</kp> | ||
<kd>1e13</kd> | ||
<max_vel>100.0</max_vel> | ||
<min_depth>0.0001</min_depth> | ||
</ode> | ||
</contact> | ||
</surface> | ||
<laser_retro>100.0</laser_retro> | ||
</collision> | ||
|
||
<sensor name="depth_camera" type="depth"> | ||
<update_rate>0.5</update_rate> | ||
<camera name="head"> | ||
<!-- TODO(lucasw) is noise used? | ||
<noise> | ||
<type>gaussian</type> | ||
<mean>0.0</mean> | ||
<stddev>0.007</stddev> | ||
</noise> | ||
--> | ||
<horizontal_fov>1.3962634</horizontal_fov> | ||
<image> | ||
<width>640</width> | ||
<height>480</height> | ||
<format>R8G8B8</format> | ||
</image> | ||
<clip> | ||
<near>0.02</near> | ||
<far>300</far> | ||
</clip> | ||
</camera> | ||
<plugin name="camera_controller" filename="libgazebo_ros_depth_camera.so"> | ||
<alwaysOn>true</alwaysOn> | ||
<!-- Keep this zero, update_rate will control the frame rate --> | ||
<updateRate>0.0</updateRate> | ||
<imageTopicName>image_raw</imageTopicName> | ||
<depthImageTopicName>depth/image_raw</depthImageTopicName> | ||
<depthImageTopicCameraInfoName>depth/camera_info</depthImageCameraInfoTopicName> | ||
<pointCloudTopicName>points</pointCloudTopicName> | ||
<cameraInfoTopicName>camera_info</cameraInfoTopicName> | ||
<cameraName>depth_cam</cameraName> | ||
<frameName>camera_link</frameName> | ||
<!-- TODO(lucasw) is this used by depth camera at all? --> | ||
<hackBaseline>0.07</hackBaseline> | ||
<pointCloudCutoff>0.001</pointCloudCutoff> | ||
<distortionK1>0.0</distortionK1> | ||
<distortionK2>0.0</distortionK2> | ||
<distortionK3>0.0</distortionK3> | ||
<distortionT1>0.0</distortionT1> | ||
<distortionT2>0.0</distortionT2> | ||
</plugin> | ||
<always_on>true</always_on> | ||
</sensor> | ||
</link> | ||
</model> | ||
|
||
</world> | ||
</sdf> |