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

Run batch simulations over set of startup params in yaml file #125

Merged
merged 32 commits into from
Jan 31, 2023
Merged
Show file tree
Hide file tree
Changes from 11 commits
Commits
Show all changes
32 commits
Select commit Hold shift + click to select a range
f3270ac
proof of concept for looping over simulation parameters
andermi Jan 24, 2023
7bd9088
try to fix
andermi Jan 24, 2023
d78e16e
set on_exit shutdown in launch files
andermi Jan 24, 2023
93866dc
install script and example batch sim params; add launch file; set def…
andermi Jan 24, 2023
c2cf6ca
add rosbag and a log file; rename some things
andermi Jan 24, 2023
326197f
Merge branch 'main' into andermi/batch_sim
andermi Jan 24, 2023
a2203b6
fix max scale in example yaml
andermi Jan 24, 2023
e393454
typo
andermi Jan 24, 2023
94fce17
remove noisy prints; get tests passing
andermi Jan 24, 2023
48667fd
use argparse
andermi Jan 24, 2023
7001355
mbari_wec/model.sdf is now generated by empy
andermi Jan 24, 2023
0ce6b71
try to debug pc commands test
andermi Jan 24, 2023
e0c211b
debug pc commands test
andermi Jan 24, 2023
b1c274c
increase timeout; remove debugging prints
andermi Jan 24, 2023
78ed18a
keep debugging
andermi Jan 24, 2023
b800a3a
keep debugging
andermi Jan 25, 2023
469aca9
keep debugging
andermi Jan 25, 2023
c45d4ea
remove debugging code
andermi Jan 25, 2023
d990b32
set z_ww for doors open/closed -- unused until #115
andermi Jan 25, 2023
862308c
fix argparse
andermi Jan 26, 2023
b384e19
cleanup prints; remove default arg for batch launch
andermi Jan 26, 2023
8ccb07d
change iterations to duration in batch params yaml
andermi Jan 26, 2023
780e53a
clean up
andermi Jan 26, 2023
20d3f06
clean up
andermi Jan 27, 2023
9e318a1
added plumbing for random seed but not yet supported by our version o…
andermi Jan 27, 2023
1fda8d9
make new directory for batch results; copy params yaml to results; ti…
andermi Jan 27, 2023
f387c0a
add some info prints
andermi Jan 27, 2023
363c37f
flake8
andermi Jan 27, 2023
4fbe16c
error checking; let --seed be optional and other params default; dura…
andermi Jan 30, 2023
5ee531c
Merge branch 'main' into andermi/batch_sim
andermi Jan 31, 2023
da98f2c
connect batching template to viscous drag plugin
andermi Jan 31, 2023
8176ac5
retest until pass
andermi Jan 31, 2023
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
13 changes: 12 additions & 1 deletion buoy_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ find_package(ament_cmake REQUIRED)
set(BUOY_BASE_MODEL_PATH "/models/mbari_wec_base")
file(MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}${BUOY_BASE_MODEL_PATH})
add_custom_command(
OUTPUT model_gen_cmd
OUTPUT base_model_gen_cmd
COMMAND python3 -m em
${CMAKE_CURRENT_SOURCE_DIR}${BUOY_BASE_MODEL_PATH}/model.sdf.em >
${CMAKE_CURRENT_BINARY_DIR}${BUOY_BASE_MODEL_PATH}/model.sdf
Expand All @@ -16,6 +16,17 @@ file(MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}${BUOY_MODEL_PATH})
set(BUOY_ROS_MODEL_PATH "/models/mbari_wec_ros")
file(MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}${BUOY_ROS_MODEL_PATH})

add_custom_target(base_model_gen_target ALL
DEPENDS base_model_gen_cmd
)

add_custom_command(
OUTPUT model_gen_cmd
COMMAND python3 -m em
${CMAKE_CURRENT_SOURCE_DIR}${BUOY_MODEL_PATH}/model.sdf.em >
${CMAKE_CURRENT_BINARY_DIR}${BUOY_MODEL_PATH}/model.sdf
)

add_custom_target(model_gen_target ALL
DEPENDS model_gen_cmd
)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,11 @@
<?xml version="1.0" ?>
@{
try:
scale_factor
except NameError:
scale_factor = 1.0 # not defined so default
}@

<sdf version="1.8">
<model name="MBARI_WEC">

Expand All @@ -11,6 +18,7 @@
<PistonArea>1.375</PistonArea>
<HydMotorDisp>0.30</HydMotorDisp>
<RotorInertia>1</RotorInertia>
<ScaleFactor>@(scale_factor)</ScaleFactor>
</plugin>

<!-- Upper Polytropic Spring plugin -->
Expand Down
29 changes: 16 additions & 13 deletions buoy_description/models/mbari_wec_base/model.sdf.em
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,23 @@ tether_top_length = 2.5

num_tether_bottom_links = 5

# Heave cone
heave_total_mass = 817
trefoil_mass = 10
# TrefoilDoors
trefoil_pose = {'open': 1.047, 'closed': 0.0}
try:
door_state
except NameError:
door_state = 'closed' # not defined so default

if 'open' in door_state:
mu_zz = 3000.0

# Heave cone
heave_total_mass = 817
trefoil_mass = 10
trefoil_mass = 20
try:
mu_zz
except NameError:
mu_zz = 10000.0 # not defined so default
Copy link
Collaborator Author

@andermi andermi Jan 24, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

FYI, I set mu_zz value for added mass depending on the door state, but this PR doesn't have the added mass implemented yet. So mu_zz is currently unused but ready when #115 is merged (or I can base this PR from that one)

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yep, mu_zz in the .sdf.em is in the "add-addedmass-to-sdf" branch and PR, but we can't really merge that until the garden debians are available with the handling of the phantom weight of the added mass terms. Also, there is one other parameter that depends upon the doors open/closed state. That's Z_WW and changes a bit with open/closed, shown here: https://osrf.github.io/buoy_entrypoint/pr-preview/pr-17/theory/ That has not yet been parametrized in a .sdf file anywhere b/c we need the viscous drag branch/pull-request to be completed (goal of this friday...)

Copy link
Collaborator Author

@andermi andermi Jan 25, 2023

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@hamilton8415 I now set z_ww as well (commit d990b32) but also unused until #115. I made a TODO to update


###################
# Computed values #
Expand Down Expand Up @@ -449,18 +459,11 @@ pto_scale = pto_inner_radius / pto_stl_inner_radius
</axis>
</joint>

<joint name="TrefoilDoors" type="revolute">
<joint name="TrefoilDoors" type="fixed">
<parent>HeaveCone</parent>
<child>Trefoil</child>
<provide_feedback>1</provide_feedback>
<pose>0.0 0.0 0.0 0 0 0</pose>
<axis>
<limit>
<lower>0.0</lower>
<upper>1.047</upper>
</limit>
<xyz>0.0 0.0 1.0</xyz>
</axis>
<pose>0.0 0.0 0.0 0 0 @(trefoil_pose[door_state])</pose>
</joint>

</model>
Expand Down
4 changes: 4 additions & 0 deletions buoy_gazebo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,10 @@ install(DIRECTORY
DESTINATION share/${PROJECT_NAME}/
)

# Install batch running script
install(PROGRAMS scripts/mbari_wec_batch DESTINATION lib/${PROJECT_NAME}/)
install(FILES scripts/example_sim_params.yaml DESTINATION share/${PROJECT_NAME})

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand Down
16 changes: 10 additions & 6 deletions buoy_gazebo/launch/mbari_wec.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -61,12 +61,16 @@ def generate_launch_description():
PythonLaunchDescriptionSource(
os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py'),
),
launch_arguments={'gz_args': PathJoinSubstitution([
pkg_buoy_gazebo,
'worlds',
LaunchConfiguration('world_file')
]),
'debugger': LaunchConfiguration('debugger')}.items(),
launch_arguments={'gz_args': [
LaunchConfiguration('gz_args'), PathJoinSubstitution([' ']),
PathJoinSubstitution([
pkg_buoy_gazebo,
'worlds',
LaunchConfiguration('world_file')
])
],
'debugger': LaunchConfiguration('debugger'),
'on_exit_shutdown': 'True'}.items(),
)

# Bridge to forward tf and joint states to ros2
Expand Down
51 changes: 51 additions & 0 deletions buoy_gazebo/launch/mbari_wec_batch.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
# Copyright 2022 Open Source Robotics Foundation, Inc. and Monterey Bay Aquarium Research Institute
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""Launch Gazebo world with a buoy."""

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, Shutdown
from launch.substitutions import LaunchConfiguration

from launch_ros.actions import Node


def generate_launch_description():

pkg_buoy_gazebo = get_package_share_directory('buoy_gazebo')
example_sim_params_yaml = os.path.join(pkg_buoy_gazebo, 'example_sim_params.yaml')

sim_params_yaml_launch_arg = DeclareLaunchArgument(
'sim_params_yaml', default_value=[example_sim_params_yaml],
description='Input batch sim params yaml'
)

batch_sim = Node(
package='buoy_gazebo',
executable='mbari_wec_batch',
arguments=[
LaunchConfiguration('sim_params_yaml'),
],
output='screen',
on_exit=Shutdown()
)

return LaunchDescription([
sim_params_yaml_launch_arg,
batch_sim,
])
3 changes: 2 additions & 1 deletion buoy_gazebo/launch/mbari_wec_sinusoidal.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,8 @@ def generate_launch_description():
'worlds',
LaunchConfiguration('world_file')
]),
'debugger': LaunchConfiguration('debugger')}.items(),
'debugger': LaunchConfiguration('debugger'),
'on_exit_shutdown': 'True'}.items(),
)

# Bridge to forward tf and joint states to ros2
Expand Down
3 changes: 3 additions & 0 deletions buoy_gazebo/scripts/example_sim_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
iterations: 5000
door_state: ['closed', 'open']
scale_factor: [0.5, 0.625, 0.75, 0.875, 1.0, 1.125, 1.25, 1.375, 1.4]
107 changes: 107 additions & 0 deletions buoy_gazebo/scripts/mbari_wec_batch
Original file line number Diff line number Diff line change
@@ -0,0 +1,107 @@
#!/usr/bin/python3
# Copyright 2022 Open Source Robotics Foundation, Inc. and Monterey Bay Aquarium Research Institute
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""Launch batch of buoy simulations."""

from em import invoke as empy
import numpy as np
import yaml

import os
import time

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch import LaunchService
from launch.actions import ExecuteProcess, IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource


def generate_simulations(sim_params_yaml):
with open(sim_params_yaml, 'r') as fd:
sim_params = yaml.load(fd, Loader=yaml.CLoader)

iterations = sim_params['iterations']
door_state = sim_params['door_state']
scale_factor = sim_params['scale_factor']
batch_params = list(zip(*[param.ravel() for param in np.meshgrid(iterations,
door_state,
scale_factor)]))

print(f'Generated {len(batch_params)} simulation runs:')
print(f'Iterations, Door State, Scale Factor\n{np.array(batch_params)}')

timestr = time.strftime("%Y%m%d%H%M%S")
with open(f'batch_runs_{timestr}.log', 'w') as fd:
fd.write(f'# Generated {len(batch_params)} simulation runs\n')
fd.write(f'Run Index, Iterations, Door State, Scale Factor\n')

pkg_buoy_gazebo = get_package_share_directory('buoy_gazebo')
pkg_buoy_description = get_package_share_directory('buoy_description')

model_dir = 'mbari_wec_base'
empy_base_sdf_file = os.path.join(pkg_buoy_description, 'models', model_dir, 'model.sdf.em')
base_sdf_file = os.path.join(pkg_buoy_description, 'models', model_dir, 'model.sdf')

model_dir = 'mbari_wec'
empy_sdf_file = os.path.join(pkg_buoy_description, 'models', model_dir, 'model.sdf.em')
sdf_file = os.path.join(pkg_buoy_description, 'models', model_dir, 'model.sdf')

for idx, (itx, ds, sf) in enumerate(batch_params):
print(f'\n\nSim run [{idx}] for {itx} iterations: door state={ds}, scale factor={sf}\n\n')
empy(['-D', f"door_state = '{ds}'",
'-o', base_sdf_file,
empy_base_sdf_file])

empy(['-D', f"scale_factor = '{sf}'",
'-o', sdf_file,
empy_sdf_file])

def generate_launch_description():
mbari_wec = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
os.path.join(pkg_buoy_gazebo, 'launch', 'mbari_wec.launch.py'),
),
launch_arguments={'gz_args': f'-rs --iterations {itx}'}.items(),
)

rosbag2_name = f'rosbag2_batch_sim_{idx}'
rosbag2 = ExecuteProcess(
cmd=['ros2', 'bag', 'record', '-o', rosbag2_name, '-a'],
output='screen'
)

with open(f'batch_runs_{timestr}.log', 'a') as fd:
fd.write(f'{idx, itx, ds, sf}\n')

return LaunchDescription([
rosbag2,
mbari_wec
])

ls = LaunchService()
ls.include_launch_description(generate_launch_description())
result = ls.run()
if result:
print(f'Simulation run [{idx}] was not successful: return code [{result}]')

if __name__=='__main__':
import argparse
parser = argparse.ArgumentParser(description='Batch running for buoy_sim')
parser.add_argument('sim_params_yaml',
help='yaml file with batch parameters')
args = parser.parse_args()
generate_simulations(args.sim_params_yaml)
11 changes: 9 additions & 2 deletions buoy_gazebo/src/ElectroHydraulicPTO/ElectroHydraulicPTO.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,12 +54,15 @@ class ElectroHydraulicPTOPrivate
/// \brief Piston joint entity
gz::sim::Entity PrismaticJointEntity{gz::sim::kNullEntity};

/// \brief Piston area
/// \brief Piston area
double PistonArea{1.0};

/// \brief Rotor Inertia
double RotorInertia{1.0};

/// \brief Default Scale Factor
double DefaultScaleFactor{DEFAULT_SCALE_FACTOR};

/// \brief Model interface
gz::sim::Model model{gz::sim::kNullEntity};

Expand All @@ -72,6 +75,7 @@ class ElectroHydraulicPTOPrivate
static constexpr double I_BattChargeMax{7.0};
static constexpr double MaxTargetVoltage{325.0};


// Dummy compensator pressure for ROS messages, not simulated
static constexpr double CompensatorPressure{2.91};

Expand Down Expand Up @@ -133,6 +137,9 @@ void ElectroHydraulicPTO::Configure(
this->dataPtr->PistonArea = SdfParamDouble(_sdf, "PistonArea", this->dataPtr->PistonArea);
}

this->dataPtr->DefaultScaleFactor =
SdfParamDouble(_sdf, "ScaleFactor", this->dataPtr->DefaultScaleFactor);

if (_sdf->HasElement("VelMode")) {
this->dataPtr->VelMode = true;
}
Expand Down Expand Up @@ -247,7 +254,7 @@ void ElectroHydraulicPTO::PreUpdate(
if (pto_state.scale_command) {
this->dataPtr->functor.I_Wind.ScaleFactor = pto_state.scale_command.value();
} else {
this->dataPtr->functor.I_Wind.ScaleFactor = DEFAULT_SCALE_FACTOR;
this->dataPtr->functor.I_Wind.ScaleFactor = this->dataPtr->DefaultScaleFactor;
}

if (pto_state.retract_command) {
Expand Down
4 changes: 3 additions & 1 deletion buoy_tests/launch/no_inputs_py.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,9 @@ def generate_test_description():
gazebo_test_fixture = Node(
package='buoy_tests',
executable='no_inputs',
output='screen'
output='screen' # ,
# TODO(anyone) for some reason this makes the test fail
# on_exit=launch.actions.Shutdown()
)

bridge = Node(package='ros_gz_bridge',
Expand Down
3 changes: 2 additions & 1 deletion buoy_tests/launch/no_inputs_ros_feedback.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,8 @@ def generate_test_description():
gazebo_test_fixture = Node(
package='buoy_tests',
executable='no_inputs_ros_feedback',
output='screen'
output='screen',
on_exit=launch.actions.Shutdown()
)

bridge = Node(package='ros_gz_bridge',
Expand Down
3 changes: 2 additions & 1 deletion buoy_tests/launch/pc_commands_ros_feedback.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ def generate_test_description():
package='buoy_tests',
executable='pc_commands_ros_feedback',
output='screen',
parameters=[config]
parameters=[config],
on_exit=launch.actions.Shutdown()
)

bridge = Node(package='ros_gz_bridge',
Expand Down
3 changes: 2 additions & 1 deletion buoy_tests/launch/pto_experiment_comparison.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ def generate_launch_description():
gazebo_test_fixture = launchNode(
package='buoy_tests',
executable='experiment_comparison',
output='screen'
output='screen',
on_exit=launch.actions.Shutdown()
)

return launch.LaunchDescription([
Expand Down
3 changes: 2 additions & 1 deletion buoy_tests/launch/run_server.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ def generate_launch_description():
gazebo_test_fixture = launchNode(
package='buoy_tests',
executable='fixture_server',
output='screen'
output='screen',
on_exit=launch.actions.Shutdown()
)

bridge = launchNode(package='ros_gz_bridge',
Expand Down
Loading