ROS packages for a 2D pedestrian simulator based on social force model of Helbing et. al. The implementation is based on an extended version of Christian Gloor's libpedsim library which has been extended to include additional behaviors and activities. This packages is useful for robot navigation experiments with crowded scenes which are hard to acquire in practice.
- Individual walking using social force model for very large crowds in real time
- Group walking using the extended social force model
- Individual static social agents
- Individual frame following social agent
- Social activities simulation
- Sensors simulation (point clouds in robot frame for people and walls)
- XML based scene design
- Extensive visualization using Rviz
- Option to connect with gazebo for physics reasoning
- ROS with the visualization stack (currently tested on
hydro
,indigo
,kinetic
). Formelodic
, see the branchmelodic-devel
- C++11 compiler and for
noetic
, see the branchnoetic-devel
.
The default version is now noetic-devel
.
cd [workspace]/src
git clone https://github.com/srl-freiburg/pedsim_ros.git
cd pedsim_ros
catkin build # or catkin_make
roslaunch pedsim_simulator simple_pedestrians.launch
Note: currently /pedbot
is not working.
To start simulating people, the launch file simulator.launch
in the package pedsim_simulator
is used. This launch file starts a /pedsim_simulator
node. The published and subscribed topics are described below:
- /pedsim_simulator/parameter_descriptions (dynamic_reconfigure/ConfigDescription)
- /pedsim_simulator/parameter_updates (dynamic_reconfigure/ConfigDescription)
- /pedsim_simulator/robot_position (nav_msgs/Odometry)
- /pedsim_simulator/simulated_agents (pedsim_msgs/AgentStates)
- /pedsim_simulator/simlated_groups (pedsim_msgs/AgentGroups)
- /pedsim_simulator/simulated_walls (pedsim_msgs/LineObstacles)
- /pedsim_simulator/simulated_waypoints (pedsim_msgs/Waypoints)
- /tf (tf2_msgs/TFMessage)
- /pedsim_simulator/pause_simulation (std_srvs/Empty)
- /pedsim_simulator/unpause_simulation (std_srvs/Empty)
-
output (string, default: screen)
If output desired from the node, can either be
screen
orlog
. -
kbd_teleop (bool, default: false)
If set to True, a keyboard teleop is initialized in the terminal.
-
rqt_teleop (bool, default: false)
If set to True, a new rqt teleop window is opened.
-
scene_file (string, default: pedsim_simulator/scenarios/social_contexts.xml)
Scenario file in which social agents are defined along with their waypoints and obstacles as well as other configurations. To see how a scenario file is defined, check scenario setup.
-
with_robot (bool, default: true)
If robot should be spawned and considered by the social agents.
-
simulation_factor (double, default: 1)
The time factor between real time and the simulation.
-
update_rate (double, default: 25)
Frequency of the social agents state update.
-
default_queue_size (int, default: 10)
Queue size of the publishers in the node.
-
max_robot_speed (double, default: 1.5)
Maximum velocity of the robot if controlled by the social force model in pedsim. (Currently not working)
-
robot_mode (int, default: 1)
This value can be: 0 - controlled | 1 - teleoperation | 3 - social drive.
-
enable_groups (bool, default: true)
If set to true, group interactions are simulated and published.
-
pose_initial_x (double, default: 5.0)
The initial position of the robot in the x-axis.
-
pose_initial_y (double, default: 5.0)
The initial position of the robot in the y-axis.
-
pose_initial_theta (double, default: 0.0)
The initial orientation of the robot.
-
detect_frozen_agents (bool, default: true)
If set to true, the social agents are analyzed and identified when they have been stuck in a place and then assigned to a random waypoint.
-
force_obstacle (double, default: 10.0)
Defines the force factor magnitude coming from obstacles.
-
sigma_obstacle (double, default: 0.2)
Corresponds to the range of interaction with obstacles.
-
force_social (double, default: 5.1)
Defines the force factor magnitude coming from social agents.
-
force_group_gaze (double, default: 3.0)
Not used.
-
force_group_coherence (double, default: 3.0)
Not used.
-
force_group_repulsion (double, default: 1.0)
Not used.
-
force_random (double, default: 0.1)
Not used.
-
force_wall (double, default: 2.0)
Not used.
-
frame_id (string, default: odom)
Main reference frame for the position of social agents.
-
robot_base_frame_id (string, default: base_footprint)
Main robot frame to be considered as the robot's position by pedsim.
-
obstacle_offset_x (double, default: 0.0)
Walls and other obstacles position offset in the x-axis.
-
obstacle_offset_y (double, default: 0.0)
Walls and other obstacles position offset in the x-axis.
-
world_frame (string, default: odom)
Main frame in the tree.
-
robot_frame (string, default: base_footprint)
Robot frame transform published by pedsim.
-
publish_tf (string, default: true)
Publishes transform of the robot_frame, if set to false, the transform has to be published manually.
To have the transforms, these can be obtained running the pedsim_frames_publisher.py
from package pedsim_simulator
as follows:
<node pkg="pedsim_gazebo_plugin" type="spawn_pedsim_agents.py" name="spawn_pedsim_agents" output="screen" />
To make social agents appear in gazebo and move around, some other steps are required. First, run the spawn_pedsim_agents.py
node from package pedsim_gazebo_plugin
as follows:
<node pkg="pedsim_gazebo_plugin" type="spawn_pedsim_agents.py" name="spawn_pedsim_agents" output="screen" />
Second, in the *.world
file used, the following an Actor Poses plugin must be added as follows (check empy_world.py):
<plugin name="ActorPosesPlugin" filename="libActorPosesPlugin.so"></plugin>
For visualization of the social agents in rviz, it is important to run the node pedsim_visualizer_node
from the package pedsim_visualizer
.
- /pedsim_visualizer/forces (visualization_msgs/MarkerArray)
- /pedsim_visualizer/tracked_groups (pedsim_msgs/TrackedGroups)
- /pedsim_visualizer/tracked_persons (pedsim_msgs/TrackedPersons)
- /pedsim_visualizer/walls (visualization_msgs/Marker)
- /pedsim_visualizer/waypoints (visualization_msgs/MarkerArray)
- /pedsim_simulator/simulated_agents (pedsim_msgs/AgentStates)
- /pedsim_simulator/simlated_groups (pedsim_msgs/AgentGroups)
- /pedsim_simulator/simulated_walls (pedsim_msgs/LineObstacles)
- /pedsim_simulator/simulated_waypoints (pedsim_msgs/Waypoints)
The core libpedsim
is licensed under LGPL. The ROS integration and extensions are licensed under BSD.
- Billy Okal
- Timm Linder
- Dizan Vasquez
- Sven Wehner
- Omar Islas
- Luigi Palmieri
The package is a work in progress mainly used in research prototyping. Pull requests and/or issues are highly encouraged.
These packages have been developed in part during the EU FP7 project SPENCER