Skip to content

Commit

Permalink
Merge pull request #158 from UoA-CARES/chore/clean-up
Browse files Browse the repository at this point in the history
Chore/clean up
  • Loading branch information
emilysteiner71 authored Apr 9, 2024
2 parents 8e3ac96 + 5e749c0 commit 2938b95
Show file tree
Hide file tree
Showing 6 changed files with 17 additions and 38 deletions.
11 changes: 7 additions & 4 deletions src/environments/environments/CarTrackEnvironment.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
import math
import rclpy
import numpy as np
from rclpy import Future
import random
from environment_interfaces.srv import Reset
from environments.F1tenthEnvironment import F1tenthEnvironment
from .termination import has_collided, has_flipped_over
from .util import process_odom, avg_lidar, create_lidar_msg, get_all_goals_and_waypoints_in_multi_tracks
from .util import process_odom, avg_lidar, create_lidar_msg, get_all_goals_and_waypoints_in_multi_tracks, ackermann_to_twist
from .goal_positions import goal_positions
from .waypoints import waypoints
from std_srvs.srv import SetBool
Expand Down Expand Up @@ -133,7 +134,11 @@ def step(self, action):
self.call_step(pause=False)
_, full_state = self.get_observation()

lin_vel, ang_vel = action
lin_vel, steering_angle = action

# TODO: get rid of hard coded wheelbase
ang_vel = ackermann_to_twist(steering_angle, lin_vel, 0.315)

self.set_velocity(lin_vel, ang_vel)

self.sleep()
Expand Down Expand Up @@ -162,8 +167,6 @@ def get_observation(self):
num_points = self.LIDAR_POINTS

reduced_range = avg_lidar(lidar, num_points)

# Get Goal Position

match (self.observation_mode):
case 'no_position':
Expand Down
2 changes: 1 addition & 1 deletion src/f1tenth
18 changes: 2 additions & 16 deletions src/reinforcement_learning/config/sanity_check.yaml
Original file line number Diff line number Diff line change
@@ -1,18 +1,4 @@
sanity_check:
ros__parameters:
environment: 'CarTrack' # CarGoal, CarWall, CarBlock, CarTrack
track: 'austin_track' # track_1, track_2, track_3 -> only applies for CarTrack
max_steps_exploration: 5000
max_steps_training: 1000000
reward_range: 1.0
collision_range: 0.2
# gamma: 0.95
# tau: 0.005
# g: 5
# batch_size: 32
# buffer_size: 1000000
# actor_lr: 0.0001
# critic_lr: 0.001
# max_steps: 10
# step_length: 0.25
# seed: 123
environment: 'CarGoal' # CarGoal, CarWall, CarBlock, CarTrack

10 changes: 5 additions & 5 deletions src/reinforcement_learning/config/test.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,12 @@ test:
ros__parameters:
environment: 'CarTrack'
track: 'multi_track' # track_1, track_2, track_3, multi_track, multi_track_testing -> only applies for CarTrack
number_eval_episodes: 100
number_eval_episodes: 3
max_steps: 3000
actor_path: training_logs/SAC-CarTrack-23_10_25_10:41:10/models/SAC-checkpoint-15000_actor.pht
critic_path: training_logs/SAC-CarTrack-23_10_25_10:41:10/models/SAC-checkpoint-15000_critic.pht
algorithm: 'SAC'
actor_path: training_logs/TD3-CarTrack-24_03_27_16:02:09/models/TD3_actor.pht
critic_path: training_logs/TD3-CarTrack-24_03_27_16:02:09/models/TD3_critic.pht
algorithm: 'TD3'
step_length: 0.1
reward_range: 3.0
reward_range: 3
collision_range: 0.2
observation_mode: 'lidar_only'
2 changes: 1 addition & 1 deletion src/reinforcement_learning/config/train.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,5 +5,5 @@ train:
car_name: 'f1tenth'
algorithm: 'TD3'
g: 1
buffer_size: 50000
buffer_size: 1000000
observation_mode: 'lidar_only'
12 changes: 1 addition & 11 deletions src/reinforcement_learning/launch/sanity_check.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,16 +31,7 @@ def generate_launch_description():
launch_description_source=PythonLaunchDescriptionSource(
os.path.join(pkg_environments, f'{env_launch[env]}.launch.py')),
launch_arguments={
'track': TextSubstitution(text=str(config['sanity_check']['ros__parameters']['track'])),
}.items() #TODO: this doesn't do anything
)

f1tenth = IncludeLaunchDescription(
launch_description_source=PythonLaunchDescriptionSource(
os.path.join(pkg_f1tenth_bringup, 'simulation_bringup.launch.py')),
launch_arguments={
'name': 'f1tenth',
'world': 'empty'
'car_name': TextSubstitution(text=str(config['sanity_check']['ros__parameters']['car_name'] if 'car_name' in config['sanity_check']['ros__parameters'] else 'f1tenth')),
}.items()
)

Expand All @@ -61,6 +52,5 @@ def generate_launch_description():
SetEnvironmentVariable(name='GZ_SIM_RESOURCE_PATH', value=pkg_f1tenth_description[:-19]),
SetParameter(name='use_sim_time', value=True),
environment,
f1tenth,
main
])

0 comments on commit 2938b95

Please sign in to comment.