Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Make environment class run on simulation time #15

Merged
merged 3 commits into from
Jun 13, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 16 additions & 9 deletions src/environments/environments/CarWallEnvironment.py
Original file line number Diff line number Diff line change
Expand Up @@ -90,13 +90,16 @@ def __init__(self, car_name, reward_range=0.2, max_steps=50, collision_range=0.2
while not self.reset_client.wait_for_service(timeout_sec=1.0):
self.get_logger().info('reset service not available, waiting again...')

time.sleep(2)

# TODO: generate goal
self.goal_position = [10, 10] # x and y

time.sleep(5)

self.timer = self.create_timer(step_length, self.timer_cb)
self.timer_future = Future()

self.get_logger().info('Environment Setup Complete')

def timer_cb(self):
self.timer_future.set_result(True)

def reset(self):
self.step_counter = 0

Expand All @@ -105,11 +108,12 @@ def reset(self):
#TODO: Remove Hard coded-ness of 10x10
self.goal_position = self.generate_goal()

time.sleep(self.STEP_LENGTH)
while not self.timer_future.done():
rclpy.spin_once(self)

self.timer_future = Future()

self.call_reset_service()

time.sleep(self.STEP_LENGTH)

observation = self.get_observation()

Expand All @@ -136,7 +140,10 @@ def step(self, action):
lin_vel, ang_vel = action
self.set_velocity(lin_vel, ang_vel)

time.sleep(self.STEP_LENGTH)
while not self.timer_future.done():
rclpy.spin_once(self)

self.timer_future = Future()

next_state = self.get_observation()
reward = self.compute_reward(state, next_state)
Expand Down
6 changes: 5 additions & 1 deletion src/environments/launch/carwall.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,11 @@ def generate_launch_description():
f'/world/empty/create@ros_gz_interfaces/srv/SpawnEntity',
f'/world/empty/remove@ros_gz_interfaces/srv/DeleteEntity',
f'/world/empty/set_pose@ros_gz_interfaces/srv/SetEntityPose',
]
f'/world/empty/clock@rosgraph_msgs/msg/Clock@gz.msgs.Clock'
],
remappings=[
(f'/world/empty/clock', f'/clock'),
],
)

gz_sim = IncludeLaunchDescription(
Expand Down
2 changes: 1 addition & 1 deletion src/f1tenth
3 changes: 2 additions & 1 deletion src/reinforcement_learning/launch/car_wall.launch.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
import os
from ament_index_python import get_package_share_directory
from launch_ros.actions import Node
from launch_ros.actions import Node, SetParameter
from launch import LaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.actions import IncludeLaunchDescription, SetEnvironmentVariable
Expand Down Expand Up @@ -47,6 +47,7 @@ def generate_launch_description():
return LaunchDescription([
#TODO: Find a way to remove this
SetEnvironmentVariable(name='GZ_SIM_RESOURCE_PATH', value=pkg_f1tenth_description[:-19]),
SetParameter(name='use_sim_time', value=True),
environment,
f1tenth,
main
Expand Down