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

Unity integration #13

Open
wants to merge 17 commits into
base: dev
Choose a base branch
from
Open
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
22 changes: 5 additions & 17 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,11 +1,6 @@
# Arena Rosnav Task Generator

This is the task generator package designed to work with:

- [arena-rosnav](https://github.com/Arena-Rosnav/arena-rosnav)
- [arena-rosnav-3d]()

The task generator is especially designed for single robot simulations.
This is the task generator package designed to work with the [Arena Benchmark](https://github.com/Arena-Rosnav/arena-rosnav) infrastructure.

## Task Modes

Expand All @@ -15,13 +10,6 @@ Our task generator package offers four task modes. We define a task as the proce

Creates random static and dynamic obstacles when a new task is started. When starting the task a random goal and start position is selected. After the robot reaching the goal a new task is started.

### Manual Task

Manual task mode is the same as the random task except that a goal must be set manually via the rviz *2D Nav Goal* button.

![image](https://arena-rosnav-wiki.readthedocs.io/en/latest/images/manual_task.png)


### Staged Task

The staged task mode is designed for the trainings process of arena-rosnav. In general, it behaves like the random task mode but there are multiple stages between one can switch. Between the stages, the amount of static and dynamic obstacles changes. The amount of obstacles is defined in a curriculum file, the path to said file is a key in the `paths` parameter.
Expand Down Expand Up @@ -51,10 +39,10 @@ robot are defined.
The scenario declaration file can be created with [arena-tools](https://github.com/Arena-Rosnav/arena-tools) and has to follow
the specified file schema.

## Environment Factory
## Simulator Factory

To be able to use the task generator module in all our environments without changes, a unified interface between environment and task generator is needed. The interface contains a lot of functions to spawn, publish or move robots or obstacles, and a lot more.
To be able to use the task generator module in all our simulators without changes, a unified interface between simulator and task generator is needed. The interface contains a lot of functions to spawn, publish or move robots or obstacles, and a lot more.

At the moment we provide environment interfaces for **Flatland** and **Gazebo**. In order to add a new environment, in which the task generator should be used, a new environment interface has to be created in `/taks_generator/environments/` and has to be registrated in the environment factory.
At the moment we provide simulator interfaces for **Flatland** and **Gazebo**. In order to add a new simulator, in which the task generator should be used, a new simulator interface has to be created in `/taks_generator/simulators/` and has to be registrated in the simulator factory.

Your newly created environment interface should derive the **BaseEnvironment** located [here](TODO) and implement all functions. A detailed description of the functions is contained in the **BaseEnvironment** itself.
Your newly created simulator interface should derive the **BaseSimulator** located [here](TODO) and implement all functions. A detailed description of the functions is contained in the **BaseSimulator** itself.
20 changes: 12 additions & 8 deletions robot_setup/marl_map_empty.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,14 +3,18 @@ robots:
# planner: rosnav
# amount: 6
# agent: rto_tlabs_marl
- model: agvota
planner: teb
amount: 1
agent: new_jackal
- model: burger
planner: teb
amount: 1
agent: new_jackal
- model: jackal
planner: rosnav
amount: 2
agent: jackal_marl
- model: rto
planner: rosnav
amount: 2
agent: rto_marl
- model: ridgeback
planner: rosnav
amount: 2
agent: ridgeback_marl
# - model: cob4
# planner: teb
# amount: 1
Expand Down
12 changes: 6 additions & 6 deletions robot_setup/rosnav_agents_marl.yaml
Original file line number Diff line number Diff line change
@@ -1,15 +1,15 @@
robots:
# - model: ridgeback
# planner: rosnav
# amount: 1
# planner: teb
# amount: 6
# agent: ridgeback_marl
- model: rto
planner: rosnav
amount: 3
planner: teb
amount: 6
agent: rto_tlabs_marl
# - model: jackal
# planner: rosnav
# amount: 1
# planner: teb
# amount: 6
# agent: jackal_marl
# - model: jackal
# planner: rosnav
Expand Down
56 changes: 54 additions & 2 deletions scenarios/marl_map_empty_obs0.json
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,60 @@
"goal": [29.94602317350325, 20.795265461388748, 0]
},
{
"start": [3.0220509108329354, 20.442857447479454, 0],
"goal": [30.58035759853998, 7.262797727271735, 0]
"start": [2.778715176849392, 3.053770554072754, 0],
"goal": [30.146818089333973, 23.16670627326246, 0]
},
{
"start": [5.237410725688214, 3.3359159449231095, 0],
"goal": [28.010574415752707, 23.16670627326246, 0]
},
{
"start": [8.05886463419178, 3.0134640696655604, 0],
"goal": [24.826362147584394, 23.126399788855267, 0]
},
{
"start": [2.980247598885362, 4.545110477138927, 0],
"goal": [31.114173715106627, 21.35291447493874, 0]
},
{
"start": [2.778715176849392, 8.092081104971982, 0],
"goal": [30.469269964591522, 18.53146056643517, 0]
},
{
"start": [2.9399411144781684, 11.27629337314029, 0],
"goal": [30.42896348018433, 16.516136346075484, 0]
},
{
"start": [2.4965697859990357, 14.379892672494213, 0],
"goal": [30.18712457374117, 12.727326811799266, 0]
},
{
"start": [3.141473536514136, 17.080427127776197, 0],
"goal": [30.348350511369944, 8.93851727752305, 0]
},
{
"start": [3.101167052106943, 19.619735645429405, 0],
"goal": [30.388656995777136, 6.802273603941779, 0]
},
{
"start": [2.8190216612565857, 22.803947913597714, 0],
"goal": [30.711108871034686, 2.932851100851173, 0]
},
{
"start": [5.277717210095408, 22.965173851226492, 0],
"goal": [28.292719806603063, 3.0134640696655604, 0]
},
{
"start": [8.099171118598974, 22.683028460376136, 0],
"goal": [25.672798320135467, 3.1343835228871413, 0]
},
{
"start": [10.033882370144276, 22.683028460376136, 0],
"goal": [25.14881402284195, 3.6180613357734708, 0]
},
{
"start": [10.598173151844989, 22.72333494478333, 0],
"goal": [23.77839355299736, 3.0134640696655604, 0]
}
],
"map": "map_empty",
Expand Down
9 changes: 5 additions & 4 deletions scripts/task_generator_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,9 @@
from task_generator.constants import Constants, TaskMode

from task_generator.tasks.utils import get_predefined_task
from task_generator.environments.environment_factory import EnvironmentFactory
from task_generator.environments.gazebo_environment import GazeboEnvironment
from task_generator.environments.flatland_environment import FlatlandRandomModel
from task_generator.simulators.simulator_factory import SimulatorFactory
from task_generator.simulators.gazebo_simulator import GazeboSimulator
from task_generator.simulators.flatland_simulator import FlatlandRandomModel


class TaskGenerator:
Expand All @@ -37,7 +37,7 @@ def __init__(self) -> None:
rospy.Service("reset_task", Empty, self.reset_task_srv_callback)

## Vars
self.env_wrapper = EnvironmentFactory.instantiate(Utils.get_environment())("")
self.env_wrapper = SimulatorFactory.instantiate(Utils.get_simulator())("")

rospy.loginfo(f"Launching task mode: {self.task_mode}")

Expand All @@ -60,6 +60,7 @@ def __init__(self) -> None:
self.number_of_resets = 0

self.reset_task()

## Timers
rospy.Timer(rospy.Duration(0.5), self.check_task_status)

Expand Down
24 changes: 12 additions & 12 deletions task_generator/constants.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
class Constants:
GOAL_REACHED_TOLERANCE = 1.0
TIMEOUT = 3.0 * 60 ## 3 min
TIMEOUT = 60 * 3 ## 3 min
WAIT_FOR_SERVICE_TIMEOUT = 5 # 5 secs
MAX_RESET_FAIL_TIMES = 3

Expand All @@ -15,9 +15,10 @@ class ObstacleManager:
class RobotManager:
SPAWN_ROBOT_SAFE_DIST = 0.4

class Environment:
class Simulator:
FLATLAND = "flatland"
GAZEBO = "gazebo"
UNITY = "unity"

class ArenaType:
TRAINING = "training"
Expand All @@ -30,10 +31,10 @@ class TaskMode:
SCENARIO = "scenario"

class Random:
MIN_DYNAMIC_OBS = 1
MAX_DYNAMIC_OBS = 3
MIN_STATIC_OBS = 1
MAX_STATIC_OBS = 3
MIN_DYNAMIC_OBS = 10
MAX_DYNAMIC_OBS = 15
MIN_STATIC_OBS = 10
MAX_STATIC_OBS = 20

class Scenario:
RESETS_DEFAULT = 5
Expand All @@ -60,11 +61,7 @@ class FlatlandRandomModel:
"body": "base_link"
}
LINEAR_VEL = 0.2
ANGLUAR_VEL_MAX = 0.2
<<<<<<< HEAD

=======
>>>>>>> master
ANGLUAR_VEL_MAX = 0.1

class Pedsim:
START_UP_MODE = "default"
Expand All @@ -89,4 +86,7 @@ class Pedsim:
FORCE_FACTOR_OBSTACLE = 1.0
FORCE_FACTOR_SOCIAL = 5.0
FORCE_FACTOR_ROBOT = 0.0
WAYPOINT_MODE = 0
WAYPOINT_MODE = 0

class UnitySimulatorConstants:
UNITY_ROS_NAVIGATION = "UNITY_ROS_NAVIGATION"
23 changes: 0 additions & 23 deletions task_generator/environments/environment_factory.py

This file was deleted.

18 changes: 9 additions & 9 deletions task_generator/manager/obstacle_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,21 +2,21 @@


class ObstacleManager:
def __init__(self, namespace, map_manager, environment):
def __init__(self, namespace, map_manager, simulator):
self.map_manager = map_manager
self.namespace = namespace
self.environment = environment
self.simulator = simulator

def start_scenario(self, scenario):
self.environment.spawn_pedsim_agents(scenario["obstacles"]["dynamic"])
self.simulator.spawn_pedsim_agents(scenario["obstacles"]["dynamic"])

def reset_scenario(self, scenario):
self.environment.reset_pedsim_agents()
self.simulator.reset_pedsim_agents()

self.environment.remove_all_obstacles()
self.simulator.remove_all_obstacles()

for obstacle in scenario["obstacles"]["static"]:
self.environment.spawn_obstacle(
self.simulator.spawn_obstacle(
[*obstacle["pos"], 0],
yaml_path=obstacle["yaml_path"],
)
Expand All @@ -27,20 +27,20 @@ def reset_random(
static_obstacles=Constants.ObstacleManager.STATIC_OBSTACLES,
forbidden_zones=[]
):
self.environment.remove_all_obstacles()
self.simulator.remove_all_obstacles()

for _ in range(dynamic_obstacles):
position = self.map_manager.get_random_pos_on_map(
safe_dist=Constants.ObstacleManager.OBSTACLE_MAX_RADIUS,
forbidden_zones=forbidden_zones
)

self.environment.spawn_random_dynamic_obstacle(position=position)
self.simulator.spawn_random_dynamic_obstacle(position=position)

for _ in range(static_obstacles):
position = self.map_manager.get_random_pos_on_map(
safe_dist=Constants.ObstacleManager.OBSTACLE_MAX_RADIUS,
forbidden_zones=forbidden_zones
)

self.environment.spawn_random_static_obstacle(position=position)
self.simulator.spawn_random_static_obstacle(position=position)
Loading