Skip to content

Commit

Permalink
Merge pull request #9 from Field-Robotics-Lab/new_models3
Browse files Browse the repository at this point in the history
move target further than 2 meters, align collision element, improve mesh
  • Loading branch information
BruceMty authored Jun 9, 2020
2 parents 194fe0e + 181104e commit 7c8091d
Show file tree
Hide file tree
Showing 10 changed files with 152 additions and 167 deletions.
13 changes: 7 additions & 6 deletions models/blueview_m450/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,27 +3,28 @@
<model name="blueview_m450">
<link name="forward_sonar_link">
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>1</mass>
<pose>0 0 0 0 0 -1.570796</pose>
<mass>4.78</mass>
<!-- Mark only - based on cylinder -->
<inertia>
<ixx>0.1</ixx>
<ixx>0.0191</ixx> <!-- as 2/5mr^2 -->
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyy>0.0191</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
<izz>0.0191</izz>
</inertia>
</inertial>
<collision name="collision">
<pose>-0.08 0 0 0 1.571 0</pose>
<pose>0 0 0 0 0 -1.570796</pose>
<geometry>
<mesh>
<uri>model://blueview_m450/meshes/COLLISION-BlueView-M450.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<pose>0 0 0 0 0 -1.570796</pose>
<geometry>
<mesh>
<uri>model://blueview_m450/meshes/BlueView-M450.dae</uri>
Expand Down
70 changes: 70 additions & 0 deletions models/blueview_p900/meshes/COLLISION-p900.dae

Large diffs are not rendered by default.

196 changes: 56 additions & 140 deletions models/blueview_p900/meshes/p900.dae

Large diffs are not rendered by default.

Binary file removed models/blueview_p900/meshes/p900.stl
Binary file not shown.
Binary file added models/blueview_p900/meshes/tx-p900.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
10 changes: 4 additions & 6 deletions models/blueview_p900/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,10 @@
</inertia>
</inertial>
<collision name="collision">
<pose>-0.08 0 0 0 1.571 0</pose>
<geometry>
<cylinder>
<radius>0.0635</radius>
<length>0.315</length>
</cylinder>
<mesh>
<uri>model://blueview_p900/meshes/COLLISION-p900.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
Expand All @@ -46,7 +44,7 @@
<format>R8G8B8</format>
</image>
<clip>
<near>02</near>
<near>02</near> <!-- optimal 2m-60m -->
<far>60</far>
</clip>
<depth_camera>
Expand Down
22 changes: 11 additions & 11 deletions models/seabat_f50/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,27 +3,27 @@
<model name="SeaBat-F50 FLS">
<link name="forward_sonar_link">
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>11.7</mass>
<pose>0 0 0 0 0 1.570796</pose>
<mass>8.2</mass>
<inertia>
<ixx>0.0306</ixx> <!-- 11.7*.56^2/12 if receiver mounted at end -->
<ixx>0.151702733</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0</iyy>
<iyy>0.012730835</iyy>
<iyz>0</iyz>
<izz>0.0306</izz>
<izz>0.150214768</izz>
</inertia>
</inertial>
<collision name="collision">
<pose>-0.08 0 0 0 1.571 0</pose>
<pose>0 0 0 0 0 1.570796</pose>
<geometry>
<cylinder>
<radius>0.051</radius>
<length>0.56</length>
</cylinder>
<box>
<size>0.46 0.0907 0.102</size>
</box>
</geometry>
</collision>
<visual name="visual">
<pose>0 0 0 0 1.570796 0</pose>
<geometry>
<mesh>
<uri>model://seabat_f50/meshes/SeaBat-F50.dae</uri>
Expand All @@ -45,7 +45,7 @@
<format>R8G8B8</format>
</image>
<clip>
<near>01</near> <!-- not defined -->
<near>2</near> <!-- not defined -->
<far>600</far>
</clip>
<depth_camera>
Expand Down
2 changes: 1 addition & 1 deletion worlds/sonar_tank_blueview_m450.world
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
<!-- cylinder target -->
<include>
<uri>model://cylinder_target</uri>
<pose>2.1 3.0 1.0 0 0 0</pose>
<pose>2.1 5.0 1.0 0 0 0</pose>
<static>true</static>
</include>

Expand Down
2 changes: 1 addition & 1 deletion worlds/sonar_tank_blueview_p900.world
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
<!-- cylinder target -->
<include>
<uri>model://cylinder_target</uri>
<pose>2.1 3.0 1.0 0 0 0</pose>
<pose>2.1 5.0 1.0 0 0 0</pose>
<static>true</static>
</include>

Expand Down
4 changes: 2 additions & 2 deletions worlds/sonar_tank_seabat_f50.world
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,14 @@
<!-- cylinder target -->
<include>
<uri>model://cylinder_target</uri>
<pose>2.1 3.0 1.0 0 0 0</pose>
<pose>2.1 5.0 1.0 0 0 0</pose>
<static>true</static>
</include>

<!-- SeaBat F50 -->
<include>
<uri>model://seabat_f50</uri>
<name>blueview_p900</name>
<name>seabat_f50</name>
<pose>2.1 1.0 1.0 0 0 1.5709</pose>
<static>true</static>
</include>
Expand Down

0 comments on commit 7c8091d

Please sign in to comment.