- 
                Notifications
    You must be signed in to change notification settings 
- Fork 1
Subsea structure #13
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: main
Are you sure you want to change the base?
Subsea structure #13
Changes from all commits
9a2fb3f
              89d5186
              9b27964
              8ff3c3c
              File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change | 
|---|---|---|
| @@ -0,0 +1 @@ | ||
| .vscode/ | 
| Original file line number | Diff line number | Diff line change | 
|---|---|---|
| @@ -0,0 +1,7 @@ | ||
| drone_position: "2.25 -16.5 6.5" | ||
| drone_orientation: "-1.57 0.0 0.0" | ||
| water_jerlow: "0.20" | ||
| seafloor_position: "0.0 0.0 3.0" | ||
| seafloor_orientation: "1.57 0.0 0.0" | ||
| structure_position: "1.0 -18.0 8.1" | ||
| structure_orientation: "-1.57 0.0 -1.57" | ||
| Original file line number | Diff line number | Diff line change | ||||||||||||||||
|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
| @@ -1,8 +1,5 @@ | ||||||||||||||||||
| <?xml version="1.0"?> | ||||||||||||||||||
| <scenario> | ||||||||||||||||||
| <!-- =========================================== | ||||||||||||||||||
| Static structure (stable concave collisions) | ||||||||||||||||||
| =========================================== --> | ||||||||||||||||||
| <static name="structure_with_valves_base" type="model"> | ||||||||||||||||||
| <physical> | ||||||||||||||||||
| <mesh filename="object_files/structure_mesh.obj" scale="1.0"/> | ||||||||||||||||||
|  | @@ -14,14 +11,19 @@ | |||||||||||||||||
| </visual> | ||||||||||||||||||
| <material name="Neutral"/> | ||||||||||||||||||
| <look name="Yellow"/> | ||||||||||||||||||
| <world_transform xyz="1.0 -18.0 8.1" rpy="-1.57 0.0 -1.57"/> | ||||||||||||||||||
| <world_transform | ||||||||||||||||||
| xyz="$(param structure_position)" | ||||||||||||||||||
| rpy="$(param structure_orientation)"/> | ||||||||||||||||||
| </static> | ||||||||||||||||||
|  | ||||||||||||||||||
| <!-- ========================= | ||||||||||||||||||
| Valve 1 as its own robot | ||||||||||||||||||
| ========================= --> | ||||||||||||||||||
| <robot name="valve1" fixed="true" self_collisions="false"> | ||||||||||||||||||
| <base_link name="valve1_base" type="model" physics="submerged"> | ||||||||||||||||||
| <base_link name="valve1_frame" type="box" physics="submerged"> | ||||||||||||||||||
| <dimensions xyz="0.001 0.001 0.001"/> | ||||||||||||||||||
| <origin xyz="0 0 0" rpy="0 0 0"/> | ||||||||||||||||||
| <material name="Neutral"/><look name="Orange"/> | ||||||||||||||||||
| </base_link> | ||||||||||||||||||
|  | ||||||||||||||||||
| <link name="valve1_base" type="model" physics="submerged"> | ||||||||||||||||||
| <physical> | ||||||||||||||||||
| <mesh filename="object_files/valve_base_mesh.obj" scale="1.0"/> | ||||||||||||||||||
| <origin rpy="-1.57 0 1.57" xyz="0 0 0"/> | ||||||||||||||||||
|  | @@ -30,9 +32,16 @@ | |||||||||||||||||
| <mesh filename="object_files/valve_base.obj" scale="1.0"/> | ||||||||||||||||||
| <origin rpy="-1.57 0 1.57" xyz="0 0 0"/> | ||||||||||||||||||
| </visual> | ||||||||||||||||||
| <material name="Steel"/> | ||||||||||||||||||
| <look name="Yellow"/> | ||||||||||||||||||
| </base_link> | ||||||||||||||||||
| <material name="Steel"/><look name="Orange"/> | ||||||||||||||||||
| </link> | ||||||||||||||||||
|  | ||||||||||||||||||
| <joint name="valve1_mount" type="fixed"> | ||||||||||||||||||
| <parent name="valve1_frame"/> | ||||||||||||||||||
| <child name="valve1_base"/> | ||||||||||||||||||
| <origin | ||||||||||||||||||
| xyz="1.196441 1.42144 1.807916" | ||||||||||||||||||
| rpy="0.0 0.0 1.57"/> | ||||||||||||||||||
| 
      Comment on lines
    
      +42
     to 
      +43
    
   There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. These are still magic numbers, which could be moved to config file if that is wanted. Maybe in a future pull requests all such relationships (like the thruster positions in orca.scn) could be moved to yaml files too. That is issue material | ||||||||||||||||||
| </joint> | ||||||||||||||||||
|  | ||||||||||||||||||
| <link name="valve1_turnable" type="model" physics="submerged"> | ||||||||||||||||||
| <physical> | ||||||||||||||||||
|  | @@ -43,8 +52,7 @@ | |||||||||||||||||
| <mesh filename="object_files/valve_turnable.obj" scale="1.0"/> | ||||||||||||||||||
| <origin rpy="-1.57 0 1.57" xyz="0 0 0.1"/> | ||||||||||||||||||
| </visual> | ||||||||||||||||||
| <material name="Steel"/> | ||||||||||||||||||
| <look name="Yellow"/> | ||||||||||||||||||
| <material name="Steel"/><look name="Orange"/> | ||||||||||||||||||
| </link> | ||||||||||||||||||
|  | ||||||||||||||||||
| <joint name="valve1_joint" type="revolute"> | ||||||||||||||||||
|  | @@ -53,20 +61,21 @@ | |||||||||||||||||
| <axis xyz="0 1 0"/> | ||||||||||||||||||
| <limits min="0.0" max="1.57"/> | ||||||||||||||||||
| <origin xyz="0 0 0" rpy="0 0 0"/> | ||||||||||||||||||
| <!-- <damping value="2.0"/> --> | ||||||||||||||||||
| </joint> | ||||||||||||||||||
|  | ||||||||||||||||||
| <!-- Composed world pose for valve 1 --> | ||||||||||||||||||
| <world_transform | ||||||||||||||||||
| xyz="2.80999954 -19.19500003 6.68000014" | ||||||||||||||||||
| rpy="0.0 0.0 1.57079632"/> | ||||||||||||||||||
| xyz="$(param structure_position)" | ||||||||||||||||||
| rpy="$(param structure_orientation)"/> | ||||||||||||||||||
| </robot> | ||||||||||||||||||
|  | ||||||||||||||||||
| <!-- ========================= | ||||||||||||||||||
| Valve 2 as its own robot | ||||||||||||||||||
| ========================= --> | ||||||||||||||||||
| <robot name="valve2" fixed="true" self_collisions="false"> | ||||||||||||||||||
| <base_link name="valve2_base" type="model" physics="submerged"> | ||||||||||||||||||
| <base_link name="valve2_frame" type="box" physics="submerged"> | ||||||||||||||||||
| <dimensions xyz="0.001 0.001 0.001"/> | ||||||||||||||||||
| <origin xyz="0 0 0" rpy="0 0 0"/> | ||||||||||||||||||
| <material name="Neutral"/><look name="Orange"/> | ||||||||||||||||||
| </base_link> | ||||||||||||||||||
|  | ||||||||||||||||||
| <link name="valve2_base" type="model" physics="submerged"> | ||||||||||||||||||
| <physical> | ||||||||||||||||||
| <mesh filename="object_files/valve_base_mesh.obj" scale="1.0"/> | ||||||||||||||||||
| <origin rpy="-1.57 0 1.57" xyz="0 0 0"/> | ||||||||||||||||||
|  | @@ -75,9 +84,16 @@ | |||||||||||||||||
| <mesh filename="object_files/valve_base.obj" scale="1.0"/> | ||||||||||||||||||
| <origin rpy="-1.57 0 1.57" xyz="0 0 0"/> | ||||||||||||||||||
| </visual> | ||||||||||||||||||
| <material name="Steel"/> | ||||||||||||||||||
| <look name="Yellow"/> | ||||||||||||||||||
| </base_link> | ||||||||||||||||||
| <material name="Steel"/><look name="Orange"/> | ||||||||||||||||||
| </link> | ||||||||||||||||||
|  | ||||||||||||||||||
| <joint name="valve2_mount" type="fixed"> | ||||||||||||||||||
| <parent name="valve2_frame"/> | ||||||||||||||||||
| <child name="valve2_base"/> | ||||||||||||||||||
| <origin | ||||||||||||||||||
| xyz="0.665 0.95140878 1.76872493" | ||||||||||||||||||
| rpy="0.0 0.0 0.0"/> | ||||||||||||||||||
| </joint> | ||||||||||||||||||
|  | ||||||||||||||||||
| <link name="valve2_turnable" type="model" physics="submerged"> | ||||||||||||||||||
| <physical> | ||||||||||||||||||
|  | @@ -88,8 +104,7 @@ | |||||||||||||||||
| <mesh filename="object_files/valve_turnable.obj" scale="1.0"/> | ||||||||||||||||||
| <origin rpy="-1.57 0 1.57" xyz="0 0 0.1"/> | ||||||||||||||||||
| </visual> | ||||||||||||||||||
| <material name="Steel"/> | ||||||||||||||||||
| <look name="Yellow"/> | ||||||||||||||||||
| <material name="Steel"/><look name="Orange"/> | ||||||||||||||||||
| </link> | ||||||||||||||||||
|  | ||||||||||||||||||
| <joint name="valve2_joint" type="revolute"> | ||||||||||||||||||
|  | @@ -98,12 +113,49 @@ | |||||||||||||||||
| <axis xyz="0 1 0"/> | ||||||||||||||||||
| <limits min="0.0" max="1.57"/> | ||||||||||||||||||
| <origin xyz="0 0 0" rpy="0 0 0"/> | ||||||||||||||||||
| <!-- <damping value="2.0"/> --> | ||||||||||||||||||
| </joint> | ||||||||||||||||||
|  | ||||||||||||||||||
| <!-- Composed world pose for valve 2 --> | ||||||||||||||||||
| <world_transform | ||||||||||||||||||
| xyz="2.77000017 -18.64999971 7.15" | ||||||||||||||||||
| rpy="0 1.57079632 1.57079632"/> | ||||||||||||||||||
| xyz="$(param structure_position)" | ||||||||||||||||||
| rpy="$(param structure_orientation)"/> | ||||||||||||||||||
| </robot> | ||||||||||||||||||
|  | ||||||||||||||||||
| <robot name="structure_markers" fixed="true" self_collisions="false"> | ||||||||||||||||||
| <base_link name="markers_frame" type="box" physics="submerged"> | ||||||||||||||||||
| <dimensions xyz="0.001 0.001 0.001"/> | ||||||||||||||||||
| <origin xyz="0 0 0" rpy="0 0 0"/> | ||||||||||||||||||
| <material name="Neutral"/> | ||||||||||||||||||
| <look name="Invisible"/> | ||||||||||||||||||
| 
      Comment on lines
    
      +127
     to 
      +128
    
   
     | ||||||||||||||||||
| <material name="Neutral"/> | |
| <look name="Invisible"/> | |
| <material name="Neutral"/> | |
| <look name="Invisible"/> | 
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I think you are wrong here buddy.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
| <material name="Neutral"/> | |
| <look name="Invisible"/> | |
| <material name="Neutral"/> | |
| <look name="Invisible"/> | 
my bad, didnt think it would mess up the indentation. I think this should be correct.
| Original file line number | Diff line number | Diff line change | ||||
|---|---|---|---|---|---|---|
|  | @@ -3,8 +3,8 @@ | |||||
| <environment> | ||||||
| <ned latitude="63.446827" longitude="10.421906"/> | ||||||
| <ocean> | ||||||
| <water density="1031.0" jerlov="0.60"/> | ||||||
| <waves height="0.0"/> | ||||||
| <water density="1031.0" jerlov="$(param water_jerlow)"/> | ||||||
| 
     | ||||||
| <water density="1031.0" jerlov="$(param water_jerlow)"/> | |
| <water density="1031.0" jerlov="$(param water_jerlov)"/> | 
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Make waves height param too?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Should be a separate issue, just copied the setup in the tacc.scn
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Set the height to 0 then probably, don't think tsunamies are common in Stavanger 😂
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Could be nice to add a comment behind every field here to indicate what it represents? For example