➕ add realsens for ignition sim
This commit is contained in:
parent
9ad9e6c031
commit
badaefd34e
1 changed files with 65 additions and 2 deletions
|
@ -21,7 +21,12 @@
|
|||
filename="ignition-gazebo-contact-system"
|
||||
name="ignition::gazebo::systems::Contact">
|
||||
</plugin>
|
||||
<gui>
|
||||
<plugin
|
||||
filename="ignition-gazebo-sensors-system"
|
||||
name="ignition::gazebo::systems::Sensors">
|
||||
<render_enfine>ogre2</render_enfine>
|
||||
</plugin>
|
||||
<!--gui>
|
||||
|
||||
<plugin filename="GzScene3D" name="3D View">
|
||||
<ignition-gui>
|
||||
|
@ -35,7 +40,7 @@
|
|||
<background_color>0.4 0.6 1.0</background_color>
|
||||
<camera_pose>8.3 7 7.8 0 0.5 -2.4</camera_pose>
|
||||
</plugin>
|
||||
</gui>
|
||||
</gui-->
|
||||
|
||||
<light type="directional" name="sun">
|
||||
<cast_shadows>true</cast_shadows>
|
||||
|
@ -78,8 +83,66 @@
|
|||
</link>
|
||||
</model>
|
||||
<include>
|
||||
<!--Нужно залить на сервер и поменять на ссылку -->
|
||||
<uri>roboasm_sgonov_world</uri>
|
||||
<pose>0 0 0.07 0 0 0</pose>
|
||||
</include>
|
||||
<include>
|
||||
<uri>realsense_camera</uri>
|
||||
<pose>1 0 1 0 0.97 3.14159</pose>
|
||||
<static>true</static>
|
||||
</include>
|
||||
|
||||
<!--model name="3d_camera">
|
||||
<static>true</static>
|
||||
<link name="kinect_sensor">
|
||||
<pose>1 0 1 0 1 3.14159</pose>
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.05</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.05 0.05 0.05</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</visual>
|
||||
<sensor name="camera" type="rgbd_camera">
|
||||
<topic>rgbd_camera</topic>
|
||||
<always_on>1</always_on>
|
||||
<update_rate>30</update_rate>
|
||||
<camera name="rgbd_sens">
|
||||
<image>
|
||||
<width>212</width>
|
||||
<heigth>120</heigth>
|
||||
</image>
|
||||
<horizontal_fov>1.567821</horizontal_fov>
|
||||
<vertical_fov>1.022238</vertical_fov>
|
||||
<clip>
|
||||
<near>0.01</near>
|
||||
<far>1000.0</far>
|
||||
</clip>
|
||||
<depth_camera>
|
||||
<clip>
|
||||
<near>0.01</near>
|
||||
<far>10.0</far>
|
||||
</clip>
|
||||
</depth_camera>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0</mean>
|
||||
<stddev>0</stddev>
|
||||
</noise>
|
||||
<visibility_mask>2</visibility_mask>
|
||||
</camera>
|
||||
|
||||
</sensor>
|
||||
</link>
|
||||
</model-->
|
||||
|
||||
</world>
|
||||
</sdf>
|
Loading…
Add table
Add a link
Reference in a new issue