Skip to content
GitLab
Menu
Projects
Groups
Snippets
Loading...
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
U2IS
aquanaute
Commits
bb89241c
Commit
bb89241c
authored
Jul 13, 2020
by
Ricardo Rico Uribe
Browse files
fixed plugin - error in topic advertisements
parent
4120d958
Changes
8
Hide whitespace changes
Inline
Side-by-side
README.md
View file @
bb89241c
...
...
@@ -10,7 +10,7 @@ Repository to simulate the Aquanaute boat in maritime conditions such as wind an
## Usage
### modify wind and waves
in the ocean.world.xacro
you have found in
/vrx_gazebo/worlds
in the ocean.world.xacro
(
/vrx_gazebo/worlds
) you have
```
xml
<!--Waves-->
<xacro:include
filename=
"$(find wave_gazebo)/world_models/ocean_waves/model.xacro"
/>
...
...
@@ -40,8 +40,15 @@ in the workspace run the command at the beginning (and every time you change a p
then launch the file you created
```
bash
roslaunch aquanaute_gazebo
world.launch
roslaunch aquanaute_gazebo
aquanaute.launch testing:
=
false
```
this parameter can be changed to true to deactivate the plugins from vrx (the world will be changed to an empty world)
on another terminal (inside the ardupilot root) run
```
bash
./Tools/autotest/sim_vehicle.py
--vehicle
=
Rover
--frame
=
sailboat-motor
--map
--console
--location
=
Xlac
```
## Author
Ricardo RICO URIBE intern at U2IS in the summer of 2020
...
...
aquanaute_description/launch/description.launch
View file @
bb89241c
...
...
@@ -5,7 +5,7 @@
<!-- send fake joint values -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="
fals
e"/>
<param name="use_gui" value="
tru
e"/>
</node>
<!-- Combine joint values -->
...
...
aquanaute_description/models/meshes/Motor.stl
View file @
bb89241c
No preview for this file type
aquanaute_description/models/meshes/Propeller.stl
0 → 100644
View file @
bb89241c
File added
aquanaute_description/urdf/aquanaute_description.urdf.xacro
View file @
bb89241c
...
...
@@ -128,24 +128,30 @@
<geometry>
<mesh
filename=
"package://aquanaute_description/models/meshes/Motor.stl"
/>
</geometry>
<material
name=
"
purple
"
/>
<material
name=
"
black
"
/>
</visual>
</link>
<link
name=
"propeller_link"
>
<inertial>
<origin
xyz=
"-0.034 0 0"
rpy=
"0 0 0"
/>
<mass
value=
"0.233"
/>
<inertia
ixx=
"1.441e-04"
ixy=
"4.406e-09"
ixz=
"0.00"
iyy=
"1.760e-04"
iyz=
"2.373e-06"
izz=
"1.961e-04"
/>
</inertial>
<collision>
<origin
xyz=
"0 0 0"
rpy=
"0 0 0"
/>
<geometry>
<
cylinder
radius=
"0.05"
length=
"0.04
"
/>
<
mesh
filename=
"package://aquanaute_description/models/meshes/Propeller.stl
"
/>
</geometry>
</collision>
<visual>
<origin
rpy=
"0 0 0"
xyz=
"0 0 0"
/>
<origin
rpy=
"0
.0
0 0"
xyz=
"0 0 0"
/>
<geometry>
<
cylinder
radius=
"0.04"
length=
"0.05
"
/>
<
mesh
filename=
"package://aquanaute_description/models/meshes/Propeller.stl
"
/>
</geometry>
<material
name=
"bl
ack
"
/>
<material
name=
"bl
ue
"
/>
</visual>
</link>
...
...
@@ -168,7 +174,7 @@
<geometry>
<mesh
filename=
"package://aquanaute_description/models/meshes/sensor_frame.stl"
/>
</geometry>
<material
name=
"
cyan
"
/>
<material
name=
"
white
"
/>
</visual>
</link>
...
...
@@ -206,15 +212,15 @@
<child
link=
"motor_link"
/>
<origin
xyz=
"-0.91 0.0 -0.09"
rpy=
"0 0 0"
/>
<axis
xyz=
"0 0 1"
/>
<limit
effort=
"
-
1"
velocity=
"
-
1"
lower=
"-0.9"
upper=
"0.9"
/>
<limit
effort=
"1"
velocity=
"1"
lower=
"-0.9"
upper=
"0.9"
/>
</joint>
<joint
name=
"propeller_motor_joint"
type=
"
fixed
"
>
<joint
name=
"propeller_motor_joint"
type=
"
revolute
"
>
<parent
link=
"motor_link"
/>
<child
link=
"propeller_link"
/>
<origin
xyz=
"-0.5 0 0.42"
rpy=
"0
1.57
0"
/>
<axis
xyz=
"0 0
1
"
/>
<limit
effort=
"
-
1"
velocity=
"
-
1"
lower=
"-1e+16"
upper=
"1e+16"
/>
<origin
xyz=
"-0.
26
5 0
-
0.42"
rpy=
"0
0
0"
/>
<axis
xyz=
"
1
0 0"
/>
<limit
effort=
"1"
velocity=
"1"
lower=
"-1e+16"
upper=
"1e+16"
/>
</joint>
<joint
name=
"sensor_frame_platform_joint"
type=
"fixed"
>
...
...
@@ -226,6 +232,6 @@
<joint
name=
"imu_platform_joint"
type=
"fixed"
>
<parent
link=
"platform_link"
/>
<child
link=
"imu_link"
/>
<origin
xyz=
"0 0 0.
1
"
rpy=
"0 0 0"
/>
<origin
xyz=
"0 0 0.
02
"
rpy=
"0 0 0"
/>
</joint>
</robot>
aquanaute_gazebo/launch/
world
.launch
→
aquanaute_gazebo/launch/
aquanaute
.launch
View file @
bb89241c
<?xml version="1.0"?>
<launch>
<env
name=
"ROSCONSOLE_CONFIG_FILE"
value=
"$(find vrx_gazebo)/config/custom_rosconsole.conf"
/>
<!-- Gazebo world to load -->
<arg
name=
"world"
default=
"$(find vrx_gazebo)/worlds/ocean.world"
/>
<!-- If true, run gazebo GUI -->
<arg
name=
"gui"
default=
"true"
/>
<!-- If true, run gazebo in verbose mode -->
...
...
@@ -14,10 +13,12 @@
<!-- Start in a default namespace -->
<arg
name=
"namespace"
default=
"aquanaute"
/>
<arg
name=
"testing"
default=
"false"
/>
<!-- Initial USV location and attitude-->
<arg
name=
"x"
default=
"0"
/>
<arg
name=
"y"
default=
"0"
/>
<arg
name=
"z"
default=
"0.1"
/>
<arg
name=
"z"
default=
"0.5"
if=
"$(arg testing)"
/>
<arg
name=
"z"
default=
"0.1"
unless=
"$(arg testing)"
/>
<arg
name=
"P"
default=
"0"
/>
<arg
name=
"R"
default=
"0"
/>
<arg
name=
"Y"
default=
"0"
/>
...
...
@@ -26,7 +27,8 @@
<!-- Start Gazebo with the world file -->
<include
file=
"$(find gazebo_ros)/launch/empty_world.launch"
>
<arg
name=
"world_name"
value=
"$(arg world)"
/>
<arg
name=
"world_name"
value=
"$(find aquanaute_gazebo)/worlds/test.world"
if=
"$(arg testing)"
/>
<arg
name=
"world_name"
value=
"$(find vrx_gazebo)/worlds/ocean.world"
unless=
"$(arg testing)"
/>
<arg
name=
"verbose"
value=
"$(arg verbose)"
/>
<arg
name=
"paused"
value=
"$(arg paused)"
/>
<arg
name=
"use_sim_time"
value=
"true"
/>
...
...
@@ -37,7 +39,8 @@
<!-- Load robot model -->
<arg
name=
"urdf"
default=
"$(find aquanaute_gazebo)/urdf/aquanaute_gazebo.urdf.xacro"
/>
<param
name=
"$(arg namespace)/robot_description"
command=
"$(find xacro)/xacro '$(arg urdf)'"
/>
<param
name=
"$(arg namespace)/robot_description"
command=
"$(find xacro)/xacro '$(arg urdf)'
testing:=$(arg testing)"
/>
<!-- Spawn model in Gazebo, script depending on non_competition_mode -->
<node
name=
"spawn_model"
pkg=
"gazebo_ros"
type=
"spawn_model"
args=
"-x $(arg x) -y $(arg y) -z $(arg z)
...
...
aquanaute_gazebo/launch/test.launch
deleted
100644 → 0
View file @
4120d958
<?xml version="1.0"?>
<launch>
<!-- Gazebo world to load -->
<arg
name=
"world"
default=
"$(find aquanaute_gazebo)/worlds/test.world"
/>
<!-- If true, run gazebo GUI -->
<arg
name=
"gui"
default=
"true"
/>
<!-- If true, run gazebo in verbose mode -->
<arg
name=
"verbose"
default=
"true"
/>
<!-- If true, start in paused state -->
<arg
name=
"paused"
default=
"false"
/>
<!-- Set various other gazebo arguments-->
<arg
name=
"extra_gazebo_args"
default=
""
/>
<!-- Start in a default namespace -->
<arg
name=
"namespace"
default=
"aquanaute"
/>
<!-- Initial USV location and attitude-->
<arg
name=
"x"
default=
"0"
/>
<arg
name=
"y"
default=
"0"
/>
<arg
name=
"z"
default=
"0.5"
/>
<arg
name=
"P"
default=
"0"
/>
<arg
name=
"R"
default=
"0"
/>
<arg
name=
"Y"
default=
"0"
/>
<!-- Start Gazebo with the world file -->
<include
file=
"$(find gazebo_ros)/launch/empty_world.launch"
>
<arg
name=
"world_name"
value=
"$(arg world)"
/>
<arg
name=
"verbose"
value=
"$(arg verbose)"
/>
<arg
name=
"paused"
value=
"$(arg paused)"
/>
<arg
name=
"use_sim_time"
value=
"true"
/>
<arg
name=
"gui"
value=
"$(arg gui)"
/>
<arg
name=
"enable_ros_network"
value=
"true"
/>
</include>
<!-- Load robot model -->
<arg
name=
"urdf"
default=
"$(find aquanaute_gazebo)/urdf/aquanaute_gazebo.urdf.xacro"
/>
<param
name=
"$(arg namespace)/robot_description"
command=
"$(find xacro)/xacro '$(arg urdf)'"
/>
<!-- Spawn model in Gazebo, script depending on non_competition_mode -->
<node
name=
"spawn_model"
pkg=
"gazebo_ros"
type=
"spawn_model"
args=
"-x $(arg x) -y $(arg y) -z $(arg z)
-R $(arg R) -P $(arg P) -Y $(arg Y)
-urdf -param $(arg namespace)/robot_description -model aquanaute"
/>
</launch>
aquanaute_gazebo/urdf/aquanaute_gazebo.urdf.xacro
View file @
bb89241c
<?xml version="1.0"?>
<!-- Basic WAM-V with gazebo plugins for dynamics -->
<robot
xmlns:xacro=
"http://ros.org/wiki/xacro"
>
<!-- Include macros for dynamics plugins
<xacro:include filename="$(find aquanaute_gazebo)/urdf/macros.xacro" /> -->
<xacro:arg
name=
"testing"
default=
"false"
/>
<!-- Include macros for dynamics plugins -->
<xacro:unless
value=
"$(arg testing)"
>
<xacro:include
filename=
"$(find aquanaute_gazebo)/urdf/macros.xacro"
/>
</xacro:unless>
<!-- Defines the base vehicle -->
<xacro:include
filename=
"$(find aquanaute_description)/urdf/aquanaute_description.urdf.xacro"
/>
<!--
Defines the sim plugin
s-->
<!--
Gazebo Reference
s-->
<gazebo
reference=
"base_link"
>
<kp>
100000.0
</kp>
...
...
@@ -49,11 +53,11 @@
</gazebo>
<gazebo
reference=
"propeller_link"
>
<kp>
1
00000
.0
</kp>
<kd>
1
00000
.0
</kd>
<mu1>
1
0
.0
</mu1>
<mu2>
1
0
.0
</mu2>
<material>
Gazebo/Bl
ack
</material>
<kp>
1.0
</kp>
<kd>
1.0
</kd>
<mu1>
1.0
</mu1>
<mu2>
1.0
</mu2>
<material>
Gazebo/Bl
ue
</material>
</gazebo>
<gazebo
reference=
"sensor_frame_link"
>
...
...
@@ -64,16 +68,15 @@
<material>
Gazebo/White
</material>
</gazebo>
<gazebo>
<link
name=
"imu_link"
>
<sensor
name=
"imu_sensor"
type=
"imu"
>
<pose>
0 0 0 3.141593 0 0
</pose>
<always_on>
1
</always_on>
<update_rate>
1000.0
</update_rate>
</sensor>
</link>
</gazebo>
<gazebo
reference=
"imu_link"
>
<sensor
name=
"imu_sensor"
type=
"imu"
>
<pose>
0 0 0 3.141593 0 0
</pose>
<always_on>
1
</always_on>
<update_rate>
1000.0
</update_rate>
</sensor>
<material>
Gazebo/Yellow
</material>
</gazebo>
<!-- * * * GAZEBO Plugins * * * -->
<gazebo>
<plugin
name=
"ardupilot_plugin"
filename=
"libArduPilotPlugin.so"
>
...
...
@@ -104,23 +107,25 @@
<cmd_min>
-1
</cmd_min>
<jointName>
aquanaute::motor_platform_joint
</jointName>
</control>
<control
channel=
"1"
>
<multiplier>
1
</multiplier>
<offset>
-0.5
</offset>
<type>
VELOCITY
</type>
<offset>
-0.5
</offset>
<p_gain>
1
</p_gain>
<i_gain>
0
</i_gain>
<d_gain>
0
</d_gain>
<i_max>
0
</i_max>
<i_min>
0
</i_min>
<cmd_max>
1
</cmd_max>
<cmd_min>
-1
</cmd_min>
<cmd_max>
1
0
</cmd_max>
<cmd_min>
-1
0
</cmd_min>
<jointName>
aquanaute::propeller_motor_joint
</jointName>
<multiplier>
70
</multiplier>
</control>
</plugin>
</gazebo>
<!-- Attach hydrodynamics plugin
<xacro:usv_dynamics_gazebo name="aquanaute_dynamics_plugin"/> -->
<!-- Attach hydrodynamics plugin -->
<xacro:unless
value=
"$(arg testing)"
>
<xacro:usv_dynamics_gazebo
name=
"aquanaute_dynamics_plugin"
/>
</xacro:unless>
</robot>
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment