Skip to content
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

Auto generated model. #89

Merged
merged 57 commits into from
Jan 6, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
57 commits
Select commit Hold shift + click to select a range
c20e586
rigid body
arjo129 Nov 17, 2021
cd7990a
Setting center of mass
arjo129 Nov 17, 2021
14f8267
Add drop weights... Leads to oscillation
arjo129 Nov 17, 2021
0f271f2
shift COM of main body forward craft is now stable.
arjo129 Nov 17, 2021
53a4415
Added mass shifter craaazy oscillations are back
arjo129 Nov 17, 2021
d28890f
Add description generator script
arjo129 Nov 19, 2021
92098f7
Automate pipeline
arjo129 Nov 20, 2021
580ddff
we are generating a new sdf
arjo129 Nov 20, 2021
e4e1ec0
Add unit test framework
arjo129 Nov 22, 2021
e86f4b0
Add hydrostatics test
arjo129 Nov 22, 2021
12ae53c
remove model
arjo129 Nov 22, 2021
b4b5c85
make fast
arjo129 Nov 22, 2021
2205951
stop debug printouts
arjo129 Nov 22, 2021
db128bd
Add second test WIP
arjo129 Nov 22, 2021
dba0867
fix compile issue
arjo129 Nov 22, 2021
7748af7
fix CMake file
arjo129 Nov 23, 2021
4d89cdf
Add joint controllers
arjo129 Nov 23, 2021
ba797f3
Stable fins
arjo129 Nov 23, 2021
d102628
remove ignition for now its not needed
arjo129 Nov 23, 2021
e50e1ae
Stavle thruster
arjo129 Nov 23, 2021
1d48f06
update plugin list
arjo129 Nov 23, 2021
2eb5141
better constraints
arjo129 Nov 23, 2021
1c55157
Add Buoyancy Engine
arjo129 Nov 23, 2021
2f3cabf
Add buoyancy engine
arjo129 Nov 24, 2021
1110005
Merge branch 'main' into arjo/autogenerated_model
arjo129 Nov 24, 2021
da52052
Add newline at EOF
arjo129 Nov 24, 2021
dce74de
Undo changes in tethys_equipped.
arjo129 Nov 24, 2021
7eb51de
Update expectation
arjo129 Nov 26, 2021
e81af75
white space correction
arjo129 Nov 26, 2021
15310c3
Merge branch 'main' into arjo/autogenerated_model
arjo129 Nov 30, 2021
8934c39
Merge branch 'main' into arjo/autogenerated_model
arjo129 Dec 8, 2021
da5c6d0
Merge branch 'main' into arjo/autogenerated_model
arjo129 Dec 10, 2021
a97af1d
Merge branch 'main' into arjo/autogenerated_model
arjo129 Dec 12, 2021
505ea0f
tag images to use recent fortress release
arjo129 Dec 13, 2021
10c46c7
Merge branch 'arjo/autogenerated_model' of github.com:osrf/lrauv into…
arjo129 Dec 13, 2021
7f0e8da
Merge branch 'main' into arjo/autogenerated_model
arjo129 Dec 14, 2021
4a690dc
Add numpy as a dependency
arjo129 Dec 14, 2021
874b053
formatting
arjo129 Dec 14, 2021
09aa07d
better debug
arjo129 Dec 14, 2021
e27a920
Merge branch 'main' into arjo/autogenerated_model
arjo129 Dec 14, 2021
45f07ed
Merge branch 'main' into arjo/autogenerated_model
arjo129 Dec 16, 2021
0d2e942
Merge branch 'main' into arjo/autogenerated_model
arjo129 Dec 18, 2021
6762595
bump garden
arjo129 Dec 18, 2021
dd4a7b0
Update lrauv_description/test/test_hydrostatic_stability.cc
arjo129 Dec 22, 2021
602d465
Update lrauv_description/test/test_hydrostatic_stability.cc
arjo129 Dec 22, 2021
50da2a4
change location of python3-numpy
arjo129 Jan 3, 2022
7bf569b
rename worlds
arjo129 Jan 3, 2022
6c3b0ee
Merge branch 'arjo/autogenerated_model' of github.com:osrf/lrauv into…
arjo129 Jan 3, 2022
4373b20
Address @mabelzhang's points
arjo129 Jan 3, 2022
1d0ea08
update hytdrostatics test
arjo129 Jan 3, 2022
fb22cec
Fix coilision volumes.
arjo129 Jan 3, 2022
f332e04
remove gravity. tag
arjo129 Jan 3, 2022
049f65e
style fix
arjo129 Jan 3, 2022
34a3434
Merge branch 'main' into arjo/autogenerated_model
chapulina Jan 5, 2022
00aa92e
Merge branch 'main' into arjo/autogenerated_model
chapulina Jan 6, 2022
010a8c1
Merge branch 'main' into arjo/autogenerated_model
chapulina Jan 6, 2022
d3c21f7
loosen tolerances, the vehicle is oscillating more
chapulina Jan 6, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion docker/debug_integration/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,8 @@ RUN apt-get update \
gnupg2 \
lsb-release \
tzdata \
wget
wget \
python3-numpy

# Add Ignition's latest packages, which may be more up-to-date than the ones from the MBARI image
RUN /bin/sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list' && \
Expand Down
1 change: 1 addition & 0 deletions docker/empty_world/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ RUN apt-get update \
software-properties-common \
sudo \
vim \
python3-numpy
&& apt-get clean

# setup timezone
Expand Down
3 changes: 2 additions & 1 deletion docker/tests/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,8 @@ RUN apt-get update \
gnupg2 \
lsb-release \
tzdata \
wget
wget \
python3-numpy

# Add Ignition's latest packages, which may be more up-to-date than the ones from the MBARI image
RUN /bin/sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list' && \
Expand Down
58 changes: 58 additions & 0 deletions lrauv_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,70 @@ cmake_minimum_required(VERSION 3.5)

project(lrauv_description)


#============================================================================
# Hooks
configure_file(
"hooks/hook.dsv.in"
"${CMAKE_CURRENT_BINARY_DIR}/hooks/hook.dsv" @ONLY
)

#============================================================================
# Model Generation
add_custom_command(
OUTPUT modelsdf
COMMAND python3 ${CMAKE_CURRENT_SOURCE_DIR}/scripts/description_generator.py
${CMAKE_CURRENT_SOURCE_DIR}/models/tethys/model.sdf.in
${CMAKE_CURRENT_BINARY_DIR}/models/tethys/model.sdf
)

add_custom_target(generate_model ALL
DEPENDS modelsdf
)

install(DIRECTORY
models
${CMAKE_CURRENT_BINARY_DIR}/hooks
DESTINATION share/${PROJECT_NAME})

install(FILES
${CMAKE_CURRENT_BINARY_DIR}/models/tethys/model.sdf
DESTINATION share/${PROJECT_NAME}/models/tethys
)

#============================================================================
# Tests
if(BUILD_TESTING)

find_package(ignition-gazebo7 REQUIRED)
set(IGN_GAZEBO_VER ${ignition-gazebo7_VERSION_MAJOR})

# Fetch and configure GTest
include(FetchContent)
FetchContent_Declare(
googletest
URL https://github.com/google/googletest/archive/609281088cfefc76f9d0ce82e1ff6c30cc3591e5.zip
)
set(gtest_force_shared_crt ON CACHE BOOL "" FORCE)
FetchContent_MakeAvailable(googletest)

enable_testing()
include(Dart)

# Build-time constants
set("PROJECT_BINARY_PATH" ${CMAKE_CURRENT_BINARY_DIR})
set("PROJECT_SOURCE_PATH" ${CMAKE_CURRENT_SOURCE_DIR})
configure_file(test/helper/TestConstants.hh.in TestConstants.hh @ONLY)

include(GoogleTest)

add_executable(test_hydrostatic_stability test/test_hydrostatic_stability.cc)
target_include_directories(test_hydrostatic_stability
PRIVATE ${CMAKE_CURRENT_BINARY_DIR})
target_link_libraries(test_hydrostatic_stability
PUBLIC gtest_main
PRIVATE ignition-gazebo${IGN_GAZEBO_VER}::ignition-gazebo${IGN_GAZEBO_VER}
)

gtest_discover_tests(test_hydrostatic_stability)
endif()
Original file line number Diff line number Diff line change
Expand Up @@ -9,36 +9,24 @@
<link name="base_link">
<inertial>
<!-- to offset battery CoM before getting real parameters for vehicle without battery -->
<!--pose>0 0.0236 0 0 0 0</pose-->
<pose>@calculated</pose>
<!-- 146.5671 subtracted by battery mass -->
<mass>114.8364</mass>
<mass>@calculated</mass>
<!--<mass>146.5671</mass>-->
<!-- TODO: Get inertial matrix of base link WITHOUT battery -->
<inertia>
<!--ixx>3.000000</ixx>
<ixx>3.000000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>41.980233</iyy>
<iyz>0</iyz>
<izz>41.980233</izz-->

<!-- Guesstimated (decreased by 1/5) to account for battery -->
<ixx>2.4</ixx>
<ixy>0</ixy>
<ixz>0.0004</ixz>
<iyy>33.5841864</iyy>
<iyz>0</iyz>
<izz>33.5841864</izz>
<izz>41.980233</izz>

</inertia>
</inertial>

<collision name="main_body_buoyancy">
<pose>0 0 0.007 0 0 0</pose>
<geometry>
<box>
<size>2 0.3 0.245945166667</size>
</box>
</geometry>
@calculated
</collision>

<visual name="visual">
Expand Down Expand Up @@ -75,7 +63,6 @@
<link name="horizontal_fins">
<pose>1.05 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 1.57 0 0.5</pose>
<mass>0.2</mass>
<inertia>
<ixx>0.0007924568755</ixx>
Expand All @@ -87,12 +74,8 @@
</inertia>
</inertial>

<collision name="collision">
<geometry>
<box>
<size>0.1 0.1 0.02</size>
</box>
</geometry>
<collision name="horizontal_fins_buoyancy">
@neutral_buoyancy
</collision>

<visual name= "visual">
Expand Down Expand Up @@ -141,12 +124,8 @@
</inertia>
</inertial>

<collision name="collision">
<geometry>
<box>
<size>0.1 0.1 0.02</size>
</box>
</geometry>
<collision name="vertical_fin_buoyancy">
@neutral_buoyancy
</collision>

<visual name= "visual">
Expand Down Expand Up @@ -196,12 +175,8 @@
</inertia>
</inertial>

<collision name="collision">
<geometry>
<box>
<size>0.03 0.1 0.03</size>
</box>
</geometry>
<collision name="propeller_buoyancy">
@neutral_buoyancy
</collision>

<visual name= "visual">
Expand Down Expand Up @@ -239,11 +214,11 @@
<!-- No separate collision for battery, because it is inside the vehicle.
Additional collision requires buoyancy volume recalculation. -->
<link name="battery">
<!-- TODO: On hold till mesh center adjusted to aft dome, then it will be 0.563, 0, 0.024. -->
<pose>0 0 0 0 0 0</pose>
<!--TODO: On hold till mesh center adjusted to aft dome, then it will be 0.563, 0, 0.024.-->

<inertial>
<!-- Non-zero y creates roll. Not fun to tune without actual base link inertia minus battery-->
<!--pose>0 -0.0236 0 0 0 0</pose-->
<pose>-0.563 0 0 0 0 0</pose>
<mass>31.7307</mass>
<inertia>
<ixx>0.2327</ixx>
Expand All @@ -258,7 +233,6 @@
<visual name= "visual">
<geometry>
<box>
<!-- z is guesstimated from schematics. Visual doesn't matter. -->
<size>0.6489446 0.24638 0.17415</size>
</box>
</geometry>
Expand All @@ -271,7 +245,7 @@

<link name="buoyancy_engine">
<!-- TODO: Determine location of buoyancy engine -->
<pose>0.4 0 0 0 0 0</pose>
<pose>0.137 0 0 0 0 0</pose>

<!-- TODO: Remove inertial and collision

Expand All @@ -297,12 +271,8 @@
<izz>0.000033571862</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.03 0.1 0.1</size>
</box>
</geometry>
<collision name="buoyancy_engine">
@neutral_buoyancy
</collision>
</link>

Expand Down Expand Up @@ -342,7 +312,7 @@
</limit>
</axis>
</joint>

<joint name="propeller_joint" type="revolute">
<pose degrees="true">0 0 0 0 180 0</pose>
<parent>base_link</parent>
Expand Down Expand Up @@ -376,20 +346,15 @@

<!-- Drop weight -->
<link name="drop_weight">
<pose>0 0 0 0 0 0</pose>
<pose>0.128 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>1</mass>
<inertia>
<ixx>0.000143971303</ixx>
<ixy>0.000000000008</ixy>
<ixz>-0.000000000224</ixz>
<iyy>0.000140915448</iyy>
<iyz>-0.000025236433</iyz>
<izz>0.000033571862</izz>
</inertia>
</inertial>
</link>

</model>
</sdf>
Loading