Skip to content

Commit 5636e3f

Browse files
committed
outcomes from the hacking
1 parent dc03945 commit 5636e3f

File tree

5 files changed

+17
-16
lines changed

5 files changed

+17
-16
lines changed

dockerfiles/ignition-foxy-hackathon-dev/Dockerfile

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
FROM rezenders/ignition:hackathon
1+
FROM rezenders/ignition:hackathon-nvidia
22

33
COPY . /home/docker/tudelft_hackathon_ws/src/tudelft_hackathon/
44
RUN [ "/bin/bash","-c","export MAKEFLAGS='-j 1' \

launch/bluerov_bringup.launch.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ def generate_launch_description():
6565

6666
agent_node = Node(
6767
package='tudelft_hackathon',
68-
executable='bluerov_agent.py',
68+
executable='potential_avoidance.py',
6969
output='screen'
7070
)
7171

@@ -102,7 +102,7 @@ def generate_launch_description():
102102
package='ping360_sonar',
103103
executable='ping360_node',
104104
parameters=[{
105-
'angle_sector' : 180,
105+
'angle_sector' : 90,
106106
'connection_type': 'udp',
107107
'udp_address': '192.168.2.2',
108108
'udp_port': 9092,

launch/bluerov_bringup_no_ign.launch.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ def generate_launch_description():
6565

6666
agent_node = Node(
6767
package='tudelft_hackathon',
68-
executable='bluerov_agent.py',
68+
executable='potential_avoidance.py',
6969
output='screen'
7070
)
7171

scripts/potential_avoidance.py

100644100755
+9-8
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@
1111
from mavros_wrapper.ardusub_wrapper import *
1212

1313
def laser_scan_cb(msg, ardusub):
14-
forward_speed = 0.3 # Maximum forward velocity
14+
forward_speed = 1 # Maximum forward velocity
1515

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

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

5050
def potential_velocity(max_vel,p,K_p,K_phi):
5151
"""
52-
This function sends velocity commands to ardusub according to
53-
the maximum velocity set for the robot
52+
This function sends velocity commands to ardusub according to
53+
the maximum velocity set for the robot
5454
and a potential repulsive field generated by an obstacle
5555
Parameters:
5656
5757
-max_vel: maximum forward velocity (without obstacles)
5858
-p: (px,py) values generated by the potential field in the x and y axis, respectively
5959
-K_p: gain that regulates linear velocity
6060
-K_phi: gain that regulates angular velocity
61-
61+
6262
"""
6363
p_x,p_y = p
6464
forward_vel = max_vel - K_p * p_x
6565
# compute the angle between linear velocity and vy generated by potential obstacles
6666
yaw_vel = K_phi*np.arctan(float(- K_p * p_y/forward_vel))
67-
67+
6868
# Write velocities in channels
69-
# The previous values should be between -1 and 1.
69+
# The previous values should be between -1 and 1.
7070
ardusub.toogle_rc_override(True) # start overriding RC
7171
ardusub.set_rc_override_channels(forward=forward_vel, yaw = yaw_vel) # set values to override
7272
print("forward_vel : ",forward_vel)
7373
print("yaw_vel : ",yaw_vel)
74+
print("kp : ",K_p)
7475

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

107108
# Sonar subscriber
108109
laser_subscriber = ardusub.create_subscription(
109-
LaserScan, '/scan', (lambda msg: laser_scan_cb(msg, ardusub)), 10)
110+
LaserScan, '/scan', (lambda msg: laser_scan_cb(msg, ardusub)), 20)
110111

111112
rate = ardusub.create_rate(2)
112113
try:

scripts/random_wall_avoidance.py

+4-4
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,9 @@
1010
from mavros_wrapper.ardusub_wrapper import *
1111

1212
def laser_scan_cb(msg, ardusub):
13-
min_distance = 1.25
13+
min_distance = 1.5
1414
yaw_speed = 0.3
15-
forward_speed = 0.12
15+
forward_speed = 0.15
1616
allGreater = True
1717
for scan in msg.ranges:
1818
if scan < min_distance:
@@ -23,7 +23,7 @@ def laser_scan_cb(msg, ardusub):
2323
yaw=_yaw_speed)
2424
break
2525
if allGreater:
26-
ardusub.set_rc_override_channels(throttle=0, pitch=0, forward=forward_speed)
26+
ardusub.set_rc_override_channels(forward=forward_speed)
2727

2828

2929
if __name__ == '__main__':
@@ -53,7 +53,7 @@ def laser_scan_cb(msg, ardusub):
5353
print("Initializing mission")
5454

5555
ardusub.toogle_rc_override(True)
56-
ardusub.set_rc_override_channels(throttle=0.0, pitch=0.0, forward=0.12)
56+
ardusub.set_rc_override_channels(forward=0.35)
5757

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

0 commit comments

Comments
 (0)