Skip to content

Commit

Permalink
renamed environment to simulator | added pedsim to scenario task in f…
Browse files Browse the repository at this point in the history
…latland
  • Loading branch information
ReykCS committed Feb 13, 2023
1 parent 7b48787 commit bdcdd9c
Show file tree
Hide file tree
Showing 21 changed files with 278 additions and 269 deletions.
2 changes: 1 addition & 1 deletion .rosinstall
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

- git:
local-name: ../utils/pedsim_ros
uri: https://github.com/ignc-research/pedsim_ros
uri: https://github.com/Arena-Rosnav/pedsim_ros.git
version: master

- git:
Expand Down
14 changes: 7 additions & 7 deletions arena_bringup/launch/start_arena.launch
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,11 @@
<!-- You can launch a single robot and his local_planner with arguments -->
<arg name="model" default="burger" doc="robot model type [burger, jackal, ridgeback, agvota, rto, ...]" />
<arg name="local_planner" default="teb" doc="local planner type [teb, dwa, mpc, rlca, arena, rosnav]" />
<arg name="environment" default="flatland" doc="[flatland, gazebo]" />
<arg name="simulator" default="flatland" doc="[flatland, gazebo]" />

<arg name="complexity" default="1" doc="1 = Map known, Position known; 2 = Map known, Position unknown (AMCL); 3 = Map unknown, Position unknown (SLAM)" />

<env name="ENVIRONMENT" value="$(arg environment)" />
<env name="SIMULATOR" value="$(arg simulator)" />

<arg name="agent_name" default="$(arg model)" doc = "DRL agent name to be deployed" unless="$(eval arg('local_planner') != 'rosnav')" />
<!-- Or you can load a robot setup file to launch multiple robots in the same simulation -->
Expand Down Expand Up @@ -71,7 +71,7 @@
<param name="use_sim_time" value="true"/>

<param name="model" value="$(arg model)" />
<param name="environment" value="$(arg environment)" />
<param name="simulator" value="$(arg simulator)" />
<param name="task_mode" value="$(arg task_mode)" />
<param name="map_path" value="$(arg map_path)" />
<param name="train_mode" value="false" />
Expand Down Expand Up @@ -107,15 +107,15 @@
<!-- use simulator-->

<!-- Flatland -->
<include file="$(find arena_bringup)/launch/testing//simulators/flatland.launch" if="$(eval arg('environment') == 'flatland')">
<include file="$(find arena_bringup)/launch/testing//simulators/flatland.launch" if="$(eval arg('simulator') == 'flatland')">
<arg name="visualization" default="$(arg visualization)" />
<arg name="rviz_file" value="$(arg rviz_file)" />
<arg name="model" value="$(arg model)" />
<arg name="show_rviz" value="$(arg show_rviz)" />
</include>

<!-- Gazebo -->
<include file="$(find arena_bringup)/launch/testing/simulators/gazebo.launch" if="$(eval arg('environment') == 'gazebo')">
<include file="$(find arena_bringup)/launch/testing/simulators/gazebo.launch" if="$(eval arg('simulator') == 'gazebo')">
<arg name="model" value="$(arg model)" />
<arg name="rviz_file" value="$(arg rviz_file)" />
<arg name="show_rviz" default="$(arg show_rviz)" />
Expand All @@ -140,13 +140,13 @@
<arg name="auto_reset" value="$(arg auto_reset)" />
</include>

<!-- <node name="pedsim_simulator" pkg="pedsim_simulator" type="pedsim_simulator" output="screen">
<node name="pedsim_simulator" pkg="pedsim_simulator" type="pedsim_simulator" output="screen">
<param name="simulation_factor" value="1" type="double"/>
<param name="pedsim_update_rate" value="30.0" type="double"/>
<param name="scene_file" value="$(find arena-simulation-setup)/world/$(arg world_file)/scenarios/$(arg world_file).xml" type="string"/>
</node>

<node name="pedsim_visualizer" type="pedsim_visualizer_node" pkg="pedsim_visualizer"/> -->
<!-- <node name="pedsim_visualizer" type="pedsim_visualizer_node" pkg="pedsim_visualizer"/> -->

<!-- launch map generator if training with random map-->
<!-- <group if="$(eval arg('map_file') == 'random_map')">
Expand Down
2 changes: 1 addition & 1 deletion arena_bringup/launch/testing/robot.launch
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@

<node pkg="tf2_ros" type="static_transform_publisher" name="transform_broadcaster" args="0 0 0 0 0 0 1 map $(arg namespace)/odom" />

<group if="$(eval env('ENVIRONMENT') == 'gazebo')">
<group if="$(eval env('SIMULATOR') == 'gazebo')">
<include file="$(find arena-simulation-setup)/robot/$(arg model)/launch/control.launch">
<arg name="robot_namespace" value="$(arg namespace)" />
</include>
Expand Down
2 changes: 1 addition & 1 deletion arena_bringup/params/flatland_deploy.yaml
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
step_size: 0.1
update_rate: 50
update_rate: 10
viz_pub_rate: 30
110 changes: 0 additions & 110 deletions install.sh

This file was deleted.

8 changes: 4 additions & 4 deletions task_generator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -39,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.
28 changes: 28 additions & 0 deletions task_generator/scenarios/Eval_13_02.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
{
"map": "small_warehouse",
"resets": 10,
"robots": [
{
"start": [-5.1, 5.9, 0],
"goal": [0.600000000000001, -7.4, 0]
}
],
"obstacles": {
"dynamic": [
{
"type": "pedestrian",
"waypoints": [
[-5.3, 0.2, 0],
[1, -1.1, 0]
]
},
{
"type": "pedestrian",
"waypoints": [
[-4.6, -3.9, 0],
[0.9, -4.1, 0]
]
}
]
}
}
3 changes: 0 additions & 3 deletions task_generator/scenarios/empty.xml

This file was deleted.

8 changes: 4 additions & 4 deletions task_generator/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 Down
2 changes: 1 addition & 1 deletion task_generator/task_generator/constants.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ class ObstacleManager:
class RobotManager:
SPAWN_ROBOT_SAFE_DIST = 0.4

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

Expand Down
23 changes: 0 additions & 23 deletions task_generator/task_generator/environments/environment_factory.py

This file was deleted.

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


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()

print(scenario.get("obstacles").get("static"))

if not scenario.get("obstacles") or not scenario.get("obstacles").get("static"):
return

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 +32,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)
8 changes: 4 additions & 4 deletions task_generator/task_generator/manager/robot_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,13 +21,13 @@ class RobotManager:
position of a robot for all task modes.
"""

def __init__(self, namespace, map_manager, environment, robot_setup):
def __init__(self, namespace, map_manager, simulator, robot_setup):
self.namespace = namespace
self.namespace_prefix = "" if namespace == "" else "/" + namespace + "/"
self.ns_prefix = lambda *topic: os.path.join(self.namespace, *topic)

self.map_manager = map_manager
self.environment = environment
self.simulator = simulator

self.start_pos = [0, 0]
self.goal_pos = [0, 0]
Expand All @@ -44,7 +44,7 @@ def set_up_robot(self):
if Utils.get_arena_type() == Constants.ArenaType.TRAINING:
self.robot_radius = rospy.get_param("robot_radius")

self.environment.spawn_robot(self.namespace, self.robot_setup["model"], self._robot_name())
self.simulator.spawn_robot(self.namespace, self.robot_setup["model"], self._robot_name())

self.move_base_goal_pub = rospy.Publisher(self.ns_prefix(self.namespace, "move_base_simple", "goal"), PoseStamped, queue_size=10)
self.pub_goal_timer = rospy.Timer(rospy.Duration(0.25), self.publish_goal_periodically)
Expand Down Expand Up @@ -159,7 +159,7 @@ def move_robot_to_start(self):
self.move_robot_to_pos(self.start_pos)

def move_robot_to_pos(self, pos):
self.environment.move_robot(pos, name=self.namespace)
self.simulator.move_robot(pos, name=self.namespace)

def _default_position(self, pos, callback_pos):
if not pos == None:
Expand Down
Loading

0 comments on commit bdcdd9c

Please sign in to comment.