Skip to content

Commit

Permalink
Changed some dimensions and configs
Browse files Browse the repository at this point in the history
  • Loading branch information
Jenny Wang committed May 3, 2020
1 parent 8bc425e commit e4572f3
Show file tree
Hide file tree
Showing 6 changed files with 74 additions and 17 deletions.
9 changes: 9 additions & 0 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -16,5 +16,14 @@ run: ## Run container
docker run -it --rm -p 6080:80 -v="/tmp/.ros/:/root/.ros/" \
-v=$$(pwd):/root/catkin_ws/src/ --name=${APP_NAME} ${APP_NAME}

run-more: ## Run container
# Beware if you have less than --cpus cpus on your computer
# Access docker stuff at localhost:6080 (type into your browser)
# Volumes: -v directoryA:directoryB means the stuff stored in directoryB in the docker container
# can also be seen from directoyA on your computer.
# aka the pwd one shares the git repo between the docker container and your computer
docker run -it --rm -p 6080:80 -v="/tmp/.ros/:/root/.ros/" \
-v=$$(pwd):/root/catkin_ws/src/ --cpus=1.5 --name=${APP_NAME} ${APP_NAME}

clean: ## Remove a container, running or not
docker rm $(APP_NAME) -f
Binary file removed descriptions/.DS_Store
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,8 @@ thruster_manager:
thruster_topic_prefix: thrusters/
thruster_topic_suffix: /input
thruster_frame_base: thruster_
max_thrust: 40.0
max_thrust: 51.4 # Nominal forward thrust in Newtons (back is about 40.2)
max_clamp: 16 # Max nominal volts. 20V is maximum
timeout: -1
update_rate: 50

Expand All @@ -22,7 +23,8 @@ thruster_manager:
# You can set the conversion function to be:
conversion_fcn: proportional
conversion_fcn_params:
gain: 0.000004 # <rotorConstant> T200, 12V for a 2nd order curve fit: tau = gain * abs(x)*x
# Not sure if this changes anything??
gain: 0.000004 # <r otorConstant> T200, 12V for a 2nd order curve fit: tau = gain * abs(x)*x

# 1.2) If the conversion function set for the thruster plugins is the following:
# <conversion>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,9 @@ def __init__(self):
self.last_update = rospy.Time.now()

# Subscriber to the wrench to be applied on the UUV
# This package's setup makes it so that the sub should respond to input
# coming from here, but we should probably replace this whole package
# with the controls team's package
self.input_sub = rospy.Subscriber('thruster_manager/input',
Wrench, self.input_callback)

Expand Down
8 changes: 4 additions & 4 deletions descriptions/urab_sub_description/urdf/urab_sub_base.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,11 @@
Vehicle's parameters (remember to enter the model parameters below)
-->
<!-- Mass -->
<xacro:property name="mass" value="30.9"/>
<xacro:property name="mass" value="13"/>
<!-- Describing the dimensions of the vehicle's bounding box: width, length, height -->
<xacro:property name="x_size" value="0.400"/>
<xacro:property name="y_size" value="0.400"/>
<xacro:property name="z_size" value="0.20066"/>
<xacro:property name="x_size" value="0.38449"/>
<xacro:property name="y_size" value="0.460"/>
<xacro:property name="z_size" value="0.286933"/>
<!-- minion_usv_height is not really! It's just for run... We need first calculate the Fossen parameters -->
<!-- Volume -->
<xacro:property name="volume" value="0.0325"/>
Expand Down
65 changes: 54 additions & 11 deletions scripts/test_thruster_power.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,17 +2,60 @@
from std_msgs.msg import Float32
from uuv_gazebo_ros_plugins_msgs.msg import FloatStamped
from random import random
from geometry_msgs.msg import Wrench, WrenchStamped, Vector3

THRUSTER_ID = '0'
THRUSTER_POWER = 1000

rospy.init_node('test_setter')
pub_thrust = rospy.Publisher('/urab_sub/thrusters/' + THRUSTER_ID + '/input', FloatStamped, queue_size=10)
rate = rospy.Rate(1)

while not rospy.is_shutdown():
def get_individual_thruster_publisher(thruster_id='0'):
return rospy.Publisher('/urab_sub/thrusters/' + thruster_id + '/input', FloatStamped, queue_size=10)
def get_individual_thruster_message(power=1):
msg = FloatStamped()
msg.header.stamp = rospy.Time.now()
msg.data = THRUSTER_POWER
pub_thrust.publish(msg)
rate.sleep()
msg.data = power
return msg

def get_thruster_manager_publisher():
return rospy.Publisher('/urab_sub/thruster_manager/input', Wrench, queue_size=10)
def get_thruster_manager_message(fx=1, fy=1, fz=1, tx=1, ty=1, tz=1):
force = Vector3()
force.x = fx
force.y = fy
force.z = fz
torque = Vector3()
torque.x = tx
torque.y = ty
torque.z = tz
msg = Wrench()
msg.force = force
msg.torque = torque
return msg

MODES = ['thruster_manager', 'thrusters_direct']
NUM_THRUSTERS = 8
mode = 1
if __name__ == "__main__":
rospy.init_node('test_setter')

publishers = []
if MODES[mode] == 'thruster_manager':
publishers.append(rospy.Publisher('/urab_sub/thruster_manager/input', Wrench, queue_size=10))
elif MODES[mode] == 'thrusters_direct':
for thruster_id in range(NUM_THRUSTERS):
publishers.append(rospy.Publisher('/urab_sub/thrusters/{}/input'.format(thruster_id), FloatStamped, queue_size=10))

rate = rospy.Rate(1)

while not rospy.is_shutdown():
messages = []
# msg = get_individual_thruster_message(20)
if MODES[mode] == 'thruster_manager':
messages.append(get_thruster_manager_message(1000000000,0,0,1000000000,0,0))
elif MODES[mode] == 'thrusters_direct':
for __ in range(NUM_THRUSTERS):
msg = FloatStamped()
msg.header.stamp = rospy.Time.now()
msg.data = 10
messages.append(msg)

for i in range(len(publishers)):
publishers[i].publish(messages[i])
print('messages', messages)
rate.sleep()

0 comments on commit e4572f3

Please sign in to comment.