Simulation of Pedestrians and an Autonomous Car in Shared Spaces
The implementation is based on Pedsim_ros, ROS packages that wrap a crowd simulator based on Christian Gloor's libpedsim library.
The pedestrian model is based on the social force model of Helbing et. al.
This package is useful to support Autonomous vehicle (AV) developments that require the simulation of pedestrians and an AV in various shared spaces scenarios.
It allows:
1. in simulation, to pre-test AV navigation algorithms in various crowd scenarios,
2. in real crowds, to help online prediction of pedestrian trajectories around the AV.
- Features
- Installation
- AV control modes
- Launch files
- Scenarios
- Reference papers
- License
- Contributors
- Acknowledgements
- Heterogeneous crowds in shared spaces for simulation and prediction of 100 pedestrians in real time.
- Individuals and groups walking using social force model, with various social relationships
- Prius AV model (from https://github.com/osrf/car_demo/tree/master/prius_description) or Zoe AV model (from https://univ-nantes.io/hamon-a/icars-public), controlled from within the simulation or by an external ROS controller publishing velocity commands.
- Pedestrians reactions to the AV
- 3 shared space environments (business area, campus, citer center) and 8 scenarios for each env. ready to test AV navigation algorithms
- Sensors simulation (point clouds in AV frame for people and walls)
- XML based scene design
- Visualization using Rviz
- Optional plugin to connect with Gazebo
Tested on:
- Ubuntu 16.04 with ROS Kinetic and Gazebo7 (master branch)
- Ubuntu 18.04 with ROS Melodic and Gazebo9 (master branch)
- Ubuntu 20.04 with ROS Noetic and Gazebo11 (noetic branch)
Requires:
- ROS with the navigation and visualization stack
- C++11 compiler (or C++14 for Noetic)
- Qt4 (or Qt5 for Noetic)
- Gazebo if pedsim_gazebo_plugin is used
cd [workspace]/src
git clone https://github.com/maprdhm/Spaciss.git
cd Spaciss
git submodule update --init --recursive
cd ../..
catkin_make or catkin build (twice at the first time)
roslaunch experimental_package business_area.launch
The previous command should start the simulator with the business area environment and the shared space scenario (many pedestrians and an AV).
More launch files are in the experimental_package/launch
repository.
Ready to test scenarios are in the experimental_package/scenarios
repository.
roslaunch pedsim_gazebo_plugin scene1.launch
The previous command should start the simulator and Gazebo with some pedestrians.
roslaunch experimental_package multi_node_parallel.launch
The previous command starts 2 simulations with the business area environment and the shared space scenario, with AV max speed of 2m/s and 4m/s respectively.
The AV in the simulator is controlled externally using any controller than sends Twist messages.
Example with the AV controlled by move_base planner:
roslaunch experimental_package business_area_external.launch
and to send goals to the planner:
rostopic pub /move_base_simple/goal geometry_msgs/PoseStamped '{header: {stamp: now, frame_id: "odom"}, pose: {position: {x: -10.0, y: 10.0, z: 0.0}, orientation: {w: 1.0}}}'
The AV in the simulator is controlled by the social force model, like for pedestrians.
For now, the social force is configured to have the AV go straight to its destination, trying to avoid walls but not pedestrians.
- simulator node
- visualizer node + rviz node
- sensor node
- robot controller node and move_base node
- timer node to shutdown all nodes after a timelapse
Parameter | Use | Default value | Possible values |
---|---|---|---|
visualize | Rviz visualisation | true | boolean |
simulation_factor | Simulation speed up | 1.0 | double |
update_rate | Simuation step (Hz) | 25.0 (0.04 s) | double |
scene_file | Scenario | "$(find experimental_package)scenarios/business_area/shared_space.xml" | absolute path to xml scenario file |
default_queue_size | size of queue for published msgs | 10 | int |
Parameter | Use | Default value | Possible values |
---|---|---|---|
kbd_teleop | Keyboard control of AV | false | boolean |
rqt_teleop | ROS rqt control of the AV (UI) | false | boolean |
with_robot | Simulation with an AV | true | boolean |
pose_initial_x | x postion of the AV | 5.0 | double |
pose_initial_y | y postion of the AV | 5.0 | double |
pose_initial_theta | Orientation of the AV | 0.0 | double |
robot_description | URDF model of AV | prius.urdf | absolute path to urdf file |
max_robot_speed | Max speed of AV (m/s) | 3.0 | double |
robot_mode | AV control mode | 1 | 0 or 1: teleoperation / 2: social_drive (with SFM) |
Parameter | Use | Default value | Possible values |
---|---|---|---|
enable_distraction | Agent visual distraction | false | boolean |
probability_random_stop | Agent probability to do a temporary stop | 0.0 | double [0..1] |
Parameter | Use | Default value | Possible values |
---|---|---|---|
enable_groups | Groups presence | true | boolean |
group_size_lambda | Lambda parameter in Poisson law distribution for groups sizes | 1.1 | double>0 |
groups_couples_proportion | Proportion of couples in groups | 0.0 | double [0..1] Couples can only be groups of 2. If proportion(group_size=2) < groups_couples_proportion -> generated groups_couples_proportion < groups_couples_proportion |
groups_friends_proportion | Proportion of couples in groups | 1.0 | double [0..1] |
groups_families_proportion | Proportion of couples in groups | 0.0 | double [0..1] |
groups_coworkers_proportion | Proportion of couples in groups | 0.0 | double [0..1] |
<scenario>
<waypoint id="wu" x="0" y="-20" r="2" b="2"/>
<waypoint id="wd" x="0" y=" 20" r="2" />
<obstacle x1="10" y1="30" x2="10" y2="-30"/>
<agent x="0" y="-30" n="12" dx="10" dy="10" type="0" purpose="1">
<addwaypoint id="wd" />
<addwaypoint id="wu" />
</agent>
</scenario>
Parameter | Use | Possible values |
---|---|---|
id | Identifiant | string |
x | x position | double |
y | y position | double |
r (opt, default 0) | radius | double |
b (opt, default 0) | behaviour | 0: simple / 1: source / 2: sink |
Parameter | Use | Possible values |
---|---|---|
x1 | x1 position: obstacle start | double |
y1 | y1 position: obstacle start | double |
x2 | x2 position: obstacle end | double |
y2 | y2 position: obstacle end | double |
Parameter | Use | Possible values |
---|---|---|
x | x initial position | double |
y | y initial position | double |
n | Number of agents, to change crowd density | int |
dx (opt if n=1) | Dispersion of agents along x axis | double |
dy (opt if n=1) | Dispersion of agents along y axis | double |
type (opt, default 0) | Agent type (affects the max speed and force desired for elderly, affects the max speed/size/max rotation angle/force social and force obstacle for robot) | 0: adult / 1: child (unused) / 2: robot (=AV) / 3: elder / 4: immob (stationary) |
purpose (opt, default 0) | Trip purpose of agent (affects the max speed except for robot and elderly) | 0: unknown / 1: work / 2: leisure |
addwaypoint | id | id of a waypoint |
Parameter | Use | Possible values |
---|---|---|
x | x initial position | double |
y | y initial position | double |
n | Number of agents | int |
dx (opt if n=1) | Dispersion of agents along x axis | double |
dy (opt if n=1) | Dispersion of agents along y axis | double |
type (opt, default 0) | Agent type | 0: adult / 1: child (unused) / 2: robot (=AV) / 3: elder / 4: immob (stationary) |
purpose (opt, default 0) | Trip purpose of agent | 0: unknown / 1: work / 2: leisure |
addwaypoint | id | id of a waypoint |
Parameter | Use | Possible values |
---|---|---|
id | Identifiant | string |
x | x initial position | double |
y | y initial position | double |
width | Width of attraction zone | double |
height | Height of attraction zone | double |
strength | Attraction strength | double |
Manon Prédhumeau. 2021. Simulating Realistic Pedestrian Behaviors in the Context of Autonomous Vehicles in Shared Spaces: Doctoral Consortium. In Proc. of the 20th International Conference on Autonomous Agents and Multiagent Systems (AAMAS 2021), May 3–7, 2021, IFAAMAS, 3 pages. http://www.ifaamas.org/Proceedings/aamas2021/pdfs/p1829.pdf
Manon Prédhumeau. 2021. Modélisation et simulation de comportements piétons réalistes en espace partagé avec un véhicule autonome. Université Grenoble Alpes. Français. tel-03518751
The core libpedsim
is licensed under LGPL.
The ROS integration and extensions are licensed under BSD.
Manon Prédhumeau, Lyuba Mancheva, Julie Dugdale, Anne Spalanzani
The package is a work in progress mainly used in research prototyping.
This work has been developed as part of the HIANIC project.