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

Reorganize plugins into different models #78

Merged
merged 2 commits into from
Aug 5, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
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
2 changes: 1 addition & 1 deletion buoy_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ project(buoy_description)
find_package(ament_cmake REQUIRED)

# Model Generation
set(BUOY_MODEL_PATH "/models/mbari_wec")
set(BUOY_MODEL_PATH "/models/mbari_wec_base")
file(MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}${BUOY_MODEL_PATH})
add_custom_command(
OUTPUT model_gen_cmd
Expand Down
5 changes: 3 additions & 2 deletions buoy_description/models/mbari_wec/model.config
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<model>
<name>MBARI_WEC</name>
<version>1.0</version>
<sdf version="1.6">model.sdf</sdf>
<sdf version="1.8">model.sdf</sdf>

<author>
<name>Michael Anderson</name>
Expand All @@ -18,6 +18,7 @@
</author>

<description>
MBARI-WEC (Wave Energy Converter) model for ocean sensing and harvesting wave energy.
MBARI-WEC (Wave Energy Converter) model for ocean sensing and harvesting wave energy
with quasi-static multi-physics plugins for Pneumatic Spring and Electro-Hydraulic Power Take-Off
</description>
</model>
66 changes: 66 additions & 0 deletions buoy_description/models/mbari_wec/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
<?xml version="1.0" ?>
<sdf version="1.8">
<model name="MBARI_WEC">

<include merge="true">
<uri>package://buoy_description/models/mbari_wec_base</uri>
</include>

<plugin filename="ElectroHydraulicPTO" name="buoy_gazebo::ElectroHydraulicPTO">
<PrismaticJointName>HydraulicRam</PrismaticJointName>
<PistonArea>1.375</PistonArea>
<HydMotorDisp>0.30</HydMotorDisp>
<RotorInertia>1</RotorInertia>
</plugin>

<!-- Add Upper/Lower Polytropic Spring plugin -->
<plugin filename="PolytropicPneumaticSpring" name="buoy_gazebo::PolytropicPneumaticSpring">
<JointName>HydraulicRam</JointName>
<chamber>upper_polytropic</chamber>
<is_upper>true</is_upper>
<!-- measure of valve opening cross-section and duration (meter-seconds) -->
<valve_absement>49e-7</valve_absement>
<pump_absement>14e-8</pump_absement>
<pump_pressure>1.7e+6</pump_pressure>
<stroke>2.03</stroke>
<piston_area>0.0127</piston_area>
<dead_volume>0.0266</dead_volume>
<T0>283.15</T0>
<R_specific>0.2968</R_specific>
<c_p>1.04</c_p>
<hysteresis>true</hysteresis>
<n1>1.2371</n1>
<n2>1.2307</n2>
<x1>0.9790</x1>
<x2>1.1912</x2>
<P1>410291</P1>
<P2>410266</P2>
</plugin>

<!-- <debug_prescribed_velocity>true</debug_prescribed_velocity>-->
<plugin filename="PolytropicPneumaticSpring" name="buoy_gazebo::PolytropicPneumaticSpring">
<JointName>HydraulicRam</JointName>
<chamber>lower_polytropic</chamber>
<is_upper>false</is_upper>
<!-- measure of valve opening cross-section and duration (meter-seconds) -->
<valve_absement>49e-7</valve_absement>
<pump_absement>14e-8</pump_absement>
<pump_pressure>1.7e+6</pump_pressure>
<stroke>2.03</stroke>
<piston_area>0.0115</piston_area>
<dead_volume>0.0523</dead_volume>
<T0>283.15</T0>
<R_specific>0.2968</R_specific>
<c_p>1.04</c_p>
<hysteresis>true</hysteresis>
<n1>1.2327</n1>
<n2>1.2518</n2>
<x1>1.1958</x1>
<x2>1.3935</x2>
<P1>1212090</P1>
<P2>1212140</P2>
</plugin>
<!-- <debug_prescribed_velocity>true</debug_prescribed_velocity>-->

</model>
</sdf>
23 changes: 23 additions & 0 deletions buoy_description/models/mbari_wec_base/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<?xml version="1.0"?>
<model>
<name>MBARI_WEC</name>
<version>1.0</version>
<sdf version="1.8">model.sdf</sdf>

<author>
<name>Michael Anderson</name>
<email>[email protected]</email>
</author>
<author>
<name>Louise Poubel</name>
<email>[email protected]</email>
</author>
<author>
<name>Dharini Dutia</name>
<email>[email protected]</email>
</author>

<description>
Base MBARI-WEC (Wave Energy Converter) model for ocean sensing and harvesting wave energy.
</description>
</model>
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ pto_inner_radius = tether_radius + pto_gap
pto_scale = pto_inner_radius / pto_stl_inner_radius
}@
<sdf version="1.8">
<model name="MBARI_WEC">
<model name="MBARI_WEC_BASE">
<self_collide>true</self_collide>
<link name="Buoy">
<pose relative_to="__model__">0 0 0 0 0 0</pose>
Expand All @@ -95,7 +95,7 @@ pto_scale = pto_inner_radius / pto_stl_inner_radius
<visual name="visual_Buoy">
<geometry>
<mesh>
<uri>package://buoy_description/models/mbari_wec/meshes/buoy_float.stl</uri>
<uri>package://buoy_description/models/mbari_wec_base/meshes/buoy_float.stl</uri>
</mesh>
</geometry>
<!--color-->
Expand Down Expand Up @@ -143,7 +143,7 @@ pto_scale = pto_inner_radius / pto_stl_inner_radius
<visual name="visual_PTO">
<geometry>
<mesh>
<uri>package://buoy_description/models/mbari_wec/meshes/pto.stl</uri>
<uri>package://buoy_description/models/mbari_wec_base/meshes/pto.stl</uri>
</mesh>
</geometry>
<material>
Expand All @@ -155,7 +155,7 @@ pto_scale = pto_inner_radius / pto_stl_inner_radius
<collision name="collision">
<geometry>
<mesh>
<uri>package://buoy_description/models/mbari_wec/meshes/pto_collision.stl</uri>
<uri>package://buoy_description/models/mbari_wec_base/meshes/pto_collision.stl</uri>
<scale>@(pto_scale) @(pto_scale) 1.0</scale>
</mesh>
</geometry>
Expand Down Expand Up @@ -192,7 +192,7 @@ pto_scale = pto_inner_radius / pto_stl_inner_radius
<visual name="visual_Piston">
<geometry>
<mesh>
<uri>package://buoy_description/models/mbari_wec/meshes/rod_and_piston.stl</uri>
<uri>package://buoy_description/models/mbari_wec_base/meshes/rod_and_piston.stl</uri>
</mesh>
</geometry>
<!--color-->
Expand Down Expand Up @@ -359,7 +359,7 @@ pto_scale = pto_inner_radius / pto_stl_inner_radius
<visual name="visual_HeaveCone">
<geometry>
<mesh>
<uri>package://buoy_description/models/mbari_wec/meshes/heave_cone.stl</uri>
<uri>package://buoy_description/models/mbari_wec_base/meshes/heave_cone.stl</uri>
</mesh>
</geometry>
<!--color-->
Expand Down Expand Up @@ -397,7 +397,7 @@ pto_scale = pto_inner_radius / pto_stl_inner_radius
<visual name="visual_Trefoil">
<geometry>
<mesh>
<uri>package://buoy_description/models/mbari_wec/meshes/trefoil.stl</uri>
<uri>package://buoy_description/models/mbari_wec_base/meshes/trefoil.stl</uri>
</mesh>
</geometry>
<!--color-->
Expand Down Expand Up @@ -461,5 +461,6 @@ pto_scale = pto_inner_radius / pto_stl_inner_radius
<xyz>0.0 0.0 1.0</xyz>
</axis>
</joint>

</model>
</sdf>
24 changes: 24 additions & 0 deletions buoy_description/models/mbari_wec_ros/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<?xml version="1.0"?>
<model>
<name>MBARI_WEC</name>
<version>1.0</version>
<sdf version="1.8">model.sdf</sdf>

<author>
<name>Michael Anderson</name>
<email>[email protected]</email>
</author>
<author>
<name>Louise Poubel</name>
<email>[email protected]</email>
</author>
<author>
<name>Dharini Dutia</name>
<email>[email protected]</email>
</author>

<description>
ROS2-enabled MBARI-WEC (Wave Energy Converter) model for ocean sensing and harvesting wave energy
with quasi-static multi-physics plugins for Pneumatic Spring and Electro-Hydraulic Power Take-Off.
andermi marked this conversation as resolved.
Show resolved Hide resolved
</description>
</model>
40 changes: 40 additions & 0 deletions buoy_description/models/mbari_wec_ros/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
<?xml version="1.0" ?>
<sdf version="1.8">
<model name="MBARI_WEC_ROS">

<include merge="true">
<uri>package://buoy_description/models/mbari_wec</uri>
</include>

<!-- Handle Unimplemented Services -->
<plugin filename="NoOpController" name="buoy_gazebo::NoOpController">
<namespace>/</namespace>
<node_name>noop_controller</node_name>
</plugin>

<plugin filename="SpringController" name="buoy_gazebo::SpringController">
<JointName>HydraulicRam</JointName>
<namespace>/</namespace>
<node_name>spring_controller</node_name>
<topic>spring_data</topic>
<publish_rate>10</publish_rate>
</plugin>

<plugin filename="PowerController" name="buoy_gazebo::PowerController">
<JointName>HydraulicRam</JointName>
<namespace>/</namespace>
<node_name>power_controller</node_name>
<topic>power_data</topic>
<publish_rate>10</publish_rate>
</plugin>

<plugin filename="XBowAHRS" name="buoy_gazebo::XBowAHRS">
<namespace>/</namespace>
<node_name>xbow_ahrs</node_name>
<xb_topic>ahrs_data</xb_topic>
<imu_topic>xb_imu</imu_topic>
<publish_rate>10</publish_rate>
</plugin>

</model>
</sdf>
4 changes: 2 additions & 2 deletions buoy_gazebo/rviz/mbari_wec.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -69,14 +69,14 @@ Visualization Manager:
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
Name: RobotModel
TF Prefix: MBARI_WEC
TF Prefix: MBARI_WEC_ROS
Update Interval: 0
Value: true
Visual Enabled: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: MBARI_WEC/odom
Fixed Frame: MBARI_WEC_ROS/odom
Frame Rate: 30
Name: root
Tools:
Expand Down
94 changes: 4 additions & 90 deletions buoy_gazebo/worlds/mbari_wec.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -42,99 +42,13 @@
</link>
</model>

<model name="MBARI_WEC">
<model name="MBARI_WEC_ROS">
<pose relative_to="world">0 0 -2 0 0 0</pose>

<include merge="true">
<uri>package://buoy_description/models/mbari_wec</uri>
<uri>package://buoy_description/models/mbari_wec_ros</uri>
</include>

<plugin filename="ElectroHydraulicPTO" name="buoy_gazebo::ElectroHydraulicPTO">
<PrismaticJointName>HydraulicRam</PrismaticJointName>
<PistonArea>1.375</PistonArea>
<HydMotorDisp>0.30</HydMotorDisp>
<RotorInertia>1</RotorInertia>
</plugin>

<!-- Handle Unimplemented Services -->
<plugin filename="NoOpController" name="buoy_gazebo::NoOpController">
<namespace>/</namespace>
<node_name>noop_controller</node_name>
</plugin>

<plugin filename="SpringController" name="buoy_gazebo::SpringController">
<JointName>HydraulicRam</JointName>
<namespace>/</namespace>
<node_name>spring_controller</node_name>
<topic>spring_data</topic>
<publish_rate>31</publish_rate>
</plugin>

<plugin filename="PowerController" name="buoy_gazebo::PowerController">
<JointName>HydraulicRam</JointName>
<namespace>/</namespace>
<node_name>power_controller</node_name>
<topic>power_data</topic>
<publish_rate>23</publish_rate>
</plugin>

<plugin filename="XBowAHRS" name="buoy_gazebo::XBowAHRS">
<namespace>/</namespace>
<node_name>xbow_ahrs</node_name>
<xb_topic>ahrs_data</xb_topic>
<imu_topic>xb_imu</imu_topic>
<publish_rate>17</publish_rate>
</plugin>

<!-- Add Upper/Lower Polytropic Spring plugin -->
<plugin filename="PolytropicPneumaticSpring" name="buoy_gazebo::PolytropicPneumaticSpring">
<JointName>HydraulicRam</JointName>
<chamber>upper_polytropic</chamber>
<is_upper>true</is_upper>
<!-- measure of valve opening cross-section and duration (meter-seconds) -->
<valve_absement>49e-7</valve_absement>
<pump_absement>14e-8</pump_absement>
<pump_pressure>1.7e+6</pump_pressure>
<stroke>2.03</stroke>
<piston_area>0.0127</piston_area>
<dead_volume>0.0266</dead_volume>
<T0>283.15</T0>
<R_specific>0.2968</R_specific>
<c_p>1.04</c_p>
<hysteresis>true</hysteresis>
<n1>1.2371</n1>
<n2>1.2307</n2>
<x1>0.9790</x1>
<x2>1.1912</x2>
<P1>410291</P1>
<P2>410266</P2>
</plugin>

<!-- <debug_prescribed_velocity>true</debug_prescribed_velocity>-->
<plugin filename="PolytropicPneumaticSpring" name="buoy_gazebo::PolytropicPneumaticSpring">
<JointName>HydraulicRam</JointName>
<chamber>lower_polytropic</chamber>
<is_upper>false</is_upper>
<!-- measure of valve opening cross-section and duration (meter-seconds) -->
<valve_absement>49e-7</valve_absement>
<pump_absement>14e-8</pump_absement>
<pump_pressure>1.7e+6</pump_pressure>
<stroke>2.03</stroke>
<piston_area>0.0115</piston_area>
<dead_volume>0.0523</dead_volume>
<T0>283.15</T0>
<R_specific>0.2968</R_specific>
<c_p>1.04</c_p>
<hysteresis>true</hysteresis>
<n1>1.2327</n1>
<n2>1.2518</n2>
<x1>1.1958</x1>
<x2>1.3935</x2>
<P1>1212090</P1>
<P2>1212140</P2>
</plugin>
<!-- <debug_prescribed_velocity>true</debug_prescribed_velocity>-->

<plugin
filename="ignition-gazebo-joint-state-publisher-system"
name="ignition::gazebo::systems::JointStatePublisher">
Expand All @@ -153,8 +67,8 @@
filename="ignition-gazebo-odometry-publisher-system"
name="ignition::gazebo::systems::OdometryPublisher">
<dimensions>3</dimensions>
<odom_frame>MBARI_WEC/odom</odom_frame>
<robot_base_frame>MBARI_WEC</robot_base_frame>
<odom_frame>MBARI_WEC_ROS/odom</odom_frame>
<robot_base_frame>MBARI_WEC_ROS</robot_base_frame>
</plugin>

</model>
Expand Down
2 changes: 1 addition & 1 deletion buoy_tests/tests/fixture_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ TEST(BuoyTests, RunServer)
{
auto world = ignition::gazebo::World(_worldEntity);

buoyEntity = world.ModelByName(_ecm, "MBARI_WEC");
buoyEntity = world.ModelByName(_ecm, "MBARI_WEC_ROS");
EXPECT_NE(ignition::gazebo::kNullEntity, buoyEntity);
}).
OnPostUpdate(
Expand Down
Loading