Skip to content

Commit

Permalink
outcomes from the hacking
Browse files Browse the repository at this point in the history
  • Loading branch information
Rezenders committed Jul 1, 2022
1 parent dc03945 commit 5636e3f
Show file tree
Hide file tree
Showing 5 changed files with 17 additions and 16 deletions.
2 changes: 1 addition & 1 deletion dockerfiles/ignition-foxy-hackathon-dev/Dockerfile
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
FROM rezenders/ignition:hackathon
FROM rezenders/ignition:hackathon-nvidia

COPY . /home/docker/tudelft_hackathon_ws/src/tudelft_hackathon/
RUN [ "/bin/bash","-c","export MAKEFLAGS='-j 1' \
Expand Down
4 changes: 2 additions & 2 deletions launch/bluerov_bringup.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ def generate_launch_description():

agent_node = Node(
package='tudelft_hackathon',
executable='bluerov_agent.py',
executable='potential_avoidance.py',
output='screen'
)

Expand Down Expand Up @@ -102,7 +102,7 @@ def generate_launch_description():
package='ping360_sonar',
executable='ping360_node',
parameters=[{
'angle_sector' : 180,
'angle_sector' : 90,
'connection_type': 'udp',
'udp_address': '192.168.2.2',
'udp_port': 9092,
Expand Down
2 changes: 1 addition & 1 deletion launch/bluerov_bringup_no_ign.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ def generate_launch_description():

agent_node = Node(
package='tudelft_hackathon',
executable='bluerov_agent.py',
executable='potential_avoidance.py',
output='screen'
)

Expand Down
17 changes: 9 additions & 8 deletions scripts/potential_avoidance.py
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
from mavros_wrapper.ardusub_wrapper import *

def laser_scan_cb(msg, ardusub):
forward_speed = 0.3 # Maximum forward velocity
forward_speed = 1 # Maximum forward velocity

# TODO: Do something with the sonar msg in order to make the robot not
# crash into the walls
Expand Down Expand Up @@ -42,35 +42,36 @@ def laser_scan_cb(msg, ardusub):
# set some gains
k_p = 1/sum_potentials_angles
# k_p = 1/sum_potentials_x
k_phi = -0.5
k_phi = -2

# Function for computing the new velocity vector
potential_velocity(forward_speed,(p),k_p,k_phi)

def potential_velocity(max_vel,p,K_p,K_phi):
"""
This function sends velocity commands to ardusub according to
the maximum velocity set for the robot
This function sends velocity commands to ardusub according to
the maximum velocity set for the robot
and a potential repulsive field generated by an obstacle
Parameters:
-max_vel: maximum forward velocity (without obstacles)
-p: (px,py) values generated by the potential field in the x and y axis, respectively
-K_p: gain that regulates linear velocity
-K_phi: gain that regulates angular velocity
"""
p_x,p_y = p
forward_vel = max_vel - K_p * p_x
# compute the angle between linear velocity and vy generated by potential obstacles
yaw_vel = K_phi*np.arctan(float(- K_p * p_y/forward_vel))

# Write velocities in channels
# The previous values should be between -1 and 1.
# The previous values should be between -1 and 1.
ardusub.toogle_rc_override(True) # start overriding RC
ardusub.set_rc_override_channels(forward=forward_vel, yaw = yaw_vel) # set values to override
print("forward_vel : ",forward_vel)
print("yaw_vel : ",yaw_vel)
print("kp : ",K_p)

if __name__ == '__main__':
print("Starting wall avoidance. Let's swim!")
Expand Down Expand Up @@ -106,7 +107,7 @@ def potential_velocity(max_vel,p,K_p,K_phi):

# Sonar subscriber
laser_subscriber = ardusub.create_subscription(
LaserScan, '/scan', (lambda msg: laser_scan_cb(msg, ardusub)), 10)
LaserScan, '/scan', (lambda msg: laser_scan_cb(msg, ardusub)), 20)

rate = ardusub.create_rate(2)
try:
Expand Down
8 changes: 4 additions & 4 deletions scripts/random_wall_avoidance.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,9 @@
from mavros_wrapper.ardusub_wrapper import *

def laser_scan_cb(msg, ardusub):
min_distance = 1.25
min_distance = 1.5
yaw_speed = 0.3
forward_speed = 0.12
forward_speed = 0.15
allGreater = True
for scan in msg.ranges:
if scan < min_distance:
Expand All @@ -23,7 +23,7 @@ def laser_scan_cb(msg, ardusub):
yaw=_yaw_speed)
break
if allGreater:
ardusub.set_rc_override_channels(throttle=0, pitch=0, forward=forward_speed)
ardusub.set_rc_override_channels(forward=forward_speed)


if __name__ == '__main__':
Expand Down Expand Up @@ -53,7 +53,7 @@ def laser_scan_cb(msg, ardusub):
print("Initializing mission")

ardusub.toogle_rc_override(True)
ardusub.set_rc_override_channels(throttle=0.0, pitch=0.0, forward=0.12)
ardusub.set_rc_override_channels(forward=0.35)

laser_subscriber = ardusub.create_subscription(
LaserScan, '/scan', (lambda msg: laser_scan_cb(msg, ardusub)), 10)
Expand Down

0 comments on commit 5636e3f

Please sign in to comment.