Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
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
60 changes: 60 additions & 0 deletions examples/dave_demo_launch/launch/dave_Santorini_demo.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
<?xml version="1.0"?>
<launch>
<arg name="gui" default="true"/>
<arg name="paused" default="false"/>
<arg name="world_name" default="$(find dave_worlds)/worlds/dave_Santorini.world"/>
<arg name="namespace" default="rexrov"/>
<arg name="set_timeout" default="false"/>
<arg name="timeout" default="0.0"/>
<arg name="velocity_control" default="true"/>
<arg name="joy_id" default="0"/>

<!-- use Gazebo's empty_world.launch with dave_ocean_waves.world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world_name)"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
<arg name="verbose" value="false"/>
</include>

<!-- use ned frame north east down -->
<include file="$(find uuv_assistants)/launch/publish_world_ned_frame.launch"/>

<!-- timeout -->
<group if="$(arg set_timeout)">
<include file="$(find uuv_assistants)/launch/set_simulation_timer.launch">
<arg name="timeout" value="$(arg timeout)"/>
</include>
</group>

<!-- rexrov robot with oberon7 arm -->
<include file="$(find rexrov_description)/launch/upload_rexrov_oberon7.launch">
<arg name="namespace" value="rexrov"/>
<arg name="x" value="1000"/>
<arg name="y" value="1000"/>
<arg name="z" value="-100"/>
<arg name="yaw" value="-1.8"/>
</include>

<!-- Velocity teleop (UUV stays in position when joystick is not used) -->
<include if="$(arg velocity_control)" file="$(find uuv_control_cascaded_pid)/launch/joy_velocity.launch">
<arg name="uuv_name" value="$(arg namespace)" />
<arg name="model_name" value="rexrov" />
<arg name="joy_id" value="$(arg joy_id)"/>
</include>

<!-- joystick control for rexrov and oberon7, no velocity control-->
<include unless="$(arg velocity_control)" file="$(find uuv_control_cascaded_pid)/launch/joy_accel.launch">
<arg name="model_name" value="rexrov"/>
<arg name="joy_id" value="$(arg joy_id)"/>
</include>

<!-- joint control for oberon7 -->
<include file="$(find oberon7_control)/launch/joint_control.launch">
<arg name="uuv_name" value="$(arg namespace)"/>
</include>

</launch>
94 changes: 94 additions & 0 deletions examples/dave_nodes/src/merry_go_round.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
#!/usr/bin/env python
'''
Maneuver the vehicle like merry-go-round

'''

# System imports
import math

# ROS/Gazebo imports
import rospy
import tf
from rosgraph_msgs.msg import Clock

# For GetModelState Service
from gazebo_msgs.srv import SetModelState
from gazebo_msgs.msg import ModelState
from geometry_msgs.msg import Pose, Twist, Transform

class MerryGoRound:

def __init__(self):

# Parse parameters
self.model_name = "rexrov"
self.xCenter = -1400
self.yCenter = -300
self.radius = 3000
self.depth = 0
self.angularSpeed = 50

# Wait for ROS init
self.t0 = rospy.get_time()
while self.t0 < 0.01:
rospy.logwarn("Waiting for ROS time to be received")
rospy.sleep(0.5)
self.t0 = rospy.get_time()
self.t0_init = self.t0

# Launch
self.launch()

def launch(self):

# Wait for Gazebo services
rospy.loginfo("Starting Merry-Go-Round maneuver...")
rospy.wait_for_service("/gazebo/set_model_state")
wait_for_sim_to_start = rospy.wait_for_message('/clock', Clock)

# Prepare initialization SetModelState service
self.set_model_srv = rospy.ServiceProxy("/gazebo/set_model_state", SetModelState)

rospy.loginfo("Vehicle will be maneuvered to rotate with (" \
+ repr(self.xCenter) + "," + repr(self.yCenter) + ") with radius of " + repr(self.radius) \
+ " [m] for " + repr(self.angularSpeed) + " [deg/sim_sec] angular speed at " + repr(self.depth) \
+ " [m] depth")

def maneuver(self):

# Timing
now = rospy.get_time()
dt = now - self.t0
if dt < 1.0e-5:
# rospy.logwarn("Timestep is too small (%f) - skipping this update"
# %dt)
return
self.t0 = now

# Generate ModelState msg
pose = Pose()
pose.position.x = self.xCenter + self.radius*math.sin(now*self.angularSpeed/180.0*math.pi)
pose.position.y = self.yCenter + self.radius*math.cos(now*self.angularSpeed/180.0*math.pi)
pose.position.z = self.depth

# meneuver
self.set_model_srv(ModelState(self.model_name, pose, Twist(), "world"))

if __name__ == '__main__':

# Start node
rospy.init_node('merry_go_round')
MerryGoRound = MerryGoRound()

# Update rate
update_rate = rospy.get_param('~update_rate', 20.0)

# Spin
r = rospy.Rate(update_rate)
try:
while not rospy.is_shutdown():
MerryGoRound.maneuver()
r.sleep()
except rospy.ROSInterruptException:
pass
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
material Bathymetry/Santorini
{
technique
{
pass
{
ambient 0.5 0.5 0.5 1.0
diffuse 0.5 0.5 0.5 1.0
specular 0.2 0.2 0.2 1.0 12.5

texture_unit
{
texture ../textures/Santorini.R_25.317_25.489_36.337_36.479.epsg3857.texture.png
scale 1 1
}
}
}
}
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Empty file.
Loading