├── 2ndparty ├── spencer_messages │ ├── .gitignore │ ├── LICENSE │ ├── README.md │ ├── spencer_control_msgs │ │ ├── CATKIN_IGNORE │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── CMakeLists.txt~ │ │ ├── LICENSE │ │ ├── msg │ │ │ └── ComponentStatus.msg │ │ └── package.xml │ ├── spencer_human_attribute_msgs │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── LICENSE │ │ ├── msg │ │ │ ├── CategoricalAttribute.msg │ │ │ ├── HumanAttributes.msg │ │ │ └── ScalarAttribute.msg │ │ └── package.xml │ ├── spencer_social_relation_msgs │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── LICENSE │ │ ├── msg │ │ │ ├── SocialActivities.msg │ │ │ ├── SocialActivity.msg │ │ │ ├── SocialRelation.msg │ │ │ └── SocialRelations.msg │ │ └── package.xml │ ├── spencer_tracking_msgs │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── LICENSE │ │ ├── msg │ │ │ ├── CompositeDetectedPerson.msg │ │ │ ├── CompositeDetectedPersons.msg │ │ │ ├── DetectedPerson.msg │ │ │ ├── DetectedPersons.msg │ │ │ ├── ImmDebugInfo.msg │ │ │ ├── ImmDebugInfos.msg │ │ │ ├── PersonTrajectory.msg │ │ │ ├── PersonTrajectoryEntry.msg │ │ │ ├── TrackedGroup.msg │ │ │ ├── TrackedGroups.msg │ │ │ ├── TrackedPerson.msg │ │ │ ├── TrackedPerson2d.msg │ │ │ ├── TrackedPersons.msg │ │ │ ├── TrackedPersons2d.msg │ │ │ └── TrackingTimingMetrics.msg │ │ ├── package.xml │ │ └── srv │ │ │ └── GetPersonTrajectories.srv │ └── spencer_vision_msgs │ │ ├── CHANGELOG.rst │ │ ├── CMakeLists.txt │ │ ├── LICENSE │ │ ├── msg │ │ ├── PersonImage.msg │ │ ├── PersonImages.msg │ │ ├── PersonROI.msg │ │ └── PersonROIs.msg │ │ └── package.xml └── spencer_tracking_rviz_plugin │ ├── .gitignore │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── LICENSE │ ├── README.md │ ├── icons │ └── classes │ │ ├── DetectedPersons.png │ │ ├── HumanAttributes.png │ │ ├── SocialActivities.png │ │ ├── SocialRelations.png │ │ ├── TrackedGroups.png │ │ └── TrackedPersons.png │ ├── media │ ├── animated_walking_man.mesh │ ├── animated_walking_man.skeleton │ ├── female_symbol.dae │ └── male_symbol.dae │ ├── package.xml │ ├── plugin_description.xml │ ├── screenshots │ ├── detected_persons.png │ ├── human_attributes.png │ ├── social_activities.png │ ├── social_relations.png │ ├── tracked_groups.png │ ├── tracked_persons_1.png │ ├── tracked_persons_2.png │ └── tracked_persons_3.png │ ├── scripts │ └── send_test_msgs.py │ └── src │ ├── additional_topic_subscriber.h │ ├── detected_persons_display.cpp │ ├── detected_persons_display.h │ ├── human_attributes_display.cpp │ ├── human_attributes_display.h │ ├── person_display_common.cpp │ ├── person_display_common.h │ ├── social_activities_display.cpp │ ├── social_activities_display.h │ ├── social_relations_display.cpp │ ├── social_relations_display.h │ ├── tracked_groups_display.cpp │ ├── tracked_groups_display.h │ ├── tracked_persons_cache.cpp │ ├── tracked_persons_cache.h │ ├── tracked_persons_display.cpp │ ├── tracked_persons_display.h │ └── visuals │ ├── covariance_visual.h │ ├── mesh_node.h │ ├── person_visual.cpp │ ├── person_visual.h │ └── text_node.h ├── 3rdparty ├── CMakeLists.txt └── libpedsim │ ├── .gitignore │ ├── CMakeLists.txt │ ├── LICENSE │ ├── README.md │ ├── include │ └── pedsim │ │ ├── ped_agent.h │ │ ├── ped_angle.h │ │ ├── ped_includes.h │ │ ├── ped_obstacle.h │ │ ├── ped_scene.h │ │ ├── ped_tree.h │ │ ├── ped_vector.h │ │ └── ped_waypoint.h │ ├── package.xml │ └── src │ ├── ped_agent.cpp │ ├── ped_angle.cpp │ ├── ped_obstacle.cpp │ ├── ped_scene.cpp │ ├── ped_tree.cpp │ ├── ped_vector.cpp │ └── ped_waypoint.cpp ├── History.md ├── LICENSE ├── README.md ├── pedsim_gazebo_plugin ├── CMakeLists.txt ├── README.md ├── launch │ ├── airport.launch │ ├── airport_activities2.launch │ ├── altorfer.launch │ ├── autolab.launch │ ├── cumberland.launch │ ├── eng_hall.launch │ ├── frieburg.launch │ ├── frieburg_origin.launch │ ├── nav_test.launch │ ├── scene1.launch │ ├── scene3.launch │ ├── scene4.launch │ ├── shopping.launch │ ├── singleagent.launch │ ├── skirkanich.launch │ ├── small_airport.launch │ ├── social_contexts.launch │ └── social_contexts_house.launch ├── models │ ├── actor_model.config │ ├── actor_model.sdf │ └── person_standing │ │ ├── actor_model.config │ │ ├── actor_model.sdf │ │ ├── materials │ │ └── textures │ │ │ ├── eyebrow001-unmodified.png │ │ │ ├── eyebrow001.png │ │ │ ├── green_eye.png │ │ │ ├── jeans01_normals.png │ │ │ ├── jeans_basic_diffuse.png │ │ │ ├── male02_diffuse_black-unmodified.png │ │ │ ├── male02_diffuse_black.png │ │ │ ├── teeth.png │ │ │ ├── tshirt02_normals.png │ │ │ ├── tshirt02_texture.png │ │ │ └── young_lightskinned_male_diffuse.png │ │ ├── meshes │ │ ├── eyebrow001-unmodified.png │ │ ├── eyebrow001.png │ │ ├── green_eye.png │ │ ├── jeans01_normals.png │ │ ├── jeans_basic_diffuse.png │ │ ├── male02_diffuse_black-unmodified.png │ │ ├── male02_diffuse_black.png │ │ ├── standing.dae │ │ ├── standing_color.dae │ │ ├── standingv2.dae │ │ ├── teeth.png │ │ ├── tshirt02_normals.png │ │ ├── tshirt02_texture.png │ │ ├── walk.dae │ │ └── young_lightskinned_male_diffuse.png │ │ ├── model.config │ │ └── model.sdf ├── package.xml ├── scripts │ ├── pedsim_to_gazbo_world.py │ └── spawn_pedsim_agents.py ├── src │ └── actor_poses_plugin.cpp └── worlds │ ├── .world │ ├── airport.world │ ├── airport_activities2.world │ ├── altorfer.world │ ├── autolab.world │ ├── av_test.world │ ├── cumberland.world │ ├── cumberland_orignal.world │ ├── eng_hall.world │ ├── eng_hall_changed.world │ ├── freiburg.world │ ├── freiburg_origin.world │ ├── nav_test.world │ ├── nav_test_xml.world │ ├── scene1.world │ ├── scene3.world │ ├── scene4.world │ ├── shopping.world │ ├── singleagent.world │ ├── skirkanich.world │ ├── small_airport.world │ ├── social_activities.world │ ├── social_contexts.world │ └── social_contexts_house.world ├── pedsim_msgs ├── CMakeLists.txt ├── msg │ ├── AgentForce.msg │ ├── AgentGroup.msg │ ├── AgentGroups.msg │ ├── AgentState.msg │ ├── AgentStates.msg │ ├── AllAgentsState.msg │ ├── LineObstacle.msg │ ├── LineObstacles.msg │ ├── SocialActivities.msg │ ├── SocialActivity.msg │ ├── SocialRelation.msg │ ├── SocialRelations.msg │ ├── TrackedGroup.msg │ ├── TrackedGroups.msg │ ├── TrackedPerson.msg │ ├── TrackedPersons.msg │ ├── Waypoint.msg │ └── Waypoints.msg └── package.xml ├── pedsim_ros ├── CMakeLists.txt └── package.xml ├── pedsim_sensors ├── CMakeLists.txt ├── include │ └── pedsim_sensors │ │ ├── obstacle_point_cloud.h │ │ ├── occlusion_point_cloud.h │ │ ├── pedsim_sensor.h │ │ └── people_point_cloud.h ├── launch │ ├── obstacle_pcd_sensor.launch │ ├── occlusion_pcd_sensor.launch │ └── people_pcd_sensor.launch ├── package.xml └── src │ └── pedsim_sensors │ ├── obstacle_point_cloud.cpp │ ├── occlusion_point_cloud.cpp │ └── people_point_cloud.cpp ├── pedsim_simulator ├── CMakeLists.txt ├── config │ └── PedsimSimulator.cfg ├── images │ ├── 1.simulation_demo.gif │ ├── 2.gazebo_macro.png │ ├── 3.gazebo_micro.png │ ├── animated_walking_man.mesh │ ├── animated_walking_man.skeleton │ ├── costmap.png │ ├── crowd1.png │ ├── darylbot.dae │ ├── darylbot_rotated_shifted.dae │ ├── kiosk.dae │ ├── man.3ds │ └── sim_shot.png ├── include │ └── pedsim_simulator │ │ ├── agentstatemachine.h │ │ ├── config.h │ │ ├── element │ │ ├── agent.h │ │ ├── agentcluster.h │ │ ├── agentgroup.h │ │ ├── areawaypoint.h │ │ ├── attractionarea.h │ │ ├── obstacle.h │ │ ├── queueingwaypoint.h │ │ ├── scenarioelement.h │ │ ├── waitingqueue.h │ │ └── waypoint.h │ │ ├── force │ │ ├── alongwallforce.h │ │ ├── force.h │ │ ├── groupcoherenceforce.h │ │ ├── groupgazeforce.h │ │ ├── grouprepulsionforce.h │ │ └── randomforce.h │ │ ├── orientationhandler.h │ │ ├── rng.h │ │ ├── scenarioreader.h │ │ ├── scene.h │ │ ├── simulator.h │ │ ├── utilities.h │ │ └── waypointplanner │ │ ├── groupwaypointplanner.h │ │ ├── individualwaypointplanner.h │ │ ├── queueingplanner.h │ │ ├── shoppingplanner.h │ │ └── waypointplanner.h ├── launch │ ├── airport_activities.launch │ ├── airport_demo.launch │ ├── altorfer.launch │ ├── robot.launch │ ├── robot_altorfer.launch │ ├── robot_controller.launch │ ├── robot_controller_v0.launch │ ├── robot_gmapping.launch │ ├── robot_jackal.launch │ ├── robot_v0.launch │ ├── simple_pedestrians.launch │ ├── simulator.launch │ ├── sources_and_sinks.launch │ └── test.launch ├── package.xml ├── rviz │ ├── airport.rviz │ ├── airport_activities.rviz │ ├── demo.rviz │ ├── social_contexts_activities.rviz │ └── sources_and_sinks.rviz ├── scenarios │ ├── airport.xml │ ├── airport2.xml │ ├── airport_activities.xml │ ├── airport_activities2.xml │ ├── altorfer.xml │ ├── autolab.xml │ ├── autolab │ │ ├── autolab_25.xml │ │ └── autolab_35_v1.xml │ ├── blank_world.xml │ ├── contexts │ │ ├── anti_flow.xml │ │ ├── flow.xml │ │ ├── queueing.xml │ │ ├── shopping.xml │ │ └── standing.xml │ ├── corridor.xml │ ├── cumberland.xml │ ├── cumberland │ │ ├── cumberland_25.xml │ │ └── cumberland_35.xml │ ├── eng_hall.xml │ ├── eng_hall_noPed.xml │ ├── eng_hall_test.xml │ ├── freiburg.xml │ ├── freiburg │ │ ├── freiburg_25.xml │ │ └── freiburg_35.xml │ ├── lobby │ │ ├── eng_hall_15.xml │ │ ├── eng_hall_25.xml │ │ ├── eng_hall_35_new.xml │ │ ├── eng_hall_45.xml │ │ ├── eng_hall_5.xml │ │ └── eng_hall_55_new.xml │ ├── nav_test.xml │ ├── scene1.xml │ ├── scene2.xml │ ├── scene3.xml │ ├── scene4.xml │ ├── shopping.xml │ ├── singleagent.xml │ ├── skirkanich.xml │ ├── small_airport.xml │ ├── social_contexts.xml │ ├── social_contexts_house.xml │ ├── square │ │ ├── new_25_v1.xml │ │ └── new_35_v1.xml │ └── srl_experiments │ │ └── nav_test1.xml ├── scripts │ ├── dummy_transforms.py │ ├── keyboard_teleop.py │ ├── mock_static_scene.py │ ├── scenario_to_png.py │ └── scene_editor.py ├── src │ ├── agentstatemachine.cpp │ ├── config.cpp │ ├── element │ │ ├── agent.cpp │ │ ├── agentcluster.cpp │ │ ├── agentgroup.cpp │ │ ├── areawaypoint.cpp │ │ ├── attractionarea.cpp │ │ ├── obstacle.cpp │ │ ├── queueingwaypoint.cpp │ │ ├── scenarioelement.cpp │ │ ├── waitingqueue.cpp │ │ └── waypoint.cpp │ ├── force │ │ ├── alongwallforce.cpp │ │ ├── force.cpp │ │ ├── groupcoherenceforce.cpp │ │ ├── groupgazeforce.cpp │ │ ├── grouprepulsionforce.cpp │ │ └── randomforce.cpp │ ├── orientationhandler.cpp │ ├── rng.cpp │ ├── scenarioreader.cpp │ ├── scene.cpp │ ├── simulate_diff_drive_robot.cpp │ ├── simulator.cpp │ ├── simulator_node.cpp │ └── waypointplanner │ │ ├── groupwaypointplanner.cpp │ │ ├── individualwaypointplanner.cpp │ │ ├── queueingplanner.cpp │ │ ├── shoppingplanner.cpp │ │ └── waypointplanner.cpp └── test │ └── .keepme ├── pedsim_srvs ├── CMakeLists.txt ├── package.xml └── srv │ ├── GetAgentState.srv │ ├── GetAllAgentsState.srv │ ├── SetAgentState.srv │ └── SetAllAgentsState.srv ├── pedsim_utils ├── CMakeLists.txt ├── include │ └── pedsim_utils │ │ └── geometry.h ├── package.xml └── src │ └── pedsim_utils │ ├── geometry.cpp │ └── pedsim_utils.cpp └── pedsim_visualizer ├── CMakeLists.txt ├── config └── PedsimVisualizer.cfg ├── include └── pedsim_visualizer │ └── sim_visualizer.h ├── launch └── visualizer.launch ├── package.xml └── src ├── sim_visualizer.cpp └── sim_visualizer_node.cpp /2ndparty/spencer_messages/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/.gitignore -------------------------------------------------------------------------------- /2ndparty/spencer_messages/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/LICENSE -------------------------------------------------------------------------------- /2ndparty/spencer_messages/README.md: -------------------------------------------------------------------------------- 1 | # spencer_messages -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_control_msgs/CATKIN_IGNORE: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_control_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_control_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_control_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_control_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_control_msgs/CMakeLists.txt~: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_control_msgs/CMakeLists.txt~ -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_control_msgs/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_control_msgs/LICENSE -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_control_msgs/msg/ComponentStatus.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_control_msgs/msg/ComponentStatus.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_control_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_control_msgs/package.xml -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_human_attribute_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_human_attribute_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_human_attribute_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_human_attribute_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_human_attribute_msgs/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_human_attribute_msgs/LICENSE -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_human_attribute_msgs/msg/CategoricalAttribute.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_human_attribute_msgs/msg/CategoricalAttribute.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_human_attribute_msgs/msg/HumanAttributes.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_human_attribute_msgs/msg/HumanAttributes.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_human_attribute_msgs/msg/ScalarAttribute.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_human_attribute_msgs/msg/ScalarAttribute.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_human_attribute_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_human_attribute_msgs/package.xml -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_social_relation_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_social_relation_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_social_relation_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_social_relation_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_social_relation_msgs/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_social_relation_msgs/LICENSE -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_social_relation_msgs/msg/SocialActivities.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_social_relation_msgs/msg/SocialActivities.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_social_relation_msgs/msg/SocialActivity.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_social_relation_msgs/msg/SocialActivity.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_social_relation_msgs/msg/SocialRelation.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_social_relation_msgs/msg/SocialRelation.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_social_relation_msgs/msg/SocialRelations.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_social_relation_msgs/msg/SocialRelations.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_social_relation_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_social_relation_msgs/package.xml -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/LICENSE -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/CompositeDetectedPerson.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/CompositeDetectedPerson.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/CompositeDetectedPersons.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/CompositeDetectedPersons.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/DetectedPerson.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/DetectedPerson.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/DetectedPersons.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/DetectedPersons.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/ImmDebugInfo.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/ImmDebugInfo.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/ImmDebugInfos.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/ImmDebugInfos.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/PersonTrajectory.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/PersonTrajectory.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/PersonTrajectoryEntry.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/PersonTrajectoryEntry.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedGroup.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedGroup.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedGroups.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedGroups.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedPerson.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedPerson.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedPerson2d.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedPerson2d.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedPersons.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedPersons.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedPersons2d.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackedPersons2d.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackingTimingMetrics.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/msg/TrackingTimingMetrics.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/package.xml -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_tracking_msgs/srv/GetPersonTrajectories.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_tracking_msgs/srv/GetPersonTrajectories.srv -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_vision_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_vision_msgs/CHANGELOG.rst -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_vision_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_vision_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_vision_msgs/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_vision_msgs/LICENSE -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_vision_msgs/msg/PersonImage.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_vision_msgs/msg/PersonImage.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_vision_msgs/msg/PersonImages.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_vision_msgs/msg/PersonImages.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_vision_msgs/msg/PersonROI.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_vision_msgs/msg/PersonROI.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_vision_msgs/msg/PersonROIs.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_vision_msgs/msg/PersonROIs.msg -------------------------------------------------------------------------------- /2ndparty/spencer_messages/spencer_vision_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_messages/spencer_vision_msgs/package.xml -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/.gitignore -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/CHANGELOG.rst: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/CHANGELOG.rst -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/CMakeLists.txt -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/LICENSE -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/README.md -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/icons/classes/DetectedPersons.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/icons/classes/DetectedPersons.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/icons/classes/HumanAttributes.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/icons/classes/HumanAttributes.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/icons/classes/SocialActivities.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/icons/classes/SocialActivities.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/icons/classes/SocialRelations.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/icons/classes/SocialRelations.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/icons/classes/TrackedGroups.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/icons/classes/TrackedGroups.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/icons/classes/TrackedPersons.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/icons/classes/TrackedPersons.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/media/animated_walking_man.mesh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/media/animated_walking_man.mesh -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/media/animated_walking_man.skeleton: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/media/animated_walking_man.skeleton -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/media/female_symbol.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/media/female_symbol.dae -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/media/male_symbol.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/media/male_symbol.dae -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/package.xml -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/plugin_description.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/plugin_description.xml -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/screenshots/detected_persons.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/screenshots/detected_persons.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/screenshots/human_attributes.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/screenshots/human_attributes.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/screenshots/social_activities.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/screenshots/social_activities.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/screenshots/social_relations.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/screenshots/social_relations.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/screenshots/tracked_groups.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/screenshots/tracked_groups.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/screenshots/tracked_persons_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/screenshots/tracked_persons_1.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/screenshots/tracked_persons_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/screenshots/tracked_persons_2.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/screenshots/tracked_persons_3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/screenshots/tracked_persons_3.png -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/scripts/send_test_msgs.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/scripts/send_test_msgs.py -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/additional_topic_subscriber.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/additional_topic_subscriber.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/detected_persons_display.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/detected_persons_display.cpp -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/detected_persons_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/detected_persons_display.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/human_attributes_display.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/human_attributes_display.cpp -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/human_attributes_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/human_attributes_display.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/person_display_common.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/person_display_common.cpp -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/person_display_common.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/person_display_common.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/social_activities_display.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/social_activities_display.cpp -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/social_activities_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/social_activities_display.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/social_relations_display.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/social_relations_display.cpp -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/social_relations_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/social_relations_display.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/tracked_groups_display.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/tracked_groups_display.cpp -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/tracked_groups_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/tracked_groups_display.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/tracked_persons_cache.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/tracked_persons_cache.cpp -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/tracked_persons_cache.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/tracked_persons_cache.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/tracked_persons_display.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/tracked_persons_display.cpp -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/tracked_persons_display.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/tracked_persons_display.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/visuals/covariance_visual.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/visuals/covariance_visual.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/visuals/mesh_node.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/visuals/mesh_node.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/visuals/person_visual.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/visuals/person_visual.cpp -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/visuals/person_visual.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/visuals/person_visual.h -------------------------------------------------------------------------------- /2ndparty/spencer_tracking_rviz_plugin/src/visuals/text_node.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/2ndparty/spencer_tracking_rviz_plugin/src/visuals/text_node.h -------------------------------------------------------------------------------- /3rdparty/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | add_subdirectory(libpedsim) 2 | -------------------------------------------------------------------------------- /3rdparty/libpedsim/.gitignore: -------------------------------------------------------------------------------- 1 | .svn 2 | -------------------------------------------------------------------------------- /3rdparty/libpedsim/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/CMakeLists.txt -------------------------------------------------------------------------------- /3rdparty/libpedsim/LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/LICENSE -------------------------------------------------------------------------------- /3rdparty/libpedsim/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/README.md -------------------------------------------------------------------------------- /3rdparty/libpedsim/include/pedsim/ped_agent.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/include/pedsim/ped_agent.h -------------------------------------------------------------------------------- /3rdparty/libpedsim/include/pedsim/ped_angle.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/include/pedsim/ped_angle.h -------------------------------------------------------------------------------- /3rdparty/libpedsim/include/pedsim/ped_includes.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/include/pedsim/ped_includes.h -------------------------------------------------------------------------------- /3rdparty/libpedsim/include/pedsim/ped_obstacle.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/include/pedsim/ped_obstacle.h -------------------------------------------------------------------------------- /3rdparty/libpedsim/include/pedsim/ped_scene.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/include/pedsim/ped_scene.h -------------------------------------------------------------------------------- /3rdparty/libpedsim/include/pedsim/ped_tree.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/include/pedsim/ped_tree.h -------------------------------------------------------------------------------- /3rdparty/libpedsim/include/pedsim/ped_vector.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/include/pedsim/ped_vector.h -------------------------------------------------------------------------------- /3rdparty/libpedsim/include/pedsim/ped_waypoint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/include/pedsim/ped_waypoint.h -------------------------------------------------------------------------------- /3rdparty/libpedsim/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/package.xml -------------------------------------------------------------------------------- /3rdparty/libpedsim/src/ped_agent.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/src/ped_agent.cpp -------------------------------------------------------------------------------- /3rdparty/libpedsim/src/ped_angle.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/src/ped_angle.cpp -------------------------------------------------------------------------------- /3rdparty/libpedsim/src/ped_obstacle.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/src/ped_obstacle.cpp -------------------------------------------------------------------------------- /3rdparty/libpedsim/src/ped_scene.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/src/ped_scene.cpp -------------------------------------------------------------------------------- /3rdparty/libpedsim/src/ped_tree.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/src/ped_tree.cpp -------------------------------------------------------------------------------- /3rdparty/libpedsim/src/ped_vector.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/src/ped_vector.cpp -------------------------------------------------------------------------------- /3rdparty/libpedsim/src/ped_waypoint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/3rdparty/libpedsim/src/ped_waypoint.cpp -------------------------------------------------------------------------------- /History.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/History.md -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/LICENSE -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/README.md -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/CMakeLists.txt -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/README.md -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/airport.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/airport.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/airport_activities2.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/airport_activities2.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/altorfer.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/altorfer.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/autolab.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/autolab.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/cumberland.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/cumberland.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/eng_hall.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/eng_hall.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/frieburg.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/frieburg.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/frieburg_origin.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/frieburg_origin.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/nav_test.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/nav_test.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/scene1.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/scene1.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/scene3.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/scene3.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/scene4.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/scene4.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/shopping.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/shopping.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/singleagent.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/singleagent.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/skirkanich.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/skirkanich.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/small_airport.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/small_airport.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/social_contexts.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/social_contexts.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/launch/social_contexts_house.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/launch/social_contexts_house.launch -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/actor_model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/actor_model.config -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/actor_model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/actor_model.sdf -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/actor_model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/actor_model.config -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/actor_model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/actor_model.sdf -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/eyebrow001-unmodified.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/eyebrow001-unmodified.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/eyebrow001.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/eyebrow001.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/green_eye.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/green_eye.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/jeans01_normals.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/jeans01_normals.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/jeans_basic_diffuse.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/jeans_basic_diffuse.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/male02_diffuse_black-unmodified.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/male02_diffuse_black-unmodified.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/male02_diffuse_black.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/male02_diffuse_black.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/teeth.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/teeth.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/tshirt02_normals.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/tshirt02_normals.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/tshirt02_texture.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/tshirt02_texture.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/materials/textures/young_lightskinned_male_diffuse.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/materials/textures/young_lightskinned_male_diffuse.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/eyebrow001-unmodified.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/eyebrow001-unmodified.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/eyebrow001.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/eyebrow001.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/green_eye.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/green_eye.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/jeans01_normals.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/jeans01_normals.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/jeans_basic_diffuse.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/jeans_basic_diffuse.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/male02_diffuse_black-unmodified.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/male02_diffuse_black-unmodified.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/male02_diffuse_black.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/male02_diffuse_black.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/standing.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/standing.dae -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/standing_color.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/standing_color.dae -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/standingv2.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/standingv2.dae -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/teeth.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/teeth.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/tshirt02_normals.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/tshirt02_normals.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/tshirt02_texture.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/tshirt02_texture.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/walk.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/walk.dae -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/meshes/young_lightskinned_male_diffuse.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/meshes/young_lightskinned_male_diffuse.png -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/model.config: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/model.config -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/models/person_standing/model.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/models/person_standing/model.sdf -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/package.xml -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/scripts/pedsim_to_gazbo_world.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/scripts/pedsim_to_gazbo_world.py -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/scripts/spawn_pedsim_agents.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/scripts/spawn_pedsim_agents.py -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/src/actor_poses_plugin.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/src/actor_poses_plugin.cpp -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/airport.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/airport.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/airport_activities2.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/airport_activities2.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/altorfer.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/altorfer.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/autolab.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/autolab.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/av_test.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/av_test.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/cumberland.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/cumberland.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/cumberland_orignal.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/cumberland_orignal.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/eng_hall.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/eng_hall.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/eng_hall_changed.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/eng_hall_changed.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/freiburg.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/freiburg.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/freiburg_origin.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/freiburg_origin.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/nav_test.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/nav_test.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/nav_test_xml.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/nav_test_xml.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/scene1.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/scene1.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/scene3.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/scene3.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/scene4.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/scene4.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/shopping.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/shopping.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/singleagent.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/singleagent.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/skirkanich.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/skirkanich.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/small_airport.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/small_airport.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/social_activities.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/social_activities.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/social_contexts.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/social_contexts.world -------------------------------------------------------------------------------- /pedsim_gazebo_plugin/worlds/social_contexts_house.world: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_gazebo_plugin/worlds/social_contexts_house.world -------------------------------------------------------------------------------- /pedsim_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/CMakeLists.txt -------------------------------------------------------------------------------- /pedsim_msgs/msg/AgentForce.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/AgentForce.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/AgentGroup.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/AgentGroup.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/AgentGroups.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/AgentGroups.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/AgentState.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/AgentState.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/AgentStates.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/AgentStates.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/AllAgentsState.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/AllAgentsState.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/LineObstacle.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/LineObstacle.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/LineObstacles.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/LineObstacles.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/SocialActivities.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/SocialActivities.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/SocialActivity.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/SocialActivity.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/SocialRelation.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/SocialRelation.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/SocialRelations.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/SocialRelations.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/TrackedGroup.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/TrackedGroup.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/TrackedGroups.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/TrackedGroups.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/TrackedPerson.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/TrackedPerson.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/TrackedPersons.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/TrackedPersons.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/Waypoint.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/Waypoint.msg -------------------------------------------------------------------------------- /pedsim_msgs/msg/Waypoints.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/msg/Waypoints.msg -------------------------------------------------------------------------------- /pedsim_msgs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_msgs/package.xml -------------------------------------------------------------------------------- /pedsim_ros/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_ros/CMakeLists.txt -------------------------------------------------------------------------------- /pedsim_ros/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_ros/package.xml -------------------------------------------------------------------------------- /pedsim_sensors/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/CMakeLists.txt -------------------------------------------------------------------------------- /pedsim_sensors/include/pedsim_sensors/obstacle_point_cloud.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/include/pedsim_sensors/obstacle_point_cloud.h -------------------------------------------------------------------------------- /pedsim_sensors/include/pedsim_sensors/occlusion_point_cloud.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/include/pedsim_sensors/occlusion_point_cloud.h -------------------------------------------------------------------------------- /pedsim_sensors/include/pedsim_sensors/pedsim_sensor.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/include/pedsim_sensors/pedsim_sensor.h -------------------------------------------------------------------------------- /pedsim_sensors/include/pedsim_sensors/people_point_cloud.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/include/pedsim_sensors/people_point_cloud.h -------------------------------------------------------------------------------- /pedsim_sensors/launch/obstacle_pcd_sensor.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/launch/obstacle_pcd_sensor.launch -------------------------------------------------------------------------------- /pedsim_sensors/launch/occlusion_pcd_sensor.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/launch/occlusion_pcd_sensor.launch -------------------------------------------------------------------------------- /pedsim_sensors/launch/people_pcd_sensor.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/launch/people_pcd_sensor.launch -------------------------------------------------------------------------------- /pedsim_sensors/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/package.xml -------------------------------------------------------------------------------- /pedsim_sensors/src/pedsim_sensors/obstacle_point_cloud.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/src/pedsim_sensors/obstacle_point_cloud.cpp -------------------------------------------------------------------------------- /pedsim_sensors/src/pedsim_sensors/occlusion_point_cloud.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/src/pedsim_sensors/occlusion_point_cloud.cpp -------------------------------------------------------------------------------- /pedsim_sensors/src/pedsim_sensors/people_point_cloud.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_sensors/src/pedsim_sensors/people_point_cloud.cpp -------------------------------------------------------------------------------- /pedsim_simulator/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/CMakeLists.txt -------------------------------------------------------------------------------- /pedsim_simulator/config/PedsimSimulator.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/config/PedsimSimulator.cfg -------------------------------------------------------------------------------- /pedsim_simulator/images/1.simulation_demo.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/1.simulation_demo.gif -------------------------------------------------------------------------------- /pedsim_simulator/images/2.gazebo_macro.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/2.gazebo_macro.png -------------------------------------------------------------------------------- /pedsim_simulator/images/3.gazebo_micro.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/3.gazebo_micro.png -------------------------------------------------------------------------------- /pedsim_simulator/images/animated_walking_man.mesh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/animated_walking_man.mesh -------------------------------------------------------------------------------- /pedsim_simulator/images/animated_walking_man.skeleton: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/animated_walking_man.skeleton -------------------------------------------------------------------------------- /pedsim_simulator/images/costmap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/costmap.png -------------------------------------------------------------------------------- /pedsim_simulator/images/crowd1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/crowd1.png -------------------------------------------------------------------------------- /pedsim_simulator/images/darylbot.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/darylbot.dae -------------------------------------------------------------------------------- /pedsim_simulator/images/darylbot_rotated_shifted.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/darylbot_rotated_shifted.dae -------------------------------------------------------------------------------- /pedsim_simulator/images/kiosk.dae: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/kiosk.dae -------------------------------------------------------------------------------- /pedsim_simulator/images/man.3ds: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/man.3ds -------------------------------------------------------------------------------- /pedsim_simulator/images/sim_shot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/images/sim_shot.png -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/agentstatemachine.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/agentstatemachine.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/config.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/config.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/element/agent.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/element/agent.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/element/agentcluster.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/element/agentcluster.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/element/agentgroup.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/element/agentgroup.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/element/areawaypoint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/element/areawaypoint.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/element/attractionarea.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/element/attractionarea.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/element/obstacle.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/element/obstacle.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/element/queueingwaypoint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/element/queueingwaypoint.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/element/scenarioelement.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/element/scenarioelement.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/element/waitingqueue.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/element/waitingqueue.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/element/waypoint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/element/waypoint.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/force/alongwallforce.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/force/alongwallforce.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/force/force.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/force/force.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/force/groupcoherenceforce.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/force/groupcoherenceforce.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/force/groupgazeforce.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/force/groupgazeforce.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/force/grouprepulsionforce.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/force/grouprepulsionforce.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/force/randomforce.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/force/randomforce.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/orientationhandler.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/orientationhandler.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/rng.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/rng.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/scenarioreader.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/scenarioreader.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/scene.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/scene.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/simulator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/simulator.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/utilities.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/utilities.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/waypointplanner/groupwaypointplanner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/waypointplanner/groupwaypointplanner.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/waypointplanner/individualwaypointplanner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/waypointplanner/individualwaypointplanner.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/waypointplanner/queueingplanner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/waypointplanner/queueingplanner.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/waypointplanner/shoppingplanner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/waypointplanner/shoppingplanner.h -------------------------------------------------------------------------------- /pedsim_simulator/include/pedsim_simulator/waypointplanner/waypointplanner.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/include/pedsim_simulator/waypointplanner/waypointplanner.h -------------------------------------------------------------------------------- /pedsim_simulator/launch/airport_activities.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/airport_activities.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/airport_demo.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/airport_demo.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/altorfer.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/altorfer.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/robot.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/robot.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/robot_altorfer.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/robot_altorfer.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/robot_controller.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/robot_controller.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/robot_controller_v0.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/robot_controller_v0.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/robot_gmapping.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/robot_gmapping.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/robot_jackal.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/robot_jackal.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/robot_v0.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/robot_v0.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/simple_pedestrians.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/simple_pedestrians.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/simulator.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/simulator.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/sources_and_sinks.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/sources_and_sinks.launch -------------------------------------------------------------------------------- /pedsim_simulator/launch/test.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/launch/test.launch -------------------------------------------------------------------------------- /pedsim_simulator/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/package.xml -------------------------------------------------------------------------------- /pedsim_simulator/rviz/airport.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/rviz/airport.rviz -------------------------------------------------------------------------------- /pedsim_simulator/rviz/airport_activities.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/rviz/airport_activities.rviz -------------------------------------------------------------------------------- /pedsim_simulator/rviz/demo.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/rviz/demo.rviz -------------------------------------------------------------------------------- /pedsim_simulator/rviz/social_contexts_activities.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/rviz/social_contexts_activities.rviz -------------------------------------------------------------------------------- /pedsim_simulator/rviz/sources_and_sinks.rviz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/rviz/sources_and_sinks.rviz -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/airport.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/airport.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/airport2.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/airport2.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/airport_activities.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/airport_activities.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/airport_activities2.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/airport_activities2.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/altorfer.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/altorfer.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/autolab.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/autolab.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/autolab/autolab_25.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/autolab/autolab_25.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/autolab/autolab_35_v1.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/autolab/autolab_35_v1.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/blank_world.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/blank_world.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/contexts/anti_flow.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/contexts/anti_flow.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/contexts/flow.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/contexts/flow.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/contexts/queueing.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/contexts/queueing.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/contexts/shopping.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/contexts/shopping.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/contexts/standing.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/contexts/standing.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/corridor.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/corridor.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/cumberland.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/cumberland.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/cumberland/cumberland_25.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/cumberland/cumberland_25.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/cumberland/cumberland_35.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/cumberland/cumberland_35.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/eng_hall.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/eng_hall.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/eng_hall_noPed.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/eng_hall_noPed.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/eng_hall_test.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/eng_hall_test.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/freiburg.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/freiburg.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/freiburg/freiburg_25.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/freiburg/freiburg_25.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/freiburg/freiburg_35.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/freiburg/freiburg_35.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/lobby/eng_hall_15.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/lobby/eng_hall_15.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/lobby/eng_hall_25.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/lobby/eng_hall_25.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/lobby/eng_hall_35_new.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/lobby/eng_hall_35_new.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/lobby/eng_hall_45.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/lobby/eng_hall_45.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/lobby/eng_hall_5.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/lobby/eng_hall_5.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/lobby/eng_hall_55_new.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/lobby/eng_hall_55_new.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/nav_test.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/nav_test.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/scene1.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/scene1.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/scene2.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/scene2.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/scene3.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/scene3.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/scene4.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/scene4.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/shopping.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/shopping.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/singleagent.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/singleagent.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/skirkanich.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/skirkanich.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/small_airport.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/small_airport.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/social_contexts.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/social_contexts.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/social_contexts_house.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/social_contexts_house.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/square/new_25_v1.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/square/new_25_v1.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/square/new_35_v1.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/square/new_35_v1.xml -------------------------------------------------------------------------------- /pedsim_simulator/scenarios/srl_experiments/nav_test1.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scenarios/srl_experiments/nav_test1.xml -------------------------------------------------------------------------------- /pedsim_simulator/scripts/dummy_transforms.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scripts/dummy_transforms.py -------------------------------------------------------------------------------- /pedsim_simulator/scripts/keyboard_teleop.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scripts/keyboard_teleop.py -------------------------------------------------------------------------------- /pedsim_simulator/scripts/mock_static_scene.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scripts/mock_static_scene.py -------------------------------------------------------------------------------- /pedsim_simulator/scripts/scenario_to_png.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/scripts/scenario_to_png.py -------------------------------------------------------------------------------- /pedsim_simulator/scripts/scene_editor.py: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /pedsim_simulator/src/agentstatemachine.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/agentstatemachine.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/config.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/config.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/element/agent.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/element/agent.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/element/agentcluster.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/element/agentcluster.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/element/agentgroup.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/element/agentgroup.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/element/areawaypoint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/element/areawaypoint.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/element/attractionarea.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/element/attractionarea.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/element/obstacle.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/element/obstacle.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/element/queueingwaypoint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/element/queueingwaypoint.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/element/scenarioelement.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/element/scenarioelement.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/element/waitingqueue.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/element/waitingqueue.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/element/waypoint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/element/waypoint.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/force/alongwallforce.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/force/alongwallforce.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/force/force.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/force/force.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/force/groupcoherenceforce.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/force/groupcoherenceforce.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/force/groupgazeforce.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/force/groupgazeforce.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/force/grouprepulsionforce.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/force/grouprepulsionforce.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/force/randomforce.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/force/randomforce.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/orientationhandler.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/orientationhandler.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/rng.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/rng.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/scenarioreader.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/scenarioreader.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/scene.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/scene.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/simulate_diff_drive_robot.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/simulate_diff_drive_robot.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/simulator.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/simulator.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/simulator_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/simulator_node.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/waypointplanner/groupwaypointplanner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/waypointplanner/groupwaypointplanner.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/waypointplanner/individualwaypointplanner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/waypointplanner/individualwaypointplanner.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/waypointplanner/queueingplanner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/waypointplanner/queueingplanner.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/waypointplanner/shoppingplanner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/waypointplanner/shoppingplanner.cpp -------------------------------------------------------------------------------- /pedsim_simulator/src/waypointplanner/waypointplanner.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_simulator/src/waypointplanner/waypointplanner.cpp -------------------------------------------------------------------------------- /pedsim_simulator/test/.keepme: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /pedsim_srvs/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_srvs/CMakeLists.txt -------------------------------------------------------------------------------- /pedsim_srvs/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_srvs/package.xml -------------------------------------------------------------------------------- /pedsim_srvs/srv/GetAgentState.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_srvs/srv/GetAgentState.srv -------------------------------------------------------------------------------- /pedsim_srvs/srv/GetAllAgentsState.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_srvs/srv/GetAllAgentsState.srv -------------------------------------------------------------------------------- /pedsim_srvs/srv/SetAgentState.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_srvs/srv/SetAgentState.srv -------------------------------------------------------------------------------- /pedsim_srvs/srv/SetAllAgentsState.srv: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_srvs/srv/SetAllAgentsState.srv -------------------------------------------------------------------------------- /pedsim_utils/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_utils/CMakeLists.txt -------------------------------------------------------------------------------- /pedsim_utils/include/pedsim_utils/geometry.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_utils/include/pedsim_utils/geometry.h -------------------------------------------------------------------------------- /pedsim_utils/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_utils/package.xml -------------------------------------------------------------------------------- /pedsim_utils/src/pedsim_utils/geometry.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_utils/src/pedsim_utils/geometry.cpp -------------------------------------------------------------------------------- /pedsim_utils/src/pedsim_utils/pedsim_utils.cpp: -------------------------------------------------------------------------------- 1 | 2 | 3 | #include 4 | -------------------------------------------------------------------------------- /pedsim_visualizer/CMakeLists.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_visualizer/CMakeLists.txt -------------------------------------------------------------------------------- /pedsim_visualizer/config/PedsimVisualizer.cfg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_visualizer/config/PedsimVisualizer.cfg -------------------------------------------------------------------------------- /pedsim_visualizer/include/pedsim_visualizer/sim_visualizer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_visualizer/include/pedsim_visualizer/sim_visualizer.h -------------------------------------------------------------------------------- /pedsim_visualizer/launch/visualizer.launch: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_visualizer/launch/visualizer.launch -------------------------------------------------------------------------------- /pedsim_visualizer/package.xml: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_visualizer/package.xml -------------------------------------------------------------------------------- /pedsim_visualizer/src/sim_visualizer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_visualizer/src/sim_visualizer.cpp -------------------------------------------------------------------------------- /pedsim_visualizer/src/sim_visualizer_node.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/TempleRAIL/pedsim_ros_with_gazebo/HEAD/pedsim_visualizer/src/sim_visualizer_node.cpp --------------------------------------------------------------------------------