Skip to content

Commit

Permalink
Moving all ROS1 simulator changes from robosub back here (#3)
Browse files Browse the repository at this point in the history
  • Loading branch information
AVSurfer123 authored Nov 9, 2020
1 parent f685e92 commit 8ff7c6f
Show file tree
Hide file tree
Showing 24 changed files with 144 additions and 26 deletions.
10 changes: 10 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,16 @@

This will set up Underwater Robotics @ Berkeley's team simulator.

# VMWare Instructions

Install VMWare Workstation Pro/Fusion with Berkeley's license from here https://software.berkeley.edu/vmware. Then download a base Ubuntu 16 desktop image from https://releases.ubuntu.com/16.04/. Now create a new virtual machine and give the Ubuntu image as the disc file. Now you can run the VM and set it up with your username and password.

After you first log in, open up a terminal with Ctrl+Alt+T or search for it and then get our code with

git clone https://github.com/berkeleyauv/robosub.git

Now you can follow the commands in the Dockerfile to install ROS, Gazebo, and the UUV simulator.

# Mac Instructions

## --Installation--
Expand Down
64 changes: 45 additions & 19 deletions descriptions/urab_sub_description/urdf/urab_sub_actuators.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<!-- Copyright (c) 2016 The UUV Simulator Authors.
All rights reserved.
Contributed by Kristoffer Rakstad Solberg,
Contributed by Kristoffer Rakstad Solberg,
Student2019 Manta AUV, Vortex NTNU. -->


Expand All @@ -16,23 +16,23 @@
<!-- Thruster joint and link snippet -->
<!-- Time constant for thruster dynamics: rpm = K / (Ts + 1)
<rotorConstant> T200, 12V for a 2nd order curve fit: tau = gain * abs(x)*x -->
<xacro:macro name="thruster_macro"
<xacro:macro name="thruster_macro"
params="namespace thruster_id *origin">
<!-- Macro definition here:
<!-- Macro definition here:
https://github.com/uuvsimulator/uuv_simulator/blob/5684de4827729f163f118cdc3a841011ef25ed8d/uuv_gazebo_plugins/uuv_gazebo_ros_plugins/urdf/thruster_snippets.xacro#L135 -->
<xacro:thruster_module_first_order_basic_fcn_macro
namespace="${namespace}"
thruster_id="${thruster_id}"
mesh_filename="${prop_mesh_file_cw}"
dyn_time_constant="0.2"
rotor_constant="0.000004">
dyn_time_constant="0.2"
rotor_constant="0.000004">
<xacro:insert_block name="origin"/>
</xacro:thruster_module_first_order_basic_fcn_macro>
</xacro:macro>

<!-- Time constant for thruster dynamics: rpm = K / (Ts + 1)
<rotorConstant> T200, 12V for a 2nd order curve fit: tau = gain * abs(x)*x -->
<xacro:macro name="thruster_macro_ccw"
<xacro:macro name="thruster_macro_ccw"
params="namespace thruster_id *origin">
<xacro:thruster_module_first_order_basic_fcn_macro
namespace="${namespace}"
Expand All @@ -47,36 +47,62 @@
<!-- Thrusters probably advertise to these topics:
https://github.com/uuvsimulator/uuv_simulator/blob/5684de4827729f163f118cdc3a841011ef25ed8d/uuv_gazebo_plugins/uuv_gazebo_ros_plugins/src/ThrusterROSPlugin.cc#L153-L168 -->

<!-- Top thrusters -->
<!-- Top thrusters -->

<xacro:thruster_macro namespace="${namespace}" thruster_id="0"> <!-- heave back left prop up-->
<xacro:thruster_macro namespace="${namespace}" thruster_id="0">
<origin xyz="-0.12070 0.12070 0" rpy="0 -1.5707963268 0"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="1"> <!-- heave bacl right prop up-->
<xacro:thruster_macro namespace="${namespace}" thruster_id="1">
<origin xyz="-0.12070 -0.12070 0" rpy="0 -1.5707963268 0"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="2"> <!-- heave front left prop up-->
<xacro:thruster_macro namespace="${namespace}" thruster_id="2">
<origin xyz="0.12070 0.12070 0" rpy="0 -1.5707963268 0"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="3"> <!-- heave front right prop up-->
<xacro:thruster_macro namespace="${namespace}" thruster_id="3">
<origin xyz="0.12070 -0.12070 0" rpy="0 -1.5707963268 0"/>
</xacro:thruster_macro>

<!-- <xacro:thruster_macro namespace="${namespace}" thruster_id="0">
<origin xyz="-0.143825 0.280455 0.230245" rpy="0 -1.5707963268 0"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="1">
<origin xyz="-0.143825 -0.280455 0.230245" rpy="0 -1.5707963268 0"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="2">
<origin xyz="0.143825 0.280455 0.230245" rpy="0 -1.5707963268 0"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="3">
<origin xyz="0.143825 -0.280455 0.230245" rpy="0 -1.5707963268 0"/>
</xacro:thruster_macro> -->

<!-- Front thrusters -->

<xacro:thruster_macro namespace="${namespace}" thruster_id="6"> <!-- lat front left-->
<origin xyz="0.20506 0.20506 0" rpy="${0*d2r} ${0*d2r} ${135*d2r}"/>
<xacro:thruster_macro namespace="${namespace}" thruster_id="6">
<origin xyz="0.20506 0.20506 0" rpy="${0*d2r} ${0*d2r} ${135*d2r}"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="7"> <!-- lat front right -->
<xacro:thruster_macro namespace="${namespace}" thruster_id="7">
<origin xyz="0.20506 -0.20506 0" rpy="${0*d2r} ${0*d2r} ${-135*d2r}"/>
</xacro:thruster_macro>

<!-- <xacro:thruster_macro namespace="${namespace}" thruster_id="6">
<origin xyz="0.192247 0.286933 0.0721539" rpy="${0*d2r} ${0*d2r} ${135*d2r}"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="7">
<origin xyz="0.192247 -0.286933 0.0721539" rpy="${0*d2r} ${0*d2r} ${-135*d2r}"/>
</xacro:thruster_macro> -->

<!-- Back thrusters -->
<xacro:thruster_macro namespace="${namespace}" thruster_id="4"> <!-- lat back left-->
<origin xyz="-0.20506 0.20506 0" rpy="${0*d2r} ${0*d2r} ${45*d2r}"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="5"> <!-- lat back right -->
<origin xyz="-0.20506 -0.20506 0" rpy="${0*d2r} ${0*d2r} ${-45*d2r}"/>
</xacro:thruster_macro>

<xacro:thruster_macro namespace="${namespace}" thruster_id="4"> <!-- lat back left-->
<origin xyz="-0.20506 0.20506 0" rpy="${0*d2r} ${0*d2r} ${45*d2r}"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="5"> <!-- lat back right -->
<origin xyz="-0.20506 -0.20506 0" rpy="${0*d2r} ${0*d2r} ${-45*d2r}"/>
<!-- <xacro:thruster_macro namespace="${namespace}" thruster_id="4">
<origin xyz="-0.192247 0.286933 0.0721539" rpy="${0*d2r} ${0*d2r} ${45*d2r}"/>
</xacro:thruster_macro>
<xacro:thruster_macro namespace="${namespace}" thruster_id="5">
<origin xyz="-0.192247 -0.286933 0.0721539" rpy="${0*d2r} ${0*d2r} ${-45*d2r}"/>
</xacro:thruster_macro> -->
</robot>
6 changes: 3 additions & 3 deletions descriptions/vortex_descriptions/launch/robosub_world.launch
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
<?xml version="1.0" ?>

<!--
<!--
Base code written by Kristoffer Rakstad Solberg, Student
Copyright (c) 2019 Manta AUV, Vortex NTNU.
All rights reserved. -->

<launch>
<arg name="gui" default="true"/>
<arg name="paused" default="false"/>
<arg name="paused" default="false"/> <!--default should be false for the robot to move-->
<arg name="set_timeout" default="false"/>
<arg name="timeout" default="0.0"/>

Expand Down Expand Up @@ -47,7 +47,7 @@
pose:
position: [0, -50, -10]
east:
plane: [100, 0.1, 20]
plane: [100, 0.1, 20]
pose:
position: [0, 50, -10]
</rosparam>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
<?xml version="1.0" ?>

<!--
<!--
Base code written by Kristoffer Rakstad Solberg, Student
Copyright (c) 2019 Manta AUV, Vortex NTNU.
All rights reserved. -->

<launch>
<include file="$(find vortex_descriptions)/launch/robosub_world.launch"/>
<include file="$(find urab_sub_description)/launch/upload_urab_sub.launch"/>
<include file="$(find urab_sub_thruster_manager)/launch/thruster_manager.launch"/>
<include file="$(find vortex_descriptions)/launch/robosub_world.launch" pass_all_args="true"/>
<include file="$(find urab_sub_description)/launch/upload_urab_sub.launch" pass_all_args="true"/>
<include file="$(find urab_sub_thruster_manager)/launch/thruster_manager.launch"/>
</launch>
61 changes: 61 additions & 0 deletions scripts/read_cameras.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
import rospy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge

class ImageListener:
""" Abstract class. Subscribes to ROS Image messages. Used for getting camera image data
from the simulator and converting it for OpenCV. """

def callback(self, img_msg):
bridge = CvBridge()
# Stores as a BGR array for OpenCV.
cv_image = bridge.imgmsg_to_cv2(img_msg, desired_encoding='bgr8')
self.images.append(cv_image)

def get_images(self, time):
self.images = []
rospy.sleep(time) # time is in seconds
return self.images

def get_images_forever(self):
self.images = []
rospy.spin()
return self.images

class FrontCameraListener(ImageListener):
""" Gets image data from the front camera. """
def __init__(self):
self.subscr = rospy.Subscriber("/urab_sub/urab_sub/camerafront/camera_image",
Image, self.callback)

class UnderCameraListener(ImageListener):
""" Gets image data from the bottom camera. """
def __init__(self):
self.subscr = rospy.Subscriber("/urab_sub/urab_sub/cameraunder/camera_image",
Image, self.callback)

if __name__ == '__main__':
# not sure if this should be moved into the ImageListener class
rospy.init_node('img_listener', anonymous=True)

front_listen = FrontCameraListener()
imgs = front_listen.get_images(1.0)

print "FRONT CAMERA"
print "ImageListener.get_images() has type " + str(type(imgs))
print "Length of image list: " + str(len(imgs))
print "The first image has type " + str(type(imgs[0]))
print "The first image has dimensions " + str(imgs[0].shape)
print "Print out the first image:"
print imgs[0]

under_listen = UnderCameraListener()
imgs = under_listen.get_images(1.0)

print "\n\nBOTTOM CAMERA"
print "ImageListener.get_images() has type " + str(type(imgs))
print "Length of image list: " + str(len(imgs))
print "The first image has type " + str(type(imgs[0]))
print "The first image has dimensions " + str(imgs[0].shape)
print "Print out the first image:"
print imgs[0]
21 changes: 21 additions & 0 deletions scripts/show_images.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
import rospy
import numpy as np
import cv2
import read_cameras

def display_camera_images(listener, time, window_name="video"):
"""Displays camera images received from an ImageListener object, which
gets video data for the specified amount of time, in seconds."""
imgs = listener.get_images(1.0)
for frame in imgs:
cv2.imshow(window_name, frame)
# you need to hold a key to see the video progress. Press q to quit.
if cv2.waitKey(0) & 0xFF == ord('q'):
break
cv2.destroyAllWindows()


if __name__ == '__main__':
rospy.init_node('img_listener', anonymous=True)
front_listen = read_cameras.FrontCameraListener()
display_camera_images(front_listen, 1, "front camera")

0 comments on commit 8ff7c6f

Please sign in to comment.