-
Notifications
You must be signed in to change notification settings - Fork 73
/
Copy pathrexrov_oberon7_transient_current.xacro
127 lines (113 loc) · 4.98 KB
/
rexrov_oberon7_transient_current.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
<?xml version="1.0"?>
<!-- Copyright (c) 2016 The UUV Simulator Authors.
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="rexrov" xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:arg name="debug" default="0"/>
<xacro:arg name="namespace" default="rexrov"/>
<xacro:arg name="inertial_reference_frame" default="world"/>
<!-- Include the ROV macro file -->
<xacro:include filename="$(find uuv_dave)/urdf/rexrov_base.xacro"/>
<xacro:include filename="$(find uuv_descriptions)/urdf/rexrov.gazebo.xacro"/>
<xacro:include filename="$(find uuv_dave)/urdf/oberon7_default.xacro" />
<!-- This implements the image_sonar_ros_plugin.so implemented in uuv_simulator.
See the source code https://github.com/uuvsimulator/uuv_simulator/blob/master/uuv_sensor_plugins/uuv_sensor_ros_plugins/src/gazebo_ros_image_sonar.cpp
See description wiki https://github.com/Field-Robotics-Lab/dave/wiki/image_sonar_description
-->
<!-- Commenting this out b/c the primary multibeam sonar sensor plugin is now here: https://github.com/Field-Robotics-Lab/nps_uw_multibeam_sonar
Keeping the snippet around for posterity -->
<!--
<xacro:uuv_forward_looking_sonar
namespace="${namespace}"
suffix="down"
parent_link="${namespace}/base_link"
topic="forward_sonar"
mass="0.015"
update_rate="40"
samples="100"
fov="1.54719755"
width="768"
height="492">
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
<origin xyz="1.15 0 0.4" rpy="0 0.3 0"/>
<visual>
</visual>
</xacro:uuv_forward_looking_sonar>
-->
<!--
<xacro:uuv_forward_multibeam_p900
namespace="${namespace}"
parent_link="${namespace}/base_link">
<origin xyz="1.15 0 0.4" rpy="0 0.3 0"/>
</xacro:uuv_forward_multibeam_p900>
-->
<!--
<xacro:uuv_fl_multibeam_generic
namespace="${namespace}"
parent_link="${namespace}/base_link">
<origin xyz="1.15 0 0.4" rpy="0 0.3 0"/>
</xacro:uuv_fl_multibeam_generic>
-->
<!-- creates beam lines in Gazebo view
<xacro:uuv_forward_multibeam_sonar_m450_130 namespace="$(arg namespace)" parent_link="$(arg namespace)/base_link">
<origin xyz="1.4 0 0.65" rpy="0 0 0"/>
</xacro:uuv_forward_multibeam_sonar_m450_130>
-->
<!-- Create the ROV -->
<xacro:rexrov_base
namespace="$(arg namespace)"
inertial_reference_frame="$(arg inertial_reference_frame)">
<!-- The underwater object plugin is given as an input block parameter to
allow the addition of external models of manipulator units -->
<gazebo>
<plugin name="dave_transient_current_plugin" filename="libdave_transient_current_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>
<tide_oscillation>true</tide_oscillation>
</plugin>
<plugin name="uuv_plugin" filename="libuuv_underwater_object_ros_plugin.so">
<fluid_density>1028.0</fluid_density>
<flow_velocity_topic>hydrodynamics/current_velocity/$(arg namespace)</flow_velocity_topic>
<debug>$(arg debug)</debug>
<!-- Adding the hydrodynamic and hydrostatic parameters for the vehicle-->
<xacro:rexrov_hydro_model namespace="$(arg namespace)"/>
<xacro:oberon7_hydro_model namespace="oberon7"/>
</plugin>
</gazebo>
</xacro:rexrov_base>
<xacro:oberon7 namespace="oberon7" parent="$(arg namespace)/base_link">
<origin xyz="1.3 -0.5 -0.615" rpy="0 0 0"/>
</xacro:oberon7>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/$(arg namespace)</robotNamespace>
<robotParam>/$(arg namespace)/robot_description</robotParam>
</plugin>
</gazebo>
<!-- Joint state publisher plugin -->
<xacro:default_joint_state_publisher namespace="$(arg namespace)" update_rate="50"/>
</robot>