Giter Club home page Giter Club logo

arena-rosnav's Introduction

Arena-Rosnav (IEEE IROS 21)

If you find this code useful, please cite our paper:

@inproceedings{kastner2021arena,
  title={Arena-Rosnav: Towards Deployment of Deep-Reinforcement-Learning-Based Obstacle Avoidance into Conventional Autonomous Navigation Systems},
  author={K{\"a}stner, Linh and Buiyan, Teham and Jiao, Lei and Le, Tuan Anh and Zhao, Xinlin and Shen, Zhengcheng and Lambrecht, Jens},
  booktitle={2021 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
  pages={6456--6463},
  organization={IEEE}
}

Important Updates (01/03/2023)!:

We have restructured, improved, and extended the whole codebase substantially. Therefore, we created a new organization at Aren-Rosnav. Please have a look at our new organization, which contains an improved version of the 2D arena-rosnav along with a variety of other modules. As of 01/03/2023, this repository is not actively maintained anymore.

Description

Note: This reporsitory is part of arena-bench. Please also check out our most recent paper on arena-bench. For our 3D version using Gazebo as simulation platform, please visit our arena-rosnav-3D repo.

This reporsitory includes the code for our paper Arena-rosnav. Arena-rosnav is a flexible, high-performance 2D simulator with configurable agents, multiple sensors, and benchmark scenarios for testing robotic navigation. Arena-Rosnav uses Flatland as the core simulator and is a modular high-level library for end-to-end experiments in embodied AI -- defining embodied AI tasks (e.g. navigation, obstacle avoidance, behavior cloning), training agents (via imitation or reinforcement learning, or no learning at all using conventional approaches like DWA, TEB or MPC), and benchmarking their performance on the defined tasks using standard metrics.

Training Stage Deployment Stage

What is this repository for?

Train DRL agents on ROS compatible simulations for autonomous navigation in highly dynamic environments. Flatland-DRL integration is inspired by Ronja Gueldenring's work: drl_local_planner_ros_stable_baselines. Test state of the art local and global planners in ROS environments both in simulation and on real hardware. Following features are included:

  • Setup to train a local planner with reinforcement learning approaches from stable baselines3
  • Training in simulator Flatland in train mode
  • Include realistic behavior patterns and semantic states of obstacles (speaking, running, etc.)
  • Include different obstacles classes (other robots, vehicles, types of persons, etc.)
  • Implementation of intermediate planner classes to combine local DRL planner with global map-based planning of ROS Navigation stack
  • Testing a variety of planners (learning based and model based) within specific scenarios in test mode
  • Modular structure for extension of new functionalities and approaches

Start Guide

We recommend starting with the start guide which contains all information you need to know to start off with this project including installation on Linux and Windows as well as tutorials to start with.

  • For Mac, please refer to our Docker.

1. Installation

Open the terminal with Ctrl+Alt+T and enter below commands one at a time.

In order to check the details of the easy installation script, please refer to the script file.

sudo apt-get update && sudo apt-get upgrade
wget https://raw.githubusercontent.com/ignc-research/arena-rosnav/noetic-devel/setup.sh -O - | bash

Create a virtual environment

source ~/.bashrc && mkvirtualenv --python=python3.8 rosnav

Install further dependencies (you can take a look at the script here)

wget https://raw.githubusercontent.com/ignc-research/arena-rosnav/noetic-devel/setup2.sh -O - | bash
source ~/.bashrc && workon rosnav

Now everything should be set up. You can start the simulation with:

roslaunch arena_bringup start_arena_flatland.launch

Alternatively, refer to Installation.md for detailed explanations about the installation process.

1.1. Docker

We provide a Docker file to run our code on other operating systems. Please refer to Docker.md for more information.

2. Usage

DRL Training

Please refer to DRL-Overview.md for detailed explanations about agent, policy, and training setup. Addtionally, useful tips and information about the training are provided.

Scenario Creation with arena-tools

To create complex, collaborative scenarios for training and/or evaluation purposes, please refer to the repo arena-tools. This application provides you with an user interface to easily create complex scenarios with multiple dynamic and static obstacles by drawing and other simple UI elements like dragging and dropping. This will save you a lot of time in creating complex scenarios for you individual use cases.

Robots

We support different robots:

turtlebot3_burger jackal ridgeback agv-ota
Robotino(rto) youbot turtlebot3_waffle_pi Car-O-Bot4 (cob4)

All robots are equipped with a laser scanner. The robots differ in size, laser-range etc. See below table for more detailed information on each robot:

Name Max Speed (vx) [_m/s] Max Speed (vy) [_m/s] Max Rotational Speed (θy) [_rad/s] Radius [m] Emergency-Stop¹ Laser-range [m] Holonomic²
turtlebot3-burger 0.22 0.0 2.84 0.113 True 3.5 False
jackal 2.0 0.0 4.0 0.267 True 30.0 False
ridgeback 1.1 0.5 2.0 0.625 True 10.0 True
agv-ota 0.5 0.0 0.4 0.629 True 5.0 False
rto 2.78 2.78 1.0 0.225 False 5.6 True
youbot 0.8 0.8 1.2 0.347 False 5.6 True
turtlebot3_waffle_pi 0.26 0.0 1.82 0.208 False 3.5 False
Car-O-Bot4 (cob4) 1.1 0.2 0.8 0.36 True 29.5 True

For additional / more detailed information about each robot:

IROS21 information

To test the code and reproduce the experiments, follow the installation steps in Installation.md. Afterwards, follow the steps in Evaluations.md.

To test the different Waypoint Generators, follow the steps in waypoint_eval.md

DRL agents are located in the agents folder.

Used third party repos:

arena-rosnav's People

Contributors

ann-rachel avatar dangaw255 avatar ducanor avatar eliastreis avatar erikryg avatar franklinbf avatar ignc-research avatar jacenty00 avatar johannescox avatar leidoubi avatar linhdoan8 avatar ll7 avatar m-yordanova avatar reykcs avatar sirupli avatar sudo-boris avatar tehamc avatar tuananhroman avatar valwai avatar wittenator avatar yisunny avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar

arena-rosnav's Issues

No world_path parameter given!

But a new error emerged:

auto-starting new master
process[master]: started with pid [17798]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 5cbb9944-c150-11ec-97ba-0242ac140002
process[rosout-1]: started with pid [17816]
started core service [/rosout]
process[flatland_server-2]: started with pid [17823]
process[spawn_model-3]: started with pid [17837]
[FATAL] [1650531145.025923810]: No world_path parameter given!
process[flatland_rviz-4]: started with pid [17838]
QStandardPaths: XDG_RUNTIME_DIR not set, defaulting to '/tmp/runtime-root'
[ INFO] [1650531145.181028704]: rviz version 1.13.16
[ INFO] [1650531145.181065425]: compiled against Qt version 5.9.5
[ INFO] [1650531145.181074845]: compiled against OGRE version 1.9.0 (Ghadamon)
[ INFO] [1650531145.188088703]: Forcing OpenGl version 0.
process[map_server-5]: started with pid [17844]
[ERROR] [1650531145.215777812]: Map_server could not open /root/arena_ws/src/arena-rosnav/simulator_setup/maps/ignc/map.yaml.
[flatland_server-2] process has died [pid 17823, exit code 1, cmd /root/catkin_ws/devel/lib/flatland_server/flatland_server __name:=flatland_server __log:=/root/.ros/log/5cbb9944-c150-11ec-97ba-0242ac140002/flatland_server-2.log].
log file: /root/.ros/log/5cbb9944-c150-11ec-97ba-0242ac140002/flatland_server-2*.log
process[map_to_odom_tfpublisher-6]: started with pid [17855]
[map_server-5] process has died [pid 17844, exit code 255, cmd /opt/ros/melodic/lib/map_server/map_server /root/arena_ws/src/arena-rosnav/simulator_setup/maps/ignc/map.yaml __name:=map_server __log:=/root/.ros/log/5cbb9944-c150-11ec-97ba-0242ac140002/map_server-5.log].
log file: /root/.ros/log/5cbb9944-c150-11ec-97ba-0242ac140002/map_server-5*.log

Originally posted by @ll7 in #48 (comment)

When i try to change debug_mode to false

The error occurred after I changed the debug_mode to False in arena-rosnav/arena_bringup/configs/training/training_config.yaml:

<=======================>
Traceback (most recent call last):
File "/home/dmz/miniconda3/envs/wzl_d86/lib/python3.8/multiprocessing/process.py", line 313, in _bootstrap
self.run()
File "/home/dmz/miniconda3/envs/wzl_d86/lib/python3.8/multiprocessing/process.py", line 108, in run
self._target(*self._args, **self._kwargs)
File "/home/dmz/arena_ws/src/utils-extern/misc/stable-baselines3/stable_baselines3/common/vec_env/subproc_vec_env.py", line 29, in _worker
env = _patch_env(env_fn_wrapper.var())
File "/home/dmz/arena_ws/src/arena-rosnav/training/tools/env_utils.py", line 55, in _init
env = FlatlandEnv(
File "/home/dmz/arena_ws/src/arena-rosnav/utils/misc/rl_utils/rl_utils/envs/flatland_gymnasium_env.py", line 130, in init
self._setup_env_for_training(reward_fnc, **kwargs)
File "/home/dmz/arena_ws/src/arena-rosnav/utils/misc/rl_utils/rl_utils/envs/flatland_gymnasium_env.py", line 167, in _setup_env_for_training
self.task: BaseTask = task_generator._get_predefined_task(**kwargs)
File "/home/dmz/arena_ws/src/arena-rosnav/task_generator/task_generator/task_generator_node.py", line 226, in _get_predefined_task
task = TaskFactory.instantiate(self._task_mode)(
File "/home/dmz/arena_ws/src/arena-rosnav/task_generator/task_generator/tasks/random.py", line 30, in init
BaseTask.init(self, **kwargs)
File "/home/dmz/arena_ws/src/arena-rosnav/task_generator/task_generator/tasks/base_task.py", line 80, in init
self.set_up_robot_managers()
File "/home/dmz/arena_ws/src/arena-rosnav/task_generator/task_generator/tasks/base_task.py", line 172, in set_up_robot_managers
manager.set_up_robot()
File "/home/dmz/arena_ws/src/arena-rosnav/task_generator/task_generator/manager/robot_manager.py", line 122, in set_up_robot
self._launch_robot()
File "/home/dmz/arena_ws/src/arena-rosnav/task_generator/task_generator/manager/robot_manager.py", line 222, in _launch_robot
roslaunch_file = roslaunch.rlutil.resolve_launch_arguments( # type: ignore
File "/opt/ros/noetic/lib/python3/dist-packages/roslaunch/rlutil.py", line 92, in resolve_launch_arguments
resolved = roslib.packages.find_resource(args[0], args[1])
File "/opt/ros/noetic/lib/python3/dist-packages/roslib/packages.py", line 526, in find_resource
search_paths = catkin_find(
File "/opt/ros/noetic/lib/python3/dist-packages/catkin/find_in_workspaces.py", line 149, in find_in_workspaces
source_path_to_packages[source_path] = find_packages(source_path)
File "/home/dmz/miniconda3/envs/wzl_d86/lib/python3.8/site-packages/catkin_pkg/packages.py", line 92, in find_packages
packages = find_packages_allowing_duplicates(basepath, exclude_paths=exclude_paths,
File "/home/dmz/miniconda3/envs/wzl_d86/lib/python3.8/site-packages/catkin_pkg/packages.py", line 145, in find_packages_allowing_duplicates
pool = multiprocessing.Pool()
File "/home/dmz/miniconda3/envs/wzl_d86/lib/python3.8/multiprocessing/context.py", line 119, in Pool
return Pool(processes, initializer, initargs, maxtasksperchild,
File "/home/dmz/miniconda3/envs/wzl_d86/lib/python3.8/multiprocessing/pool.py", line 212, in init
self._repopulate_pool()
File "/home/dmz/miniconda3/envs/wzl_d86/lib/python3.8/multiprocessing/pool.py", line 303, in _repopulate_pool
return self._repopulate_pool_static(self._ctx, self.Process,
File "/home/dmz/miniconda3/envs/wzl_d86/lib/python3.8/multiprocessing/pool.py", line 326, in _repopulate_pool_static
w.start()
File "/home/dmz/miniconda3/envs/wzl_d86/lib/python3.8/multiprocessing/process.py", line 118, in start
assert not _current_process._config.get('daemon'),
AssertionError: daemonic processes are not allowed to have children
<=======================>

I'm looking at the printout and guessing that the reason might be because the robot.launch file fails to start at line 222 of arena-rosnav/task_generator/task_generator/manager/robot_manager.py.
I can't fix it!

Actually, earlier, when debug_mode=true, I've tried to fix a lot of minor bugs, including
1, Incongruous errors from version updates in planners/rosnav/scripts/rosnav_node.py.
2, incorrect paths to the launch file when testing other Planners, and other Planners that don't run or don't test well(include:crowdnav、all-in-one .etc)
3、When full_range_laser= true, the network input dimension reports an error
...
Some of the above problems I can fix myself and some I'm not so good at (although it has taken a lot of effort)

Please help me, I'm limited in my ability to work out these bugs on my own, I won't be able to graduate [cry].

Unable to find plan_ fsm_ param. yaml

Hello!My name is Yixiao Du.
When I reproduce your code, there are two problems. Hope to get your help!Thank you!
When I want to run the trained agent:

python run_agent.py --load DRL_LOCAL_PLANNER_2021_03_22__19_33 -s obstacle_map1_obs20

And I should note:
Notes:

  • When running start_arena_flatland.launch: Make sure that drl_mode is activated in plan_fsm_param.yaml

However, I can't find the file in this location.

If I ignore this file, continue to run the code

# Start the simulation
roslaunch arena_bringup start_training.launch num_envs:=1 map_folder_name:=map1 train_mode:=false

python run_agent.py --load DRL_LOCAL_PLANNER_2021_03_22__19_33 --scenario obstacle_map1_obs20

Then I got:

Can't not determinate the number of the environment, training script may crash!
/home/dell/.cache/pypoetry/virtualenvs/arena-rosnav-jPKqHTAF-py3.8/lib/python3.8/site-packages/gym/spaces/box.py:73: UserWarning: WARN: Box bound precision lowered by casting to float32
  logger.warn(
Traceback (most recent call last):
  File "run_agent.py", line 142, in <module>
    env = DummyVecEnv(
  File "/home/dell/catkin_ws/src/forks/stable-baselines3/stable_baselines3/common/vec_env/dummy_vec_env.py", line 25, in __init__
    self.envs = [fn() for fn in env_fns]
  File "/home/dell/catkin_ws/src/forks/stable-baselines3/stable_baselines3/common/vec_env/dummy_vec_env.py", line 25, in <listcomp>
    self.envs = [fn() for fn in env_fns]
  File "run_agent.py", line 84, in _init
    env = FlatlandEnv(
  File "/home/dell/catkin_ws/src/arena-rosnav/arena_navigation/arena_local_planner/learning_based/arena_local_planner_drl/rl_agent/envs/flatland_gym_env.py", line 129, in __init__
    self.task = get_predefined_task(
  File "/home/dell/catkin_ws/src/arena-rosnav/task_generator/task_generator/tasks.py", line 672, in get_predefined_task
    robot_manager = RobotManager(
  File "/home/dell/catkin_ws/src/arena-rosnav/task_generator/task_generator/robot_manager.py", line 73, in __init__
    self.planner = rospy.get_param("/local_planner")
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/client.py", line 467, in get_param
    return _param_server[param_name] #MasterProxy does all the magic for us
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/msproxy.py", line 123, in __getitem__
    raise KeyError(key)
KeyError: '/local_planner'

In addition, when I evaluated cadrl, it doesn't work,too.

When I run:

roslaunch arena_bringup start_arena_flatland.launch disable_scenario:="false" map_file:="map1" scenario_file:="eval/obstacle_map1_obs10.json" local_planner:="teb"

an error occurred:

[cadrl/cadrl_node-8] process has died [pid 8116, exit code 1, cmd /home/dell/catkin_ws/src/arena-rosnav/arena_navigation/arena_local_planner/model_based/cadrl_ros/scripts/cadrl_node_tb3.py ~other_vels:=other_vels ~nn_cmd_vel:=/cmd_vel ~pose_marker:=pose_marker ~path_marker:=path_marker ~goal_path_marker:=goal_path_marker ~agent_marker:=other_agents_marker ~agent_markers:=other_agents_markers ~pose:=/odom ~velocity:=velocity ~safe_actions:=local_path_finder/safe_actions ~planner_mode:=planner_fsm/mode ~goal:=/goal ~subgoal:=/subgoal ~clusters:=/obst_odom ~peds:=ped_manager/ped_recent __name:=cadrl_node __log:=/home/dell/.ros/log/efbdc6e4-9168-11ec-b105-08beac085e17/cadrl-cadrl_node-8.log].
log file: /home/dell/.ros/log/efbdc6e4-9168-11ec-b105-08beac085e17/cadrl-cadrl_node-8*.log

It doesn't appear when I use TEB, DWA, etc

It puzzles me.

Hope to get your help, thank you very much!

rospy.exceptions.ROSException: timeout exceeded while waiting for service /pedsim_simulator/spawn_interactive_obstacles

Any ideas what is going wrong?

roslaunch arena_bringup start_arena_flatland.launch
... logging to /root/.ros/log/84e550f4-cd12-11ec-ac59-0242ac130003/roslaunch-d5247af3bda6-2629.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://d5247af3bda6:35995/

SUMMARY
========

PARAMETERS
 * /action_frequency: 10
 * /inter_planner/astar/allocate_num: 100000
 * /inter_planner/astar/lambda_heu: 0.1
 * /inter_planner/astar/resolution_astar: 0.1
 * /inter_planner/astar/time_resolution: 0.8
 * /inter_planner/b_spline/control_points_distance: 0.5
 * /inter_planner/b_spline/feasibility_tolerance: 0.05
 * /inter_planner/b_spline/max_acc: 2.0
 * /inter_planner/b_spline/max_jerk: 4.0
 * /inter_planner/b_spline/max_vel: 3.0
 * /inter_planner/b_spline/planning_horizon: 7.5
 * /inter_planner/global_planner/dist_next_wp: 3.0
 * /inter_planner/global_planner/dist_tolerance: 1.0
 * /inter_planner/global_planner/rou_thresh: 15.0
 * /inter_planner/global_planner/use_astar: True
 * /inter_planner/global_planner/use_kino_astar: True
 * /inter_planner/global_planner/use_oneshot: True
 * /inter_planner/global_planner/use_optimization_astar: True
 * /inter_planner/global_planner/use_optimization_esdf: True
 * /inter_planner/kino_astar/allocate_num: 100000
 * /inter_planner/kino_astar/check_num: 5
 * /inter_planner/kino_astar/horizon: 30
 * /inter_planner/kino_astar/init_max_tau: 0.8
 * /inter_planner/kino_astar/lambda_heu: 0.1
 * /inter_planner/kino_astar/max_acc: 2.0
 * /inter_planner/kino_astar/max_tau: 0.6
 * /inter_planner/kino_astar/max_vel: 3.0
 * /inter_planner/kino_astar/resolution_astar: 0.1
 * /inter_planner/kino_astar/time_resolution: 0.8
 * /inter_planner/kino_astar/w_time: 10.0
 * /inter_planner/optimization_ESDF/algorithm1: 15
 * /inter_planner/optimization_ESDF/algorithm2: 11
 * /inter_planner/optimization_ESDF/dist0: 0.4
 * /inter_planner/optimization_ESDF/lambda1: 10.0
 * /inter_planner/optimization_ESDF/lambda2: 5.0
 * /inter_planner/optimization_ESDF/lambda3: 1e-05
 * /inter_planner/optimization_ESDF/lambda4: 0.01
 * /inter_planner/optimization_ESDF/lambda5: 1.5
 * /inter_planner/optimization_ESDF/lambda6: 10.0
 * /inter_planner/optimization_ESDF/lambda7: 100.0
 * /inter_planner/optimization_ESDF/max_acc: 2.0
 * /inter_planner/optimization_ESDF/max_iteration_num1: 2
 * /inter_planner/optimization_ESDF/max_iteration_num2: 300
 * /inter_planner/optimization_ESDF/max_iteration_num3: 200
 * /inter_planner/optimization_ESDF/max_iteration_num4: 200
 * /inter_planner/optimization_ESDF/max_iteration_time1: 0.0001
 * /inter_planner/optimization_ESDF/max_iteration_time2: 0.005
 * /inter_planner/optimization_ESDF/max_iteration_time3: 0.003
 * /inter_planner/optimization_ESDF/max_iteration_time4: 0.003
 * /inter_planner/optimization_ESDF/max_vel: 3.0
 * /inter_planner/optimization_ESDF/order: 3
 * /inter_planner/optimization_astar/dist0: 0.5
 * /inter_planner/optimization_astar/lambda_collision: 0.5
 * /inter_planner/optimization_astar/lambda_feasibility: 0.1
 * /inter_planner/optimization_astar/lambda_fitness: 1.0
 * /inter_planner/optimization_astar/lambda_smooth: 1.0
 * /inter_planner/optimization_astar/max_acc: 2.0
 * /inter_planner/optimization_astar/max_vel: 3.0
 * /inter_planner/optimization_astar/order: 3
 * /inter_planner/sdf_map/frame_id: map
 * /inter_planner/sdf_map/local_bound_inflate: 0.0
 * /inter_planner/sdf_map/local_map_margin: 50.0
 * /inter_planner/sdf_map/local_update_range_x: 10.0
 * /inter_planner/sdf_map/local_update_range_y: 10.0
 * /inter_planner/sdf_map/max_ray_length: 10.0
 * /inter_planner/sdf_map/min_ray_length: 0.5
 * /inter_planner/sdf_map/obstacles_inflation: 0.3
 * /inter_planner/sdf_map/p_hit: 0.55
 * /inter_planner/sdf_map/p_max: 0.8
 * /inter_planner/sdf_map/p_min: 0.12
 * /inter_planner/sdf_map/p_miss: 0.2
 * /inter_planner/sdf_map/p_occ: 0.7
 * /inter_planner/sdf_map/resolution: 0.05
 * /inter_planner/sdf_map/show_esdf_time: False
 * /inter_planner/sdf_map/show_occ_time: False
 * /inter_planner/sdf_map/use_occ_esdf: True
 * /laser_update_rate: 10
 * /local_planner: teb
 * /map_file: ignc
 * /map_layer_path: /root/arena_ws/sr...
 * /map_server/frame_id: map
 * /model: burger
 * /move_base/DWAPlannerROS/acc_lim_theta: 3.2
 * /move_base/DWAPlannerROS/acc_lim_x: 2.5
 * /move_base/DWAPlannerROS/acc_lim_y: 0.0
 * /move_base/DWAPlannerROS/controller_frequency: 10.0
 * /move_base/DWAPlannerROS/forward_point_distance: 0.325
 * /move_base/DWAPlannerROS/goal_distance_bias: 20.0
 * /move_base/DWAPlannerROS/latch_xy_goal_tolerance: False
 * /move_base/DWAPlannerROS/max_scaling_factor: 0.2
 * /move_base/DWAPlannerROS/max_vel_theta: 2.75
 * /move_base/DWAPlannerROS/max_vel_trans: 0.22
 * /move_base/DWAPlannerROS/max_vel_x: 0.22
 * /move_base/DWAPlannerROS/max_vel_y: 0.0
 * /move_base/DWAPlannerROS/min_vel_theta: 1.37
 * /move_base/DWAPlannerROS/min_vel_trans: 0.11
 * /move_base/DWAPlannerROS/min_vel_x: -0.22
 * /move_base/DWAPlannerROS/min_vel_y: 0.0
 * /move_base/DWAPlannerROS/occdist_scale: 0.02
 * /move_base/DWAPlannerROS/oscillation_reset_dist: 0.05
 * /move_base/DWAPlannerROS/path_distance_bias: 32.0
 * /move_base/DWAPlannerROS/publish_cost_grid_pc: True
 * /move_base/DWAPlannerROS/publish_traj_pc: True
 * /move_base/DWAPlannerROS/scaling_speed: 0.25
 * /move_base/DWAPlannerROS/sim_time: 1.5
 * /move_base/DWAPlannerROS/stop_time_buffer: 0.2
 * /move_base/DWAPlannerROS/vth_samples: 40
 * /move_base/DWAPlannerROS/vx_samples: 20
 * /move_base/DWAPlannerROS/vy_samples: 0
 * /move_base/DWAPlannerROS/xy_goal_tolerance: 0.05
 * /move_base/DWAPlannerROS/yaw_goal_tolerance: 0.17
 * /move_base/TebLocalPlannerROS/acc_lim_theta: 0.5
 * /move_base/TebLocalPlannerROS/acc_lim_x: 0.5
 * /move_base/TebLocalPlannerROS/allow_init_with_backwards_motion: False
 * /move_base/TebLocalPlannerROS/complete_global_plan: True
 * /move_base/TebLocalPlannerROS/costmap_converter_plugin: 
 * /move_base/TebLocalPlannerROS/costmap_converter_rate: 5
 * /move_base/TebLocalPlannerROS/costmap_converter_spin_thread: True
 * /move_base/TebLocalPlannerROS/costmap_obstacles_behind_robot_dist: 1.5
 * /move_base/TebLocalPlannerROS/delete_detours_backwards: True
 * /move_base/TebLocalPlannerROS/dt_hysteresis: 0.1
 * /move_base/TebLocalPlannerROS/dt_ref: 0.3
 * /move_base/TebLocalPlannerROS/dynamic_obstacle_inflation_dist: 0.6
 * /move_base/TebLocalPlannerROS/enable_homotopy_class_planning: True
 * /move_base/TebLocalPlannerROS/enable_multithreading: True
 * /move_base/TebLocalPlannerROS/exact_arc_length: False
 * /move_base/TebLocalPlannerROS/feasibility_check_no_poses: 5
 * /move_base/TebLocalPlannerROS/footprint_model/type: point
 * /move_base/TebLocalPlannerROS/free_goal_vel: False
 * /move_base/TebLocalPlannerROS/global_plan_overwrite_orientation: True
 * /move_base/TebLocalPlannerROS/global_plan_prune_distance: 1
 * /move_base/TebLocalPlannerROS/global_plan_viapoint_sep: -1
 * /move_base/TebLocalPlannerROS/h_signature_prescaler: 0.5
 * /move_base/TebLocalPlannerROS/h_signature_threshold: 0.1
 * /move_base/TebLocalPlannerROS/include_costmap_obstacles: True
 * /move_base/TebLocalPlannerROS/include_dynamic_obstacles: True
 * /move_base/TebLocalPlannerROS/inflation_dist: 0.6
 * /move_base/TebLocalPlannerROS/max_global_plan_lookahead_dist: 3.0
 * /move_base/TebLocalPlannerROS/max_number_classes: 4
 * /move_base/TebLocalPlannerROS/max_ratio_detours_duration_best_duration: 3.0
 * /move_base/TebLocalPlannerROS/max_samples: 500
 * /move_base/TebLocalPlannerROS/max_vel_theta: 0.3
 * /move_base/TebLocalPlannerROS/max_vel_x: 0.22
 * /move_base/TebLocalPlannerROS/max_vel_x_backwards: 0.2
 * /move_base/TebLocalPlannerROS/max_vel_y: 0.0
 * /move_base/TebLocalPlannerROS/min_obstacle_dist: 0.25
 * /move_base/TebLocalPlannerROS/min_turning_radius: 0.0
 * /move_base/TebLocalPlannerROS/no_inner_iterations: 5
 * /move_base/TebLocalPlannerROS/no_outer_iterations: 4
 * /move_base/TebLocalPlannerROS/obstacle_cost_exponent: 4
 * /move_base/TebLocalPlannerROS/obstacle_heading_threshold: 0.45
 * /move_base/TebLocalPlannerROS/obstacle_poses_affected: 15
 * /move_base/TebLocalPlannerROS/odom_topic: odom
 * /move_base/TebLocalPlannerROS/optimization_activate: True
 * /move_base/TebLocalPlannerROS/optimization_verbose: False
 * /move_base/TebLocalPlannerROS/oscillation_filter_duration: 10
 * /move_base/TebLocalPlannerROS/oscillation_omega_eps: 0.1
 * /move_base/TebLocalPlannerROS/oscillation_recovery: True
 * /move_base/TebLocalPlannerROS/oscillation_recovery_min_duration: 10
 * /move_base/TebLocalPlannerROS/oscillation_v_eps: 0.1
 * /move_base/TebLocalPlannerROS/penalty_epsilon: 0.1
 * /move_base/TebLocalPlannerROS/publish_feedback: False
 * /move_base/TebLocalPlannerROS/roadmap_graph_area_length_scale: 1.0
 * /move_base/TebLocalPlannerROS/roadmap_graph_area_width: 5
 * /move_base/TebLocalPlannerROS/roadmap_graph_no_samples: 15
 * /move_base/TebLocalPlannerROS/selection_alternative_time_cost: False
 * /move_base/TebLocalPlannerROS/selection_cost_hysteresis: 1.0
 * /move_base/TebLocalPlannerROS/selection_obst_cost_scale: 100.0
 * /move_base/TebLocalPlannerROS/selection_prefer_initial_plan: 0.9
 * /move_base/TebLocalPlannerROS/shrink_horizon_backup: True
 * /move_base/TebLocalPlannerROS/shrink_horizon_min_duration: 10
 * /move_base/TebLocalPlannerROS/switching_blocking_period: 0.0
 * /move_base/TebLocalPlannerROS/teb_autosize: True
 * /move_base/TebLocalPlannerROS/viapoints_all_candidates: True
 * /move_base/TebLocalPlannerROS/visualize_hc_graph: False
 * /move_base/TebLocalPlannerROS/visualize_with_time_as_z_axis_scale: False
 * /move_base/TebLocalPlannerROS/weight_acc_lim_theta: 1
 * /move_base/TebLocalPlannerROS/weight_acc_lim_x: 1
 * /move_base/TebLocalPlannerROS/weight_adapt_factor: 2
 * /move_base/TebLocalPlannerROS/weight_dynamic_obstacle: 10
 * /move_base/TebLocalPlannerROS/weight_dynamic_obstacle_inflation: 0.2
 * /move_base/TebLocalPlannerROS/weight_inflation: 0.2
 * /move_base/TebLocalPlannerROS/weight_kinematics_forward_drive: 1
 * /move_base/TebLocalPlannerROS/weight_kinematics_nh: 1000
 * /move_base/TebLocalPlannerROS/weight_kinematics_turning_radius: 1
 * /move_base/TebLocalPlannerROS/weight_max_vel_theta: 1
 * /move_base/TebLocalPlannerROS/weight_max_vel_x: 2
 * /move_base/TebLocalPlannerROS/weight_obstacle: 100
 * /move_base/TebLocalPlannerROS/weight_optimaltime: 1
 * /move_base/TebLocalPlannerROS/weight_shortest_path: 0
 * /move_base/TebLocalPlannerROS/weight_viapoint: 1
 * /move_base/TebLocalPlannerROS/xy_goal_tolerance: 0.2
 * /move_base/TebLocalPlannerROS/yaw_goal_tolerance: 0.1
 * /move_base/base_local_planner: teb_local_planner...
 * /move_base/controller_frequency: 5.0
 * /move_base/controller_patience: 15.0
 * /move_base/global_costmap/cost_scaling_factor: 3.0
 * /move_base/global_costmap/footprint: [[-0.105, -0.105]...
 * /move_base/global_costmap/global_frame: map
 * /move_base/global_costmap/inflation_radius: 1.0
 * /move_base/global_costmap/map_type: costmap
 * /move_base/global_costmap/observation_sources: scan
 * /move_base/global_costmap/obstacle_range: 3.0
 * /move_base/global_costmap/publish_frequency: 10.0
 * /move_base/global_costmap/raytrace_range: 3.5
 * /move_base/global_costmap/robot_base_frame: base_footprint
 * /move_base/global_costmap/scan/clearing: True
 * /move_base/global_costmap/scan/data_type: LaserScan
 * /move_base/global_costmap/scan/marking: True
 * /move_base/global_costmap/scan/sensor_frame: laser_link
 * /move_base/global_costmap/scan/topic: scan
 * /move_base/global_costmap/static_map: True
 * /move_base/global_costmap/transform_tolerance: 0.5
 * /move_base/global_costmap/update_frequency: 10.0
 * /move_base/local_costmap/cost_scaling_factor: 3.0
 * /move_base/local_costmap/footprint: [[-0.105, -0.105]...
 * /move_base/local_costmap/global_frame: odom
 * /move_base/local_costmap/height: 3
 * /move_base/local_costmap/inflation_radius: 1.0
 * /move_base/local_costmap/map_type: costmap
 * /move_base/local_costmap/observation_sources: scan
 * /move_base/local_costmap/obstacle_range: 3.0
 * /move_base/local_costmap/publish_frequency: 10.0
 * /move_base/local_costmap/raytrace_range: 3.5
 * /move_base/local_costmap/resolution: 0.05
 * /move_base/local_costmap/robot_base_frame: base_footprint
 * /move_base/local_costmap/rolling_window: True
 * /move_base/local_costmap/scan/clearing: True
 * /move_base/local_costmap/scan/data_type: LaserScan
 * /move_base/local_costmap/scan/marking: True
 * /move_base/local_costmap/scan/sensor_frame: laser_link
 * /move_base/local_costmap/scan/topic: scan
 * /move_base/local_costmap/static_map: False
 * /move_base/local_costmap/transform_tolerance: 0.5
 * /move_base/local_costmap/update_frequency: 10.0
 * /move_base/local_costmap/width: 3
 * /move_base/planner_frequency: 1.0
 * /obs_vel: 0.3
 * /pedsim_simulator/pedsim_update_rate: 30.0
 * /pedsim_simulator/scene_file: /root/arena_ws/sr...
 * /pedsim_simulator/simulation_factor: 1.0
 * /plan_manager/look_ahead_distance: 2.3
 * /plan_manager/timeout_goal: 330.0
 * /plan_manager/timeout_subgoal: 20
 * /plan_manager/tolerance_approach: 0.6
 * /plan_manager/train_mode: False
 * /radius: 0.113
 * /robot_action_rate: 5
 * /rosdistro: noetic
 * /rosversion: 1.15.14
 * /show_viz: True
 * /single_env: True
 * /speed: 0.22
 * /step_size: 0.01
 * /task_generator_node/auto_reset: True
 * /task_generator_node/delta: 1.0
 * /task_generator_node/scenarios_json_path: /root/arena_ws/sr...
 * /task_generator_node/task_mode: scenario
 * /task_generator_node/timeout: 3.0
 * /train_mode: False
 * /update_rate: 500
 * /use_rviz: True
 * /use_sim_time: True
 * /viz_pub_rate: 30
 * /world_path: /root/arena_ws/sr...

NODES
  /
    flatland_rviz (rviz/rviz)
    flatland_server (flatland_server/flatland_server)
    inter_planner (arena_intermediate_planner/arena_intermediate_planner)
    map_server (map_server/map_server)
    map_to_odom_tfpublisher (tf2_ros/static_transform_publisher)
    move_base (move_base/move_base)
    pedsim_simulator (pedsim_simulator/pedsim_simulator)
    plan_manager (arena_plan_manager/plan_manager_node)
    spawn_model (rosservice/rosservice)
    task_generator_node (task_generator/task_generator_node.py)
  /sensorsim/
    sensorsim_node (sensor_simulator/sensorsim_node_tmgr.py)

auto-starting new master
process[master]: started with pid [2644]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 84e550f4-cd12-11ec-ac59-0242ac130003
process[rosout-1]: started with pid [2660]
started core service [/rosout]
process[flatland_server-2]: started with pid [2667]
process[spawn_model-3]: started with pid [2668]
process[flatland_rviz-4]: started with pid [2669]
process[map_server-5]: started with pid [2670]
process[map_to_odom_tfpublisher-6]: started with pid [2671]
process[task_generator_node-7]: started with pid [2672]
process[sensorsim/sensorsim_node-8]: started with pid [2673]
process[move_base-9]: started with pid [2674]
process[plan_manager-10]: started with pid [2679]
process[inter_planner-11]: started with pid [2681]
[ INFO] [1651823997.155403848]: waitForService: Service [/global_kino_make_plan] has not been advertised, waiting...
process[pedsim_simulator-12]: started with pid [2682]
start
[ INFO] [1651823997.188061405]: waitForService: Service [/static_map] has not been advertised, waiting...
QStandardPaths: XDG_RUNTIME_DIR not set, defaulting to '/tmp/runtime-root'
QStandardPaths: XDG_RUNTIME_DIR not set, defaulting to '/tmp/runtime-root'
[ INFO] [1651823997.319684030]: rviz version 1.14.14
[ INFO] [1651823997.319722830]: compiled against Qt version 5.12.8
[ INFO] [1651823997.319733290]: compiled against OGRE version 1.9.0 (Ghadamon)
[ INFO] [1651823997.322569955]: Updated sim with live config: Rate=24 incoming rate=24
[ INFO] [1651823997.329627631]: Forcing OpenGl version 0.
[ INFO] [1651823997.342950420]: Using default queue size of 1 for publisher queues... 
[ INFO] [1651823997.362650769]: Simulation params: world_yaml_file(/root/arena_ws/src/arena-rosnav/simulator_setup/maps/ignc/map.world.yaml), map_layer_yaml_file(/root/arena_ws/src/arena-rosnav/simulator_setup/maps/ignc/map_layer.yaml), map_file(ignc), update_rate(500.000000), step_size(0.010000) show_viz(true), viz_pub_rate(30.000000)
[ INFO] [1651823997.364142127]: Initialized
[ INFO] [1651823997.364166767]: Initializing...
[ INFO] [1651823997.364998111]: Loading scene [/root/arena_ws/src/arena-rosnav/simulator_setup/scenarios/empty.xml] for simulation
[ INFO] [1651823997.367669315]: created agent with id: 1
[ INFO] [1651823997.423675512]: Loading layer "static" from path="/root/arena_ws/src/arena-rosnav/simulator_setup/maps/ignc/map.yaml"
[ INFO] [1651823997.423840983]: layer "static" loading image from path="/root/arena_ws/src/arena-rosnav/simulator_setup/maps/ignc/map.pgm"
[ INFO] [1651823997.430108886]: Layer "static" loaded
[ INFO] [1651823997.430163396]: Leaving active layer "static"
[ INFO] [1651823997.430198316]: World loaded
[ INFO] [1651823997.431393892]: Visualizing layer/static
[ INFO] [1651823997.434384558]: Model spawning service ready to go
[ INFO] [1651823997.434409208]: Model deleting service ready to go
[ INFO] [1651823997.434422858]: Model moving service ready to go
[ INFO] [1651823997.434441878]: Simulation loop started
[ INFO] [1651823997.668255696, 1.180000000]: Loading model from path="/root/arena_ws/src/arena-rosnav/simulator_setup/robot/burger.model.yaml"
[ INFO] [1651823997.678294377, 1.180000000]: Model Plugin "diff_drive" type "DiffDrive" model "burger" loaded
[ INFO] [1651823997.678886930, 1.180000000]: Laser plugin loaded with 13 threads
[ INFO] [1651823997.679364123, 1.180000000]: Model Plugin "static_laser" type "Laser" model "burger" loaded
[ INFO] [1651823997.679459553, 1.180000000]: Model Plugin "tf_publisher" type "ModelTfPublisher" model "burger" loaded
[ INFO] [1651823997.679557684, 1.180000000]: Model "burger" loaded
[ INFO] [1651823997.735483101]: Stereo is NOT SUPPORTED
[ INFO] [1651823997.735547061]: OpenGL device: llvmpipe (LLVM 12.0.0, 256 bits)
[ INFO] [1651823997.735568231]: OpenGl version: 3.1 (GLSL 1.4).
======================================== reset:0
dynamic obstacles: 0
[ INFO] [1651823997.772829901]: waitForService: Service [/static_map] is now available.
[ INFO] [1651823997.773636355]: Is stacic map available: True
use_occ_esdf: 1
x_size: 25
y_size: 25
x_origin: -12.5
y_origin: -12.5
x_size_pix: 250
y_size_pix: 250
x_map_max_idx: 249
y_map_max_idx: 249
x_local_update_range_: 10
y_local_update_range_: 10
hit: 0.200671
miss: -1.38629
min log: -1.99243
max: 1.38629
thresh log: 0.847298
dist_next_wp_=3
lambda_heu_:0.1
origin_: -12.5 -12.5
map size: 25 25
origin_: -12.5 -12.5
map size: 25 25
[ERROR] [1651823997.831150571, 1.900000000]: Failed to load model! Exception: Flatland YAML: Model with name "burger" already exists
[ INFO] [1651823997.861979799, 2.020000000]: waitForService: Service [/global_kino_make_plan] is now available.
[ WARN] [1651823997.870575213, 2.100000000]: Map I got is empty. Timeout? Trying again.
[ WARN] [1651823997.971485830, 2.600000000]: global_costmap: Parameter "plugins" not provided, loading pre-Hydro parameters
[ INFO] [1651823997.987879274, 2.690000000]: global_costmap: Using plugin "static_layer"
[ INFO] [1651823997.995224412, 2.720000000]: Requesting the map...
[ INFO] [1651823998.002775641, 2.760000000]: Got map h x w: 250 x 250
[ INFO] [1651823998.005628035, 2.770000000]: node initialized, now running 
[ INFO] [1651823998.173478034, 3.600000000]: SpawnModelTool::SetMovingModelColor
[ WARN] [1651823998.173892186, 3.600000000]: OGRE EXCEPTION(2:InvalidParametersException): Object index out of bounds. in SceneNode::getAttachedObject at /build/ogre-1.9-kiU5_5/ogre-1.9-1.9.0+dfsg1/OgreMain/src/OgreSceneNode.cpp (line 160)
[ WARN] [1651823998.174408709, 3.600000000]: Invalid preview model
[ INFO] [1651823998.239270882, 3.900000000]: Creating 1 swatches
[ INFO] [1651823998.266981854, 4.030000000]: Resizing costmap to 250 X 250 at 0.100000 m/pix
[ INFO] [1651823998.287384018, 4.130000000]: Received a 250 X 250 map at 0.100000 m/pix
[ INFO] [1651823998.289463888, 4.140000000]: global_costmap: Using plugin "obstacle_layer"
[ INFO] [1651823998.291316788, 4.150000000]:     Subscribed to Topics: scan
[ INFO] [1651823998.302320365, 4.200000000]: global_costmap: Using plugin "inflation_layer"
[ WARN] [1651823998.326278798, 4.320000000]: local_costmap: Parameter "plugins" not provided, loading pre-Hydro parameters
[ INFO] [1651823998.333377124, 4.360000000]: local_costmap: Using plugin "obstacle_layer"
[ INFO] [1651823998.335072613, 4.370000000]:     Subscribed to Topics: scan
[spawn_model-3] process has finished cleanly
log file: /root/.ros/log/84e550f4-cd12-11ec-ac59-0242ac130003/spawn_model-3*.log
[ INFO] [1651823998.344078109, 4.410000000]: local_costmap: Using plugin "inflation_layer"
[ INFO] [1651823998.370998977, 4.540000000]: Created local_planner teb_local_planner/TebLocalPlannerROS
[ INFO] [1651823998.409368333, 4.730000000]: Footprint model 'point' loaded for trajectory optimization.
[ INFO] [1651823998.409442293, 4.730000000]: Parallel planning in distinctive topologies enabled.
[ INFO] [1651823998.409479033, 4.730000000]: No costmap conversion plugin specified. All occupied costmap cells are treaten as point obstacles.
[ INFO] [1651823998.453104607, 4.950000000]: Footprint model 'point' loaded for trajectory optimization.
[ INFO] [1651823998.506385351, 5.210000000]: Recovery behavior will clear layer 'obstacles'
[ INFO] [1651823998.510118700, 5.230000000]: Recovery behavior will clear layer 'obstacles'
[ INFO] [1651823998.623072879, 5.800000000]: odom received!
[ INFO] [1651823998.631596113, 5.840000000]: Creating 1 swatches
[ INFO] [1651823998.632074625, 5.840000000]: Creating 1 swatches
Traceback (most recent call last):
  File "/root/arena_ws/src/arena-rosnav/task_generator/scripts/task_generator_node.py", line 120, in <module>
    task_generator = TaskGenerator()
  File "/root/arena_ws/src/arena-rosnav/task_generator/scripts/task_generator_node.py", line 23, in __init__
    self.task = get_predefined_task("",mode, PATHS=paths)
  File "/root/arena_ws/src/arena-rosnav/task_generator/task_generator/tasks.py", line 724, in get_predefined_task
    task = ScenarioTask(
  File "/root/arena_ws/src/arena-rosnav/task_generator/task_generator/tasks.py", line 602, in __init__
    self.pedsim_manager = PedsimManager()
  File "/root/arena_ws/src/arena-rosnav/task_generator/task_generator/tasks.py", line 545, in __init__
    rospy.wait_for_service(pawn_interactive_obstacles_service_name, 6.0)
  File "/opt/ros/noetic/lib/python3/dist-packages/rospy/impl/tcpros_service.py", line 148, in wait_for_service
    raise ROSException("timeout exceeded while waiting for service %s"%resolved_name)
rospy.exceptions.ROSException: timeout exceeded while waiting for service /pedsim_simulator/spawn_interactive_obstacles
[task_generator_node-7] process has died [pid 2672, exit code 1, cmd /root/arena_ws/src/arena-rosnav/task_generator/scripts/task_generator_node.py __name:=task_generator_node __log:=/root/.ros/log/84e550f4-cd12-11ec-ac59-0242ac130003/task_generator_node-7.log].
log file: /root/.ros/log/84e550f4-cd12-11ec-ac59-0242ac130003/task_generator_node-7*.log

How can I use pedsim in flatland?

I want to use Pedsim in Flatland, so I made it by referring to the files in rosnav3d, but it doesn't work well. If the flatland model runs without applying the pedsim plugin, the pedsim simulator publishes a topic well, but if applied, it publishes an empty topic and the simulator dies. I wonder if you have ever applied pedsim to flatland. If you have, I would appreciate it if you could tell me how. Thank you.

[error] Training on the GPU Server

Your work is very good.
When I follow the tutorial “Training on the GPU Server”, I encountered some problems.
Now I execute the following code:
python scripts/training/train_agent.py --load pretrained_ppo_mpc --n_envs 24 --eval_log
But, It reminds me that the observation space does not match. The detailed error information is as follows:

(sim_3) Stage 1: Spawning 6 static and 0 dynamic obstacles!
/home/server/python_env/rosnav/lib/python3.8/site-packages/gym/spaces/box.py:73: UserWarning: WARN: Box bound precision lowered by casting to float32
  logger.warn(
(sim_4) Stage 1: Spawning 6 static and 0 dynamic obstacles!
Traceback (most recent call last):
  File "scripts/training/train_agent.py", line 217, in <module>
    main()
  File "scripts/training/train_agent.py", line 189, in main
    model = PPO.load(os.path.join(PATHS["model"], AGENT_NAME), env)
  File "/home/server/workspace/arena3D_ws/src/forks/stable-baselines3/stable_baselines3/common/base_class.py", line 628, in load
    check_for_correct_spaces(env, data["observation_space"], data["action_space"])
  File "/home/server/workspace/arena3D_ws/src/forks/stable-baselines3/stable_baselines3/common/utils.py", line 207, in check_for_correct_spaces
    raise ValueError(f"Observation spaces do not match: {observation_space} != {env.observation_space}")
ValueError: Observation spaces do not match: Box([ 0.         0.         0.         0.         0.         0. .............

I hope you can give me some suggestions. Thank you!

Error processing '../forks/navigation/local_planner/teb'

Based on #49 (comment) I tried aspects of the Common error handling https://github.com/ignc-research/arena-rosnav/blob/local_planner_subgoalmode/docs/guide.md#common-error-handling

(rosnav) ➜  arena_ws cd src/arena-rosnav 
(rosnav) ➜  arena-rosnav git:(local_planner_subgoalmode) git pull                                   
Already up to date.
(rosnav) ➜  arena-rosnav git:(local_planner_subgoalmode) rosws update     
[../forks/flatland] Fetching https://github.com/ignc-research/flatland (version dev_multi_lei) to /root/arena_ws/src/forks/flatland
Cloning into '/root/arena_ws/src/forks/flatland'...
remote: Enumerating objects: 7496, done.
remote: Counting objects: 100% (896/896), done.
remote: Compressing objects: 100% (229/229), done.
remote: Total 7496 (delta 622), reused 828 (delta 604), pack-reused 6600
Receiving objects: 100% (7496/7496), 1.80 MiB | 2.85 MiB/s, done.
Resolving deltas: 100% (5376/5376), done.
[../forks/flatland] Done.
[../forks/stable-baselines3] Fetching https://github.com/ignc-research/stable-baselines3 (version master) to /root/arena_ws/src/forks/stable-baselines3
Cloning into '/root/arena_ws/src/forks/stable-baselines3'...
remote: Enumerating objects: 7223, done.
remote: Total 7223 (delta 0), reused 0 (delta 0), pack-reused 7223
Receiving objects: 100% (7223/7223), 2.75 MiB | 6.01 MiB/s, done.
Resolving deltas: 100% (5304/5304), done.
[../forks/stable-baselines3] Done.
[../forks/navigation/local_planner/teb] Fetching https://github.com/rst-tu-dortmund/teb_local_planner (version melodic-devel) to /root/arena_ws/src/forks/navigation/local_planner/teb
Cloning into '/root/arena_ws/src/forks/navigation/local_planner/teb'...
remote: Enumerating objects: 3856, done.
remote: Counting objects: 100% (1562/1562), done.
remote: Compressing objects: 100% (154/154), done.
remote: Total 3856 (delta 1488), reused 1410 (delta 1408), pack-reused 2294
Receiving objects: 100% (3856/3856), 1.62 MiB | 498.00 KiB/s, done.
Resolving deltas: 100% (2769/2769), done.
fatal: BUG: initial ref transaction called with existing refs
[../forks/navigation/local_planner/mpc] Fetching https://github.com/rst-tu-dortmund/mpc_local_planner (version master) to /root/arena_ws/src/forks/navigation/local_planner/mpc
Cloning into '/root/arena_ws/src/forks/navigation/local_planner/mpc'...
remote: Enumerating objects: 430, done.
remote: Counting objects: 100% (42/42), done.
remote: Compressing objects: 100% (35/35), done.
remote: Total 430 (delta 16), reused 20 (delta 5), pack-reused 388
Receiving objects: 100% (430/430), 183.08 KiB | 7.96 MiB/s, done.
Resolving deltas: 100% (256/256), done.
[../forks/navigation/local_planner/mpc] Done.
[../forks/navigation/msgs/ford] Fetching https://bitbucket.org/acl-swarm/ford_msgs/src/master (version master) to /root/arena_ws/src/forks/navigation/msgs/ford
Cloning into '/root/arena_ws/src/forks/navigation/msgs/ford'...
Receiving objects: 100% (239/239), 1019.89 KiB | 2.93 MiB/s, done.
Resolving deltas: 100% (100/100), done.
[../forks/navigation/msgs/ford] Done.
[../forks/pedsim_ros] Fetching https://github.com/ignc-research/pedsim_ros (version master) to /root/arena_ws/src/forks/pedsim_ros
Cloning into '/root/arena_ws/src/forks/pedsim_ros'...
remote: Enumerating objects: 5262, done.
remote: Counting objects: 100% (5262/5262), done.
remote: Compressing objects: 100% (1757/1757), done.
remote: Total 5262 (delta 3795), reused 4678 (delta 3223), pack-reused 0
Receiving objects: 100% (5262/5262), 24.49 MiB | 22.17 MiB/s, done.
Resolving deltas: 100% (3795/3795), done.
Submodule path '2ndparty/spencer_messages': checked out '3b392e7e5ba367dd23a3cc07e934e558229437d4'
Submodule path '2ndparty/spencer_tracking_rviz_plugin': checked out 'd14353d13efe74a7748d26b670811de737241ca8'
[../forks/pedsim_ros] Done.
[../forks/arena-tools] Fetching https://github.com/Jacenty00/arena-tools (version main) to /root/arena_ws/src/forks/arena-tools
Cloning into '/root/arena_ws/src/forks/arena-tools'...
remote: Enumerating objects: 380, done.
remote: Counting objects: 100% (380/380), done.
remote: Compressing objects: 100% (285/285), done.
remote: Total 380 (delta 227), reused 224 (delta 92), pack-reused 0
Receiving objects: 100% (380/380), 1.85 MiB | 563.00 KiB/s, done.
Resolving deltas: 100% (227/227), done.
fatal: BUG: initial ref transaction called with existing refs
[../forks/jackal] Fetching https://github.com/jackal/jackal.git (version None) to /root/arena_ws/src/forks/jackal
Cloning into '/root/arena_ws/src/forks/jackal'...
remote: Enumerating objects: 2651, done.
remote: Counting objects: 100% (390/390), done.
remote: Compressing objects: 100% (94/94), done.
remote: Total 2651 (delta 322), reused 296 (delta 296), pack-reused 2261
Receiving objects: 100% (2651/2651), 12.82 MiB | 22.88 MiB/s, done.
Resolving deltas: 100% (1735/1735), done.
[../forks/jackal] Done.
Exception caught during install: Error processing '../forks/navigation/local_planner/teb' : [../forks/navigation/local_planner/teb] Checkout of https://github.com/rst-tu-dortmund/teb_local_planner version melodic-devel into /root/arena_ws/src/forks/navigation/local_planner/teb failed.
Error processing '../forks/arena-tools' : [../forks/arena-tools] Checkout of https://github.com/Jacenty00/arena-tools version main into /root/arena_ws/src/forks/arena-tools failed.

ERROR in config: Error processing '../forks/navigation/local_planner/teb' : [../forks/navigation/local_planner/teb] Checkout of https://github.com/rst-tu-dortmund/teb_local_planner version melodic-devel into /root/arena_ws/src/forks/navigation/local_planner/teb failed.
Error processing '../forks/arena-tools' : [../forks/arena-tools] Checkout of https://github.com/Jacenty00/arena-tools version main into /root/arena_ws/src/forks/arena-tools failed.

[task_generator_node-6] process has died

This project is interesting. When I launch "arena_bringup start_arena_flatland.launch" firstly, there are some issues:

  1. The bash shows "[task_generator_node-6] process has died" but the robot can navigation correctly. How to address this?
  2. Also, bash shows "Failed to load model! Exception: Flatland YAML: Model with name "burger" already exists". Seems like I don't need to care about it?
  3. I try to replace teb of local_planner with arena in "arena_bringup start_arena_flatland.launch". The robot can move to the goal but cannot stop here instead toss. Is this due to me not training the network?

start_arena_flatland.launch not found

I am using the docker version of arena-rosnav and I get the following error message:

(rosnav) ➜  ~ roslaunch arena_bringup start_arena_flatland.launch
RLException: [start_arena_flatland.launch] is neither a launch file in package [arena_bringup] nor is [arena_bringup] a launch file name
The traceback for the exception was written to the log file

I am using Ubuntu 20.04 and started the docker images according to https://github.com/ignc-research/arena-rosnav/blob/local_planner_subgoalmode/docs/Docker.md

After entering the ros containter from vscode, I activated workon rosnav and executed roslaunch arena_bringup start_arena_flatland.launch https://github.com/ignc-research/arena-rosnav/blob/local_planner_subgoalmode/docs/guide.md#start-a-simulation.

Map update loop missed its desired rate of 10.0000Hz...

Hi I'm getting this warning while running the default code from noetic-devel branch.

python scripts/training/train_agent.py --agent MLP_ARENA2D

Example warnings:
[ WARN] [1647671519.840101736, 92308.850000000]: Map update loop missed its desired rate of 10.0000Hz... the loop actually took 0.1800 seconds
[ WARN] [1647671519.849543441, 92309.060000000]: Map update loop missed its desired rate of 10.0000Hz... the loop actually took 0.1900 seconds
[ WARN] [1647671519.866806290, 92309.400000000]: Map update loop missed its desired rate of 10.0000Hz... the loop actually took 0.2300 seconds

My CPU and GPU usage remains very low. Any idea how to avoid this if I still want to maintain 10hz?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.