Changed sonar w/ opt_flow

This commit is contained in:
cesar 2022-04-26 12:20:47 -03:00
parent 67aec40dea
commit d9716d0905
1 changed files with 33 additions and 53 deletions

View File

@ -408,58 +408,10 @@
<child>gps0_link</child>
</joint>
</model>
<!--model name="sonar">
<link name="sonar_link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.000000000000001</mass>
<inertia>
<ixx>2.08333333e-7</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.08333333e-7</iyy>
<iyz>0</iyz>
<izz>4.16666667e-8</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<box>
<size>0.005 0.015 0.005</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Black</name>
</script>
</material>
</visual>
<sensor name="sonar" type="sonar">
<pose>0 0 0 0 0 0</pose>
<sonar>
<min>0.02</min>
<max>10.0</max>
<radius>1.33974388395</radius>
</sonar>
<plugin name="SonarPlugin" filename="libgazebo_sonar_plugin.so">
<robotNamespace></robotNamespace>
<topic>/height_cesar</topic>
</plugin>
<always_on>1</always_on>
<update_rate>20</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
<joint name='sonar_joint' type='fixed'>
<parent>base</parent>
<child>sonar_link</child>
</joint-->
<!--sonar-->
<!--sonar>
<link name="sonar_link">
<pose frame=''>0 0 0 0 1.57 0</pose>
<inertial> <!-- causes issues when omitted -->
<inertial> <! causes issues when omitted >
<mass>0.05</mass>
<inertia>
<ixx>2.08333333333e-07</ixx>
@ -495,8 +447,8 @@
</horizontal>
</scan>
<range>
<min>0.06</min> <!-- do not lower past 0.06 -->
<max>35</max> <!-- do not increase past 35 -->
<min>0.06</min> <! do not lower past 0.06 >
<max>35</max> <! do not increase past 35 >
<resolution>0.01</resolution>
</range>
<noise>
@ -519,7 +471,35 @@
<joint name="sonar_joint" type="fixed">
<parent>base</parent>
<child>sonar_link</child>
</joint>
</joint-->
<!--px4flow camera-->
<include>
<uri>model://px4flow</uri>
<pose>0.05 0 -0.05 0 0 0</pose>
</include>
<joint name="px4flow_joint" type="revolute">
<parent>spiri::base</parent>
<child>px4flow::link</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>
<!--lidar-->
<include>
<uri>model://lidar</uri>
<pose>0 0 -0.05 0 0 0</pose>
</include>
<joint name="lidar_joint" type="fixed">
<parent>spiri::base</parent>
<child>lidar::link</child>
</joint>
<plugin name='rosbag' filename='libgazebo_multirotor_base_plugin.so'>
<robotNamespace/>
<linkName>base</linkName>