forked from Field-Robotics-Lab/dave
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
launch and xacro for multi-vehicle transient current demo
- Loading branch information
Showing
2 changed files
with
215 additions
and
0 deletions.
There are no files selected for viewing
32 changes: 32 additions & 0 deletions
32
examples/dave_demo_launch/launch/dave_transient_current_multi.launch
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,32 @@ | ||
<?xml version="1.0"?> | ||
<launch> | ||
|
||
<arg name="namespace" default="smilodon"/> | ||
<arg name="velocity_control" default="true"/> | ||
<arg name="debug" default="false"/> | ||
<arg name="x" default="25"/> | ||
<arg name="y" default="0"/> | ||
<arg name="z" default="-85"/> | ||
<arg name="roll" default="0"/> | ||
<arg name="pitch" default="0"/> | ||
<arg name="yaw" default="-1.8"/> | ||
|
||
|
||
|
||
<param name="/$(arg namespace)/robot_description" | ||
command="$(find xacro)/xacro '$(find smilodon_description)/urdf/smilodon_gazebo_transient_current.xacro' --inorder | ||
debug:=$(arg debug) | ||
namespace:=$(arg namespace) | ||
inertial_reference_frame:=world" /> | ||
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot --> | ||
<node name="urdf_spawner" pkg="uuv_descriptions" type="spawn_model" respawn="false" output="screen" | ||
args="-urdf -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg roll) -P $(arg pitch) -Y $(arg yaw) -model $(arg namespace) -param /$(arg namespace)/robot_description"/> | ||
|
||
<!-- A joint state publisher plugin already is started with the model, | ||
no need to use the default joint state publisher. --> | ||
<!-- Robot state publisher subscribes to the custom joint state publisher --> | ||
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen"> | ||
<remap from="robot_description" to="/$(arg namespace)/robot_description"/> | ||
</node> | ||
|
||
</launch> |
183 changes: 183 additions & 0 deletions
183
urdf/robots/smilodon_description/urdf/smilodon_gazebo_transient_current.xacro
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,183 @@ | ||
<?xml version="1.0"?> | ||
<!-- | ||
All rights reserved. | ||
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. | ||
--> | ||
|
||
<robot name="smilodon" xmlns:xacro="http://www.ros.org/wiki/xacro" > | ||
|
||
<xacro:arg name="debug" default="0"/> | ||
<xacro:arg name="namespace" default="smilodon"/> | ||
<xacro:arg name="inertial_reference_frame" default="world"/> | ||
|
||
<!-- Includes --> | ||
<!--xacro:include filename="$(find uuv_dave)/urdf/sensor_snippets.xacro"/>--> | ||
<!----> | ||
|
||
<!-- base_link according to ROS conventions: x forward, z up --> | ||
<link name="$(arg namespace)/base_link"> | ||
<inertial> | ||
<mass value="1862.87"/> | ||
<origin xyz="0 0 0"/> | ||
<inertia ixx="525.39" ixy="1.44" ixz="33.41" iyy="794.20" iyz="2.6" izz="691.23"/> | ||
</inertial> | ||
<visual> | ||
<origin xyz="0 0 0" rpy="0 0 1.5708"/> | ||
<geometry> | ||
<mesh filename="package://smilodon_description/meshes/smilodon_nologo_visual.dae" scale="1 1 1"/> | ||
</geometry> | ||
</visual> | ||
<collision> | ||
<origin xyz="0 0 0" rpy="0 0 1.5708"/> | ||
<geometry> | ||
<mesh filename="package://smilodon_description/meshes/smilodon_collision.dae" scale="1 1 1"/> | ||
</geometry> | ||
</collision> | ||
</link> | ||
|
||
<gazebo> | ||
<!-- Create plugin to generate depth-dependent current for this vehicle--> | ||
<plugin name="dave_transient_current_plugin" filename="libdave_ocean_current_model_plugin.so"> | ||
<flow_velocity_topic>hydrodynamics/current_velocity/$(arg namespace)</flow_velocity_topic> | ||
<base_link_name>$(arg namespace)/base_link</base_link_name> | ||
<transient_current> | ||
<topic_stratified_database>stratified_current_velocity_database</topic_stratified_database> | ||
<velocity_north> | ||
<noiseAmp>0.3</noiseAmp> | ||
<noiseFreq>0.0</noiseFreq> | ||
</velocity_north> | ||
<velocity_east> | ||
<noiseAmp>0.3</noiseAmp> | ||
<noiseFreq>0.0</noiseFreq> | ||
</velocity_east> | ||
<velocity_down> | ||
<noiseAmp>0.3</noiseAmp> | ||
<noiseFreq>0.0</noiseFreq> | ||
</velocity_down> | ||
</transient_current> | ||
</plugin> | ||
<!-- UUV plugin subscribes to this vehicle's depth-dependent current topic--> | ||
<plugin name="uuv_plugin" filename="libuuv_underwater_object_ros_plugin.so"> | ||
<!-- Hydro parameters for the vehicle--> | ||
<fluid_density>1028.0</fluid_density> | ||
<flow_velocity_topic>hydrodynamics/current_velocity/$(arg namespace)</flow_velocity_topic> | ||
<debug>$(arg debug)</debug> | ||
|
||
<link name="$(arg namespace)/base_link"> | ||
<neutrally_buoyant>1</neutrally_buoyant> | ||
<!-- Volume, see p.31 in Berg2012 --> | ||
<volume>1.8382</volume> | ||
<box> | ||
<width>1.5</width> | ||
<length>2.6</length> | ||
<height>1.6</height> | ||
</box> | ||
<!-- | ||
Center of buoyancy according to eq. (3.1) p. 28 in Berg2012. | ||
The original values, [0.0822, -0.00773, 0.3872] however, seem to | ||
assume NWU (otherwise cob is below cog?). | ||
--> | ||
<center_of_buoyancy>0.0 0.0 0.3</center_of_buoyancy> | ||
<hydrodynamic_model> | ||
<type>fossen</type> | ||
<!-- Added mass: see p.28 in Berg2012 --> | ||
<added_mass> | ||
779.79 -6.8773 -103.32 8.5426 -165.54 -7.8033 | ||
-6.8773 1222 51.29 409.44 -5.8488 62.726 | ||
-103.32 51.29 3659.9 6.1112 -386.42 10.774 | ||
8.5426 409.44 6.1112 534.9 -10.027 21.019 | ||
-165.54 -5.8488 -386.42 -10.027 842.69 -1.1162 | ||
-7.8033 62.726 10.775 21.019 -1.1162 224.32 | ||
</added_mass> | ||
<!-- Linear damping: see p.31 in Berg2012 --> | ||
<linear_damping> | ||
-74.82 -69.48 -728.4 -268.8 -309.77 -105 | ||
</linear_damping> | ||
<!-- Non-linear damping: see p.30 in Berg2012 --> | ||
<quadratic_damping> | ||
-748.22 -992.53 -1821.01 -672 -774.44 -523.27 | ||
</quadratic_damping> | ||
</hydrodynamic_model> | ||
</link> | ||
</plugin> | ||
</gazebo> | ||
|
||
<gazebo> | ||
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> | ||
<robotNamespace>/$(arg namespace)</robotNamespace> | ||
<robotParam>/$(arg namespace)/robot_description</robotParam> | ||
</plugin> | ||
</gazebo> | ||
|
||
<!-- Define thrusters for propulsion --> | ||
<xacro:property name="prop_mesh_file" value="file://$(find uuv_descriptions)/meshes/prop.dae"/> | ||
<!-- Common values, colors, converstion, standard shapes/inertia etc. | ||
Dependency for the thruster_snippets.xacro--> | ||
<xacro:include filename="$(find uuv_descriptions)/urdf/common.urdf.xacro"/> | ||
<!-- Various thruster models --> | ||
<xacro:include filename="$(find uuv_gazebo_ros_plugins)/urdf/thruster_snippets.xacro"/> | ||
<xacro:property name="prop_mesh_file" value="file://$(find uuv_descriptions)/meshes/prop.dae"/> | ||
<!-- Thruster joint and link snippet | ||
Wrapper for the the thruster_module_first_order_basic_fcn_macro | ||
defined in uuv_gazebo_ros_plugins/urdf/thruster_snippet. | ||
Uses the "thruster_cf_basic_macro" | ||
1) Basic curve | ||
Input: x | ||
Output: thrust | ||
Function: thrust = rotorConstant * x * abs(x) | ||
--> | ||
<xacro:macro name="thruster_macro" | ||
params="thruster_id *origin"> | ||
<xacro:thruster_module_first_order_basic_fcn_macro | ||
namespace="$(arg namespace)" | ||
thruster_id="${thruster_id}" | ||
mesh_filename="${prop_mesh_file}" | ||
dyn_time_constant="0.05" | ||
rotor_constant="0.00031"> | ||
<xacro:insert_block name="origin"/> | ||
</xacro:thruster_module_first_order_basic_fcn_macro> | ||
</xacro:macro> | ||
|
||
<!-- Port-Aft --> | ||
<xacro:thruster_macro thruster_id="0"> | ||
<origin xyz="-3.3 0.8 -0.1" rpy="${0*d2r} ${0*d2r} ${200.0*d2r}"/> | ||
</xacro:thruster_macro> | ||
<!-- Stbd-Aft --> | ||
<xacro:thruster_macro thruster_id="1"> | ||
<origin xyz="-3.3 -0.8 -0.1" rpy="${0*d2r} ${0*d2r} ${160.0*d2r}"/> | ||
</xacro:thruster_macro> | ||
<!-- Port-Vert --> | ||
<xacro:thruster_macro thruster_id="2"> | ||
<origin xyz="1.8 0.8 0.4" rpy="${0*d2r} ${-110.0*d2r} ${90.0*d2r}"/> | ||
</xacro:thruster_macro> | ||
<!-- Stbd-Vert --> | ||
<xacro:thruster_macro thruster_id="3"> | ||
<origin xyz="1.8 -0.8 0.4" rpy="${0*d2r} ${-110*d2r} ${-90.0*d2r}"/> | ||
</xacro:thruster_macro> | ||
<!-- Port-Lat --> | ||
<xacro:thruster_macro thruster_id="4"> | ||
<origin xyz="1.8 1.3 -0.07" rpy="${0*d2r} ${0*d2r} ${90.0*d2r}"/> | ||
</xacro:thruster_macro> | ||
<!-- Stbd-Lat --> | ||
<xacro:thruster_macro thruster_id="5"> | ||
<origin xyz="1.8 -1.3 -0.07" rpy="${0*d2r} ${0*d2r} ${-90.0*d2r}"/> | ||
</xacro:thruster_macro> | ||
|
||
|
||
<!-- Default joint state publisher --> | ||
<gazebo> | ||
<plugin name="uuv_joint_state_publisher" filename="libuuv_joint_state_publisher.so"> | ||
<robotNamespace>$(arg namespace)</robotNamespace> | ||
<updateRate>50</updateRate> | ||
</plugin> | ||
</gazebo> | ||
|
||
</robot> |