-
Notifications
You must be signed in to change notification settings - Fork 770
/
gazebo_ros_camera_triggered_demo.world
154 lines (143 loc) · 4.24 KB
/
gazebo_ros_camera_triggered_demo.world
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
<?xml version="1.0" ?>
<!--
Gazebo ROS triggered camera plugin demo
Try for example:
1. Launch RViz and visualize Images from `/demo_triggered_cam/camera1/image_raw/raw`
Nothing should show at first, because the camera hasn't been triggered.
2. Trigger the camera as follows and see a new image show up on RViz.
ros2 topic pub /demo_triggered_cam/camera1/image_trigger std_msgs/Empty -1
-->
<sdf version="1.6">
<world name="default">
<include>
<uri>model://sun</uri>
</include>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
</friction>
<bounce>
<restitution_coefficient>1.0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<max_vel>10000</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>
<model name="ball">
<allow_auto_disable>false</allow_auto_disable>
<pose>-1 0 1 0 0 0</pose>
<static>false</static>
<link name="link">
<inertial>
<mass>0.026</mass>
<!-- inertia based on solid sphere 2/5 mr^2 -->
<inertia>
<ixx>1.664e-5</ixx>
<iyy>1.664e-5</iyy>
<izz>1.664e-5</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<sphere>
<radius>0.04</radius>
</sphere>
</geometry>
<surface>
<bounce>
<restitution_coefficient>1.0</restitution_coefficient>
<threshold>0</threshold>
</bounce>
<contact>
<ode>
<max_vel>10000</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<geometry>
<sphere>
<radius>0.04</radius>
</sphere>
</geometry>
</visual>
</link>
</model>
<model name="camera_model">
<pose>0 0 0.5 0 0 3.14</pose>
<static>true</static>
<link name="camera_link">
<sensor type="camera" name="camera1">
<update_rate>60</update_rate>
<visualize>true</visualize>
<camera name="head">
<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>
<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]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<ros>
<namespace>demo_triggered_cam</namespace>
</ros>
<triggered>true</triggered>
</plugin>
</sensor>
</link>
</model>
</world>
</sdf>