From 8d4ca315d073ddd3a3d7869dca3f87fc4dcba0b9 Mon Sep 17 00:00:00 2001 From: Ernesto Corbellini Date: Thu, 17 May 2018 17:13:26 -0300 Subject: [PATCH 1/3] Converted gazebo_msgs to ros2. --- gazebo_msgs/CMakeLists.txt | 125 +++++++++++++------------ gazebo_msgs/msg/ContactsState.msg | 2 +- gazebo_msgs/msg/ODEJointProperties.msg | 4 +- gazebo_msgs/msg/WorldState.msg | 2 +- gazebo_msgs/package.xml | 33 ++++--- gazebo_msgs/srv/ApplyBodyWrench.srv | 4 +- gazebo_msgs/srv/ApplyJointEffort.srv | 22 ++--- gazebo_msgs/srv/GetModelState.srv | 2 +- 8 files changed, 100 insertions(+), 94 deletions(-) diff --git a/gazebo_msgs/CMakeLists.txt b/gazebo_msgs/CMakeLists.txt index e15014c3f..2b0d7aaac 100644 --- a/gazebo_msgs/CMakeLists.txt +++ b/gazebo_msgs/CMakeLists.txt @@ -1,68 +1,75 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.5) + project(gazebo_msgs) -find_package(catkin REQUIRED COMPONENTS - std_msgs - trajectory_msgs - geometry_msgs - sensor_msgs - std_srvs - message_generation - ) +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + # we dont use add_compile_options with pedantic in message packages + # because the Python C extensions dont comply with it + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(builtin_interfaces REQUIRED) +find_package(std_msgs REQUIRED) +find_package(trajectory_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +set(msg_files + "msg/ContactState.msg" + "msg/ContactsState.msg" + "msg/LinkState.msg" + "msg/LinkStates.msg" + "msg/ModelState.msg" + "msg/ModelStates.msg" + "msg/ODEJointProperties.msg" + "msg/ODEPhysics.msg" + "msg/WorldState.msg" +) -add_message_files( - DIRECTORY msg - FILES - ContactsState.msg - ContactState.msg - LinkState.msg - LinkStates.msg - ModelState.msg - ModelStates.msg - ODEJointProperties.msg - ODEPhysics.msg - WorldState.msg - ) +set(srv_files + "srv/ApplyBodyWrench.srv" + "srv/ApplyJointEffort.srv" + "srv/BodyRequest.srv" + "srv/DeleteLight.srv" + "srv/DeleteModel.srv" + "srv/GetJointProperties.srv" + "srv/GetLightProperties.srv" + "srv/GetLinkProperties.srv" + "srv/GetLinkState.srv" + "srv/GetModelProperties.srv" + "srv/GetModelState.srv" + "srv/GetPhysicsProperties.srv" + "srv/GetWorldProperties.srv" + "srv/JointRequest.srv" + "srv/SetJointProperties.srv" + "srv/SetJointTrajectory.srv" + "srv/SetLightProperties.srv" + "srv/SetLinkProperties.srv" + "srv/SetLinkState.srv" + "srv/SetModelConfiguration.srv" + "srv/SetModelState.srv" + "srv/SetPhysicsProperties.srv" + "srv/SpawnModel.srv" +) -add_service_files(DIRECTORY srv FILES - ApplyBodyWrench.srv - DeleteModel.srv - DeleteLight.srv - GetLinkState.srv - GetPhysicsProperties.srv - SetJointProperties.srv - SetModelConfiguration.srv - SpawnModel.srv - ApplyJointEffort.srv - GetJointProperties.srv - GetModelProperties.srv - GetWorldProperties.srv - SetLinkProperties.srv - SetModelState.srv - BodyRequest.srv - GetLinkProperties.srv - GetModelState.srv - JointRequest.srv - SetLinkState.srv - SetPhysicsProperties.srv - SetJointTrajectory.srv - GetLightProperties.srv - SetLightProperties.srv - ) +rosidl_generate_interfaces(${PROJECT_NAME} + ${msg_files} + ${srv_files} -generate_messages(DEPENDENCIES + DEPENDENCIES + builtin_interfaces std_msgs geometry_msgs - sensor_msgs trajectory_msgs - ) -catkin_package( - CATKIN_DEPENDS - message_runtime - std_msgs - trajectory_msgs - geometry_msgs - sensor_msgs - std_srvs - ) + ADD_LINTER_TESTS +) + +ament_export_dependencies(rosidl_default_runtime) + +ament_package() diff --git a/gazebo_msgs/msg/ContactsState.msg b/gazebo_msgs/msg/ContactsState.msg index 668235049..fe9ab8521 100644 --- a/gazebo_msgs/msg/ContactsState.msg +++ b/gazebo_msgs/msg/ContactsState.msg @@ -1,2 +1,2 @@ -Header header # stamp +std_msgs/Header header # stamp gazebo_msgs/ContactState[] states # array of geom pairs in contact diff --git a/gazebo_msgs/msg/ODEJointProperties.msg b/gazebo_msgs/msg/ODEJointProperties.msg index 40ea60540..10f775fe7 100644 --- a/gazebo_msgs/msg/ODEJointProperties.msg +++ b/gazebo_msgs/msg/ODEJointProperties.msg @@ -1,7 +1,7 @@ # access to low level joint properties, change these at your own risk float64[] damping # joint damping -float64[] hiStop # joint limit -float64[] loStop # joint limit +float64[] hi_stop # joint limit +float64[] lo_stop # joint limit float64[] erp # set joint erp float64[] cfm # set joint cfm float64[] stop_erp # set joint erp for joint limit "contact" joint diff --git a/gazebo_msgs/msg/WorldState.msg b/gazebo_msgs/msg/WorldState.msg index e523e7790..f14c4dddd 100644 --- a/gazebo_msgs/msg/WorldState.msg +++ b/gazebo_msgs/msg/WorldState.msg @@ -34,7 +34,7 @@ # * visual information - does not vary in time # -Header header +std_msgs/Header header string[] name geometry_msgs/Pose[] pose diff --git a/gazebo_msgs/package.xml b/gazebo_msgs/package.xml index 85c834a8d..95c59d78e 100644 --- a/gazebo_msgs/package.xml +++ b/gazebo_msgs/package.xml @@ -1,36 +1,35 @@ - + + gazebo_msgs 2.8.4 - Message and service data structures for interacting with Gazebo from ROS. + Message and service data structures for interacting with Gazebo from ROS2. Jose Luis Rivero BSD - http://gazebosim.org/tutorials?cat=connect_ros - https://github.com/ros-simulation/gazebo_ros_pkgs/issues - https://github.com/ros-simulation/gazebo_ros_pkgs - - John Hsu - - catkin + ament_cmake + rosidl_default_generators + builtin_interfaces geometry_msgs - sensor_msgs trajectory_msgs std_msgs - std_srvs - message_generation - + + rosidl_default_runtime + builtin_interfaces geometry_msgs - sensor_msgs trajectory_msgs std_msgs - message_runtime - std_srvs - + ament_lint_common + + rosidl_interface_packages + + ament_cmake + + diff --git a/gazebo_msgs/srv/ApplyBodyWrench.srv b/gazebo_msgs/srv/ApplyBodyWrench.srv index ca27ab5db..1e4e7982b 100644 --- a/gazebo_msgs/srv/ApplyBodyWrench.srv +++ b/gazebo_msgs/srv/ApplyBodyWrench.srv @@ -9,10 +9,10 @@ string reference_frame # wrench is defined in the reference f # frame names are bodies prefixed by model name, e.g. pr2::base_link geometry_msgs/Point reference_point # wrench is defined at this location in the reference frame geometry_msgs/Wrench wrench # wrench applied to the origin of the body -time start_time # (optional) wrench application start time (seconds) +builtin_interfaces/Time start_time # (optional) wrench application start time (seconds) # if start_time is not specified, or # start_time < current time, start as soon as possible -duration duration # optional duration of wrench application time (seconds) +builtin_interfaces/Duration duratio # optional duration of wrench application time (seconds) # if duration < 0, apply wrench continuously without end # if duration = 0, do nothing # if duration < step size, apply wrench diff --git a/gazebo_msgs/srv/ApplyJointEffort.srv b/gazebo_msgs/srv/ApplyJointEffort.srv index 5ba952396..2614cb4ea 100644 --- a/gazebo_msgs/srv/ApplyJointEffort.srv +++ b/gazebo_msgs/srv/ApplyJointEffort.srv @@ -1,13 +1,13 @@ # set urdf joint effort -string joint_name # joint to apply wrench (linear force and torque) -float64 effort # effort to apply -time start_time # optional wrench application start time (seconds) - # if start_time < current time, start as soon as possible -duration duration # optional duration of wrench application time (seconds) - # if duration < 0, apply wrench continuously without end - # if duration = 0, do nothing - # if duration < step size, assume step size and - # display warning in status_message +string joint_name # joint to apply wrench (linear force and torque) +float64 effort # effort to apply +builtin_interfaces/Time start_time # optional wrench application start time (seconds) + # if start_time < current time, start as soon as possible +builtin_interfaces/Duration duration # optional duration of wrench application time (seconds) + # if duration < 0, apply wrench continuously without end + # if duration = 0, do nothing + # if duration < step size, assume step size and + # display warning in status_message --- -bool success # return true if effort application is successful -string status_message # comments if available +bool success # return true if effort application is successful +string status_message # comments if available diff --git a/gazebo_msgs/srv/GetModelState.srv b/gazebo_msgs/srv/GetModelState.srv index 9c6b6eee2..16461ceaf 100644 --- a/gazebo_msgs/srv/GetModelState.srv +++ b/gazebo_msgs/srv/GetModelState.srv @@ -4,7 +4,7 @@ string relative_entity_name # return pose and twist relative to this en # be sure to use gazebo scoped naming notation (e.g. [model_name::body_name]) # leave empty or "world" will use inertial world frame --- -Header header # Standard metadata for higher-level stamped data types. +std_msgs/Header header # Standard metadata for higher-level stamped data types. # * header.seq holds the number of requests since the plugin started # * header.stamp timestamp related to the pose # * header.frame_id not used but currently filled with the relative_entity_name From 37726f6b3c51f6c20dad9834d7741c64811b7b10 Mon Sep 17 00:00:00 2001 From: Kevin Allen Date: Tue, 17 Jul 2018 13:47:38 -0700 Subject: [PATCH 2/3] Move all unported files to .ros1_unported --- .../__init__.py => .ros1_unported/AMENT_IGNORE | 0 .../__init__.py => .ros1_unported/COLCON_IGNORE | 0 .../gazebo_dev}/CHANGELOG.rst | 0 .../gazebo_dev}/CMakeLists.txt | 0 .../gazebo_dev}/cmake/gazebo_dev-extras.cmake | 0 .../gazebo_dev}/package.xml | 0 .../gazebo_plugins}/CHANGELOG.rst | 0 .../gazebo_plugins}/CMakeLists.txt | 0 .../gazebo_plugins}/Media/models/chair/doc.kml | 0 .../Media/models/chair/images/texture0.jpg | Bin .../Media/models/chair/images/texture1.jpg | Bin .../Media/models/chair/models/Chair.dae | 0 .../Media/models/chair/models/Chair.stl | Bin .../gazebo_plugins}/Media/models/chair/textures.txt | 0 .../gazebo_plugins}/cfg/CameraSynchronizer.cfg | 0 .../gazebo_plugins}/cfg/GazeboRosCamera.cfg | 0 .../gazebo_plugins}/cfg/GazeboRosOpenniKinect.cfg | 0 .../gazebo_plugins}/cfg/Hokuyo.cfg | 0 .../include/gazebo_plugins/MultiCameraPlugin.h | 0 .../include/gazebo_plugins/PubQueue.h | 0 .../include/gazebo_plugins/gazebo_ros_block_laser.h | 0 .../include/gazebo_plugins/gazebo_ros_bumper.h | 0 .../include/gazebo_plugins/gazebo_ros_camera.h | 0 .../gazebo_plugins/gazebo_ros_camera_utils.h | 0 .../gazebo_plugins/gazebo_ros_depth_camera.h | 0 .../include/gazebo_plugins/gazebo_ros_diff_drive.h | 0 .../include/gazebo_plugins/gazebo_ros_elevator.h | 0 .../include/gazebo_plugins/gazebo_ros_f3d.h | 0 .../include/gazebo_plugins/gazebo_ros_force.h | 0 .../include/gazebo_plugins/gazebo_ros_ft_sensor.h | 0 .../include/gazebo_plugins/gazebo_ros_gpu_laser.h | 0 .../include/gazebo_plugins/gazebo_ros_hand_of_god.h | 0 .../include/gazebo_plugins/gazebo_ros_harness.h | 0 .../include/gazebo_plugins/gazebo_ros_imu.h | 0 .../include/gazebo_plugins/gazebo_ros_imu_sensor.h | 0 .../gazebo_ros_joint_pose_trajectory.h | 0 .../gazebo_ros_joint_state_publisher.h | 0 .../include/gazebo_plugins/gazebo_ros_laser.h | 0 .../include/gazebo_plugins/gazebo_ros_multicamera.h | 0 .../gazebo_plugins/gazebo_ros_openni_kinect.h | 0 .../include/gazebo_plugins/gazebo_ros_p3d.h | 0 .../include/gazebo_plugins/gazebo_ros_planar_move.h | 0 .../include/gazebo_plugins/gazebo_ros_projector.h | 0 .../include/gazebo_plugins/gazebo_ros_prosilica.h | 0 .../include/gazebo_plugins/gazebo_ros_range.h | 0 .../gazebo_plugins/gazebo_ros_skid_steer_drive.h | 0 .../include/gazebo_plugins/gazebo_ros_template.h | 0 .../gazebo_plugins/gazebo_ros_tricycle_drive.h | 0 .../gazebo_plugins/gazebo_ros_triggered_camera.h | 0 .../gazebo_ros_triggered_multicamera.h | 0 .../include/gazebo_plugins/gazebo_ros_utils.h | 0 .../gazebo_plugins/gazebo_ros_vacuum_gripper.h | 0 .../include/gazebo_plugins/gazebo_ros_video.h | 0 .../include/gazebo_plugins/vision_reconfigure.h | 0 .../gazebo_plugins}/package.xml | 0 .../gazebo_plugins}/scripts/gazebo_model | 0 .../gazebo_plugins}/scripts/set_pose.py | 0 .../gazebo_plugins}/scripts/set_wrench.py | 0 .../gazebo_plugins}/scripts/test_range.py | 0 .../gazebo_plugins}/setup.py | 0 .../gazebo_plugins}/src/MultiCameraPlugin.cpp | 0 .../gazebo_plugins}/src/camera_synchronizer.cpp | 0 .../gazebo_plugins/src/gazebo_plugins/__init__.py | 0 .../src/gazebo_plugins/gazebo_plugins_interface.py | 0 .../gazebo_plugins}/src/gazebo_ros_block_laser.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_bumper.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_camera.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_camera_utils.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_depth_camera.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_diff_drive.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_elevator.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_f3d.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_force.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_ft_sensor.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_gpu_laser.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_hand_of_god.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_harness.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_imu.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_imu_sensor.cpp | 0 .../src/gazebo_ros_joint_pose_trajectory.cpp | 0 .../src/gazebo_ros_joint_state_publisher.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_laser.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_multicamera.cpp | 0 .../src/gazebo_ros_openni_kinect.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_p3d.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_planar_move.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_projector.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_prosilica.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_range.cpp | 0 .../src/gazebo_ros_skid_steer_drive.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_template.cpp | 0 .../src/gazebo_ros_tricycle_drive.cpp | 0 .../src/gazebo_ros_triggered_camera.cpp | 0 .../src/gazebo_ros_triggered_multicamera.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_utils.cpp | 0 .../src/gazebo_ros_vacuum_gripper.cpp | 0 .../gazebo_plugins}/src/gazebo_ros_video.cpp | 0 .../gazebo_plugins}/src/hokuyo_node.cpp | 0 .../gazebo_plugins}/src/vision_reconfigure.cpp | 0 .../test/bumper_test/gazebo_ros_bumper.world | 0 .../test/bumper_test/test_bumper.launch | 0 .../gazebo_plugins}/test/bumper_test/test_bumper.py | 0 .../gazebo_plugins}/test/camera/camera.cpp | 0 .../gazebo_plugins}/test/camera/camera.h | 0 .../gazebo_plugins}/test/camera/camera.test | 0 .../gazebo_plugins}/test/camera/camera.world | 0 .../gazebo_plugins}/test/camera/camera16bit.cpp | 0 .../gazebo_plugins}/test/camera/camera16bit.test | 0 .../gazebo_plugins}/test/camera/camera16bit.world | 0 .../gazebo_plugins}/test/camera/depth_camera.cpp | 0 .../gazebo_plugins}/test/camera/depth_camera.test | 0 .../gazebo_plugins}/test/camera/depth_camera.world | 0 .../gazebo_plugins}/test/camera/distortion.h | 0 .../test/camera/distortion_barrel.cpp | 0 .../test/camera/distortion_barrel.test | 0 .../test/camera/distortion_barrel.world | 0 .../test/camera/distortion_pincushion.cpp | 0 .../test/camera/distortion_pincushion.test | 0 .../test/camera/distortion_pincushion.world | 0 .../gazebo_plugins}/test/camera/multicamera.cpp | 0 .../gazebo_plugins}/test/camera/multicamera.test | 0 .../gazebo_plugins}/test/camera/multicamera.world | 0 .../test/camera/triggered_camera.cpp | 0 .../test/camera/triggered_camera.test | 0 .../test/camera/triggered_camera.world | 0 .../gazebo_plugins}/test/config/example_models.yaml | 0 .../launch/multi_robot_scenario.launch | 0 .../launch/pioneer3dx.gazebo.launch | 0 .../multi_robot_scenario/launch/pioneer3dx.rviz | 0 .../launch/pioneer3dx.urdf.launch | 0 .../multi_robot_scenario/meshes/laser/hokuyo.dae | 0 .../multi_robot_scenario/meshes/p3dx/Coordinates | 0 .../multi_robot_scenario/meshes/p3dx/back_rim.stl | Bin .../multi_robot_scenario/meshes/p3dx/back_sonar.stl | Bin .../meshes/p3dx/center_hubcap.stl | Bin .../meshes/p3dx/center_wheel.stl | Bin .../multi_robot_scenario/meshes/p3dx/chassis.stl | Bin .../multi_robot_scenario/meshes/p3dx/front_rim.stl | Bin .../meshes/p3dx/front_sonar.stl | Bin .../meshes/p3dx/left_hubcap.stl | Bin .../multi_robot_scenario/meshes/p3dx/left_wheel.stl | Bin .../meshes/p3dx/right_hubcap.stl | Bin .../meshes/p3dx/right_wheel.stl | Bin .../multi_robot_scenario/meshes/p3dx/swivel.stl | Bin .../test/multi_robot_scenario/meshes/p3dx/top.stl | Bin .../multi_robot_scenario/xacro/camera/camera.xacro | 0 .../multi_robot_scenario/xacro/laser/hokuyo.xacro | 0 .../xacro/laser/hokuyo_gpu.xacro | 0 .../test/multi_robot_scenario/xacro/materials.xacro | 0 .../xacro/p3dx/battery_block.xacro | 0 .../xacro/p3dx/inertia_tensors.xacro | 0 .../xacro/p3dx/pioneer3dx.xacro | 0 .../xacro/p3dx/pioneer3dx_body.xacro | 0 .../xacro/p3dx/pioneer3dx_chassis.xacro | 0 .../xacro/p3dx/pioneer3dx_plugins.xacro | 0 .../xacro/p3dx/pioneer3dx_sonar.xacro | 0 .../xacro/p3dx/pioneer3dx_swivel.xacro | 0 .../xacro/p3dx/pioneer3dx_wheel.xacro | 0 .../test/p3d_test/test_3_double_pendulums.launch | 0 .../test/p3d_test/test_3_single_pendulums.launch | 0 .../test/p3d_test/test_double_pendulum.launch | 0 .../gazebo_plugins}/test/p3d_test/test_link_pose.py | 0 .../test/p3d_test/test_single_pendulum.launch | 0 .../test/p3d_test/worlds/3_double_pendulums.world | 0 .../test/p3d_test/worlds/3_single_pendulums.world | 0 .../test/p3d_test/worlds/double_pendulum.world | 0 .../test/p3d_test/worlds/single_pendulum.world | 0 .../test/pub_joint_trajectory_test.cpp | 0 .../gazebo_plugins}/test/range/range_plugin.test | 0 .../set_model_state_test/set_model_state_test.cpp | 0 .../set_model_state_test/set_model_state_test.test | 0 .../set_model_state_test_p2dx.world | 0 .../test/spawn_test/parameter_server_test.launch | 0 .../gazebo_plugins}/test/spawn_test/spawn_robots.sh | 0 .../test/test_worlds/bumper_test.world | 0 .../gazebo_plugins}/test/test_worlds/elevator.world | 0 .../test/test_worlds/gazebo_ros_block_laser.world | 0 .../test/test_worlds/gazebo_ros_camera.world | 0 .../test/test_worlds/gazebo_ros_depth_camera.world | 0 .../test/test_worlds/gazebo_ros_gpu_laser.world | 0 .../test/test_worlds/gazebo_ros_laser.world | 0 .../test/test_worlds/gazebo_ros_range.world | 0 .../test_worlds/gazebo_ros_trimesh_collision.world | 0 .../test/test_worlds/test_lasers.world | 0 .../test/tricycle_drive/launch/.directory | 0 .../tricycle_drive/launch/tricycle.gazebo.launch | 0 .../test/tricycle_drive/launch/tricycle.rviz | 0 .../test/tricycle_drive/launch/tricycle.urdf.launch | 0 .../launch/tricycle_drive_scenario.launch | 0 .../test/tricycle_drive/launch/tricycle_rviz.launch | 0 .../test/tricycle_drive/xacro/.directory | 0 .../test/tricycle_drive/xacro/materials.xacro | 0 .../xacro/tricycle/inertia_tensors.xacro | 0 .../tricycle_drive/xacro/tricycle/tricycle.xacro | 0 .../xacro/tricycle/tricycle_body.xacro | 0 .../xacro/tricycle/tricycle_chassis.xacro | 0 .../xacro/tricycle/tricycle_plugins.xacro | 0 .../test/tricycle_drive/xacro/tricycle/wheel.xacro | 0 .../xacro/tricycle/wheel_actuated.xacro | 0 .../gazebo_plugins}/test2/CMakeLists_tests_pkg.txt | 0 .../test2/contact_tolerance/contact_tolerance.cpp | 0 .../contact_tolerance/contact_tolerance.launch | 0 .../test2/large_models/large_model.launch | 0 .../test2/large_models/large_model.urdf.xacro | 0 .../test2/large_models/large_models.world | 0 .../test2/large_models/smaller_large_model.launch | 0 .../large_models/smaller_large_model.urdf.xacro | 0 .../gazebo_plugins}/test2/lcp_tests/balance.launch | 0 .../gazebo_plugins}/test2/lcp_tests/balance.world | 0 .../gazebo_plugins}/test2/lcp_tests/stack.launch | 0 .../gazebo_plugins}/test2/lcp_tests/stack.world | 0 .../gazebo_plugins}/test2/lcp_tests/stacks.launch | 0 .../gazebo_plugins}/test2/lcp_tests/stacks.world | 0 .../gazebo_plugins}/test2/meshes/cube.wings | Bin .../gazebo_plugins}/test2/meshes/cube_20k.stl | Bin .../gazebo_plugins}/test2/meshes/cube_30k.stl | Bin .../test2/spawn_model/check_model.cpp | 0 .../gazebo_plugins}/test2/spawn_model/spawn_box.cpp | 0 .../test2/spawn_model/spawn_box.launch | 0 .../test2/spawn_model/spawn_box_file.launch | 0 .../test2/spawn_model/spawn_box_param.launch | 0 .../test2/trimesh_tests/test_trimesh.launch | 0 .../gazebo_plugins}/test2/urdf/box.urdf | 0 .../gazebo_plugins}/test2/urdf/cube.urdf | 0 .../gazebo_plugins}/test2/worlds/empty.world | 0 .../gazebo_ros}/.idea/gazebo_ros.iml | 0 .../gazebo_ros}/CHANGELOG.rst | 0 .../gazebo_ros}/CMakeLists.txt | 0 .../gazebo_ros}/cfg/Physics.cfg | 0 .../include/gazebo_ros/gazebo_ros_api_plugin.h | 0 .../gazebo_ros}/launch/elevator_world.launch | 0 .../gazebo_ros}/launch/empty_world.launch | 0 .../gazebo_ros}/launch/mud_world.launch | 0 .../gazebo_ros}/launch/range_world.launch | 0 .../gazebo_ros}/launch/rubble_world.launch | 0 .../gazebo_ros}/launch/shapes_world.launch | 0 .../gazebo_ros}/launch/willowgarage_world.launch | 0 .../gazebo_ros}/package.xml | 0 .../gazebo_ros}/scripts/debug | 0 .../gazebo_ros}/scripts/gazebo | 0 .../gazebo_ros}/scripts/gdbrun | 0 .../gazebo_ros}/scripts/gzclient | 0 .../gazebo_ros}/scripts/gzserver | 0 .../gazebo_ros}/scripts/libcommon.sh | 0 .../gazebo_ros}/scripts/perf | 0 .../gazebo_ros}/scripts/spawn_model | 0 {gazebo_ros => .ros1_unported/gazebo_ros}/setup.py | 0 .../gazebo_ros/src/gazebo_ros/__init__.py | 0 .../gazebo_ros}/src/gazebo_ros/gazebo_interface.py | 0 .../gazebo_ros}/src/gazebo_ros_api_plugin.cpp | 0 .../gazebo_ros}/src/gazebo_ros_paths_plugin.cpp | 0 .../gazebo_ros}/test/CMakeLists.txt | 0 .../test/ros_network/gazebo_network_api.yaml | 0 .../test/ros_network/no_gazebo_network_api.yaml | 0 .../gazebo_ros}/test/ros_network/ros_api_checker | 0 .../test/ros_network/ros_network_default.test | 0 .../test/ros_network/ros_network_disabled.test | 0 .../gazebo_ros_control}/CHANGELOG.rst | 0 .../gazebo_ros_control}/CMakeLists.txt | 0 .../gazebo_ros_control}/README.md | 0 .../gazebo_ros_control/default_robot_hw_sim.h | 0 .../gazebo_ros_control/gazebo_ros_control_plugin.h | 0 .../include/gazebo_ros_control/robot_hw_sim.h | 0 .../gazebo_ros_control}/package.xml | 0 .../gazebo_ros_control}/robot_hw_sim_plugins.xml | 0 .../src/default_robot_hw_sim.cpp | 0 .../src/gazebo_ros_control_plugin.cpp | 0 .../gazebo_ros_pkgs}/CHANGELOG.rst | 0 .../gazebo_ros_pkgs}/CMakeLists.txt | 0 .../documentation/gazebo_ros_api.odg | Bin .../documentation/gazebo_ros_api.pdf | Bin .../documentation/gazebo_ros_api.png | Bin .../documentation/gazebo_ros_transmission.odg | Bin .../documentation/gazebo_ros_transmission.pdf | Bin .../documentation/gazebo_ros_transmission.png | Bin .../gazebo_ros_pkgs}/package.xml | 0 276 files changed, 0 insertions(+), 0 deletions(-) rename gazebo_plugins/src/gazebo_plugins/__init__.py => .ros1_unported/AMENT_IGNORE (100%) rename gazebo_ros/src/gazebo_ros/__init__.py => .ros1_unported/COLCON_IGNORE (100%) rename {gazebo_dev => .ros1_unported/gazebo_dev}/CHANGELOG.rst (100%) rename {gazebo_dev => .ros1_unported/gazebo_dev}/CMakeLists.txt (100%) rename {gazebo_dev => .ros1_unported/gazebo_dev}/cmake/gazebo_dev-extras.cmake (100%) rename {gazebo_dev => .ros1_unported/gazebo_dev}/package.xml (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/CHANGELOG.rst (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/CMakeLists.txt (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/Media/models/chair/doc.kml (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/Media/models/chair/images/texture0.jpg (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/Media/models/chair/images/texture1.jpg (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/Media/models/chair/models/Chair.dae (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/Media/models/chair/models/Chair.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/Media/models/chair/textures.txt (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/cfg/CameraSynchronizer.cfg (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/cfg/GazeboRosCamera.cfg (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/cfg/GazeboRosOpenniKinect.cfg (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/cfg/Hokuyo.cfg (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/MultiCameraPlugin.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/PubQueue.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_block_laser.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_bumper.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_camera.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_camera_utils.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_depth_camera.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_diff_drive.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_elevator.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_f3d.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_force.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_ft_sensor.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_gpu_laser.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_hand_of_god.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_harness.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_imu.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_imu_sensor.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_joint_pose_trajectory.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_joint_state_publisher.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_laser.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_multicamera.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_openni_kinect.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_p3d.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_planar_move.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_projector.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_prosilica.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_range.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_skid_steer_drive.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_template.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_tricycle_drive.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_triggered_camera.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_triggered_multicamera.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_utils.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_vacuum_gripper.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/gazebo_ros_video.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/include/gazebo_plugins/vision_reconfigure.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/package.xml (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/scripts/gazebo_model (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/scripts/set_pose.py (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/scripts/set_wrench.py (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/scripts/test_range.py (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/setup.py (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/MultiCameraPlugin.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/camera_synchronizer.cpp (100%) create mode 100644 .ros1_unported/gazebo_plugins/src/gazebo_plugins/__init__.py rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_plugins/gazebo_plugins_interface.py (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_block_laser.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_bumper.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_camera.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_camera_utils.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_depth_camera.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_diff_drive.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_elevator.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_f3d.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_force.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_ft_sensor.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_gpu_laser.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_hand_of_god.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_harness.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_imu.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_imu_sensor.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_joint_pose_trajectory.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_joint_state_publisher.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_laser.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_multicamera.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_openni_kinect.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_p3d.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_planar_move.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_projector.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_prosilica.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_range.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_skid_steer_drive.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_template.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_tricycle_drive.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_triggered_camera.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_triggered_multicamera.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_utils.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_vacuum_gripper.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/gazebo_ros_video.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/hokuyo_node.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/src/vision_reconfigure.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/bumper_test/gazebo_ros_bumper.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/bumper_test/test_bumper.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/bumper_test/test_bumper.py (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/camera.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/camera.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/camera.test (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/camera.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/camera16bit.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/camera16bit.test (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/camera16bit.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/depth_camera.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/depth_camera.test (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/depth_camera.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/distortion.h (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/distortion_barrel.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/distortion_barrel.test (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/distortion_barrel.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/distortion_pincushion.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/distortion_pincushion.test (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/distortion_pincushion.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/multicamera.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/multicamera.test (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/multicamera.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/triggered_camera.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/triggered_camera.test (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/camera/triggered_camera.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/config/example_models.yaml (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/launch/multi_robot_scenario.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/launch/pioneer3dx.gazebo.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/launch/pioneer3dx.rviz (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/launch/pioneer3dx.urdf.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/laser/hokuyo.dae (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/Coordinates (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/back_rim.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/back_sonar.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/center_hubcap.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/center_wheel.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/chassis.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/front_rim.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/front_sonar.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/left_hubcap.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/left_wheel.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/right_hubcap.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/right_wheel.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/swivel.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/meshes/p3dx/top.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/camera/camera.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/laser/hokuyo.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/laser/hokuyo_gpu.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/materials.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/p3dx/battery_block.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/p3dx/inertia_tensors.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/p3dx/pioneer3dx.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_body.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_chassis.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_plugins.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_sonar.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_swivel.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_wheel.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/p3d_test/test_3_double_pendulums.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/p3d_test/test_3_single_pendulums.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/p3d_test/test_double_pendulum.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/p3d_test/test_link_pose.py (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/p3d_test/test_single_pendulum.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/p3d_test/worlds/3_double_pendulums.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/p3d_test/worlds/3_single_pendulums.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/p3d_test/worlds/double_pendulum.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/p3d_test/worlds/single_pendulum.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/pub_joint_trajectory_test.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/range/range_plugin.test (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/set_model_state_test/set_model_state_test.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/set_model_state_test/set_model_state_test.test (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/set_model_state_test/set_model_state_test_p2dx.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/spawn_test/parameter_server_test.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/spawn_test/spawn_robots.sh (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/test_worlds/bumper_test.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/test_worlds/elevator.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/test_worlds/gazebo_ros_block_laser.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/test_worlds/gazebo_ros_camera.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/test_worlds/gazebo_ros_depth_camera.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/test_worlds/gazebo_ros_gpu_laser.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/test_worlds/gazebo_ros_laser.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/test_worlds/gazebo_ros_range.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/test_worlds/gazebo_ros_trimesh_collision.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/test_worlds/test_lasers.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/launch/.directory (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/launch/tricycle.gazebo.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/launch/tricycle.rviz (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/launch/tricycle.urdf.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/launch/tricycle_drive_scenario.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/launch/tricycle_rviz.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/xacro/.directory (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/xacro/materials.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/xacro/tricycle/inertia_tensors.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/xacro/tricycle/tricycle.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/xacro/tricycle/tricycle_body.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/xacro/tricycle/tricycle_chassis.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/xacro/tricycle/tricycle_plugins.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/xacro/tricycle/wheel.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test/tricycle_drive/xacro/tricycle/wheel_actuated.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/CMakeLists_tests_pkg.txt (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/contact_tolerance/contact_tolerance.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/contact_tolerance/contact_tolerance.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/large_models/large_model.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/large_models/large_model.urdf.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/large_models/large_models.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/large_models/smaller_large_model.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/large_models/smaller_large_model.urdf.xacro (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/lcp_tests/balance.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/lcp_tests/balance.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/lcp_tests/stack.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/lcp_tests/stack.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/lcp_tests/stacks.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/lcp_tests/stacks.world (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/meshes/cube.wings (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/meshes/cube_20k.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/meshes/cube_30k.stl (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/spawn_model/check_model.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/spawn_model/spawn_box.cpp (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/spawn_model/spawn_box.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/spawn_model/spawn_box_file.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/spawn_model/spawn_box_param.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/trimesh_tests/test_trimesh.launch (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/urdf/box.urdf (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/urdf/cube.urdf (100%) rename {gazebo_plugins => .ros1_unported/gazebo_plugins}/test2/worlds/empty.world (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/.idea/gazebo_ros.iml (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/CHANGELOG.rst (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/CMakeLists.txt (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/cfg/Physics.cfg (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/include/gazebo_ros/gazebo_ros_api_plugin.h (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/launch/elevator_world.launch (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/launch/empty_world.launch (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/launch/mud_world.launch (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/launch/range_world.launch (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/launch/rubble_world.launch (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/launch/shapes_world.launch (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/launch/willowgarage_world.launch (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/package.xml (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/scripts/debug (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/scripts/gazebo (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/scripts/gdbrun (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/scripts/gzclient (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/scripts/gzserver (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/scripts/libcommon.sh (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/scripts/perf (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/scripts/spawn_model (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/setup.py (100%) create mode 100644 .ros1_unported/gazebo_ros/src/gazebo_ros/__init__.py rename {gazebo_ros => .ros1_unported/gazebo_ros}/src/gazebo_ros/gazebo_interface.py (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/src/gazebo_ros_api_plugin.cpp (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/src/gazebo_ros_paths_plugin.cpp (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/test/CMakeLists.txt (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/test/ros_network/gazebo_network_api.yaml (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/test/ros_network/no_gazebo_network_api.yaml (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/test/ros_network/ros_api_checker (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/test/ros_network/ros_network_default.test (100%) rename {gazebo_ros => .ros1_unported/gazebo_ros}/test/ros_network/ros_network_disabled.test (100%) rename {gazebo_ros_control => .ros1_unported/gazebo_ros_control}/CHANGELOG.rst (100%) rename {gazebo_ros_control => .ros1_unported/gazebo_ros_control}/CMakeLists.txt (100%) rename {gazebo_ros_control => .ros1_unported/gazebo_ros_control}/README.md (100%) rename {gazebo_ros_control => .ros1_unported/gazebo_ros_control}/include/gazebo_ros_control/default_robot_hw_sim.h (100%) rename {gazebo_ros_control => .ros1_unported/gazebo_ros_control}/include/gazebo_ros_control/gazebo_ros_control_plugin.h (100%) rename {gazebo_ros_control => .ros1_unported/gazebo_ros_control}/include/gazebo_ros_control/robot_hw_sim.h (100%) rename {gazebo_ros_control => .ros1_unported/gazebo_ros_control}/package.xml (100%) rename {gazebo_ros_control => .ros1_unported/gazebo_ros_control}/robot_hw_sim_plugins.xml (100%) rename {gazebo_ros_control => .ros1_unported/gazebo_ros_control}/src/default_robot_hw_sim.cpp (100%) rename {gazebo_ros_control => .ros1_unported/gazebo_ros_control}/src/gazebo_ros_control_plugin.cpp (100%) rename {gazebo_ros_pkgs => .ros1_unported/gazebo_ros_pkgs}/CHANGELOG.rst (100%) rename {gazebo_ros_pkgs => .ros1_unported/gazebo_ros_pkgs}/CMakeLists.txt (100%) rename {gazebo_ros_pkgs => .ros1_unported/gazebo_ros_pkgs}/documentation/gazebo_ros_api.odg (100%) rename {gazebo_ros_pkgs => .ros1_unported/gazebo_ros_pkgs}/documentation/gazebo_ros_api.pdf (100%) rename {gazebo_ros_pkgs => .ros1_unported/gazebo_ros_pkgs}/documentation/gazebo_ros_api.png (100%) rename {gazebo_ros_pkgs => .ros1_unported/gazebo_ros_pkgs}/documentation/gazebo_ros_transmission.odg (100%) rename {gazebo_ros_pkgs => .ros1_unported/gazebo_ros_pkgs}/documentation/gazebo_ros_transmission.pdf (100%) rename {gazebo_ros_pkgs => .ros1_unported/gazebo_ros_pkgs}/documentation/gazebo_ros_transmission.png (100%) rename {gazebo_ros_pkgs => .ros1_unported/gazebo_ros_pkgs}/package.xml (100%) diff --git a/gazebo_plugins/src/gazebo_plugins/__init__.py b/.ros1_unported/AMENT_IGNORE similarity index 100% rename from gazebo_plugins/src/gazebo_plugins/__init__.py rename to .ros1_unported/AMENT_IGNORE diff --git a/gazebo_ros/src/gazebo_ros/__init__.py b/.ros1_unported/COLCON_IGNORE similarity index 100% rename from gazebo_ros/src/gazebo_ros/__init__.py rename to .ros1_unported/COLCON_IGNORE diff --git a/gazebo_dev/CHANGELOG.rst b/.ros1_unported/gazebo_dev/CHANGELOG.rst similarity index 100% rename from gazebo_dev/CHANGELOG.rst rename to .ros1_unported/gazebo_dev/CHANGELOG.rst diff --git a/gazebo_dev/CMakeLists.txt b/.ros1_unported/gazebo_dev/CMakeLists.txt similarity index 100% rename from gazebo_dev/CMakeLists.txt rename to .ros1_unported/gazebo_dev/CMakeLists.txt diff --git a/gazebo_dev/cmake/gazebo_dev-extras.cmake b/.ros1_unported/gazebo_dev/cmake/gazebo_dev-extras.cmake similarity index 100% rename from gazebo_dev/cmake/gazebo_dev-extras.cmake rename to .ros1_unported/gazebo_dev/cmake/gazebo_dev-extras.cmake diff --git a/gazebo_dev/package.xml b/.ros1_unported/gazebo_dev/package.xml similarity index 100% rename from gazebo_dev/package.xml rename to .ros1_unported/gazebo_dev/package.xml diff --git a/gazebo_plugins/CHANGELOG.rst b/.ros1_unported/gazebo_plugins/CHANGELOG.rst similarity index 100% rename from gazebo_plugins/CHANGELOG.rst rename to .ros1_unported/gazebo_plugins/CHANGELOG.rst diff --git a/gazebo_plugins/CMakeLists.txt b/.ros1_unported/gazebo_plugins/CMakeLists.txt similarity index 100% rename from gazebo_plugins/CMakeLists.txt rename to .ros1_unported/gazebo_plugins/CMakeLists.txt diff --git a/gazebo_plugins/Media/models/chair/doc.kml b/.ros1_unported/gazebo_plugins/Media/models/chair/doc.kml similarity index 100% rename from gazebo_plugins/Media/models/chair/doc.kml rename to .ros1_unported/gazebo_plugins/Media/models/chair/doc.kml diff --git a/gazebo_plugins/Media/models/chair/images/texture0.jpg b/.ros1_unported/gazebo_plugins/Media/models/chair/images/texture0.jpg similarity index 100% rename from gazebo_plugins/Media/models/chair/images/texture0.jpg rename to .ros1_unported/gazebo_plugins/Media/models/chair/images/texture0.jpg diff --git a/gazebo_plugins/Media/models/chair/images/texture1.jpg b/.ros1_unported/gazebo_plugins/Media/models/chair/images/texture1.jpg similarity index 100% rename from gazebo_plugins/Media/models/chair/images/texture1.jpg rename to .ros1_unported/gazebo_plugins/Media/models/chair/images/texture1.jpg diff --git a/gazebo_plugins/Media/models/chair/models/Chair.dae b/.ros1_unported/gazebo_plugins/Media/models/chair/models/Chair.dae similarity index 100% rename from gazebo_plugins/Media/models/chair/models/Chair.dae rename to .ros1_unported/gazebo_plugins/Media/models/chair/models/Chair.dae diff --git a/gazebo_plugins/Media/models/chair/models/Chair.stl b/.ros1_unported/gazebo_plugins/Media/models/chair/models/Chair.stl similarity index 100% rename from gazebo_plugins/Media/models/chair/models/Chair.stl rename to .ros1_unported/gazebo_plugins/Media/models/chair/models/Chair.stl diff --git a/gazebo_plugins/Media/models/chair/textures.txt b/.ros1_unported/gazebo_plugins/Media/models/chair/textures.txt similarity index 100% rename from gazebo_plugins/Media/models/chair/textures.txt rename to .ros1_unported/gazebo_plugins/Media/models/chair/textures.txt diff --git a/gazebo_plugins/cfg/CameraSynchronizer.cfg b/.ros1_unported/gazebo_plugins/cfg/CameraSynchronizer.cfg similarity index 100% rename from gazebo_plugins/cfg/CameraSynchronizer.cfg rename to .ros1_unported/gazebo_plugins/cfg/CameraSynchronizer.cfg diff --git a/gazebo_plugins/cfg/GazeboRosCamera.cfg b/.ros1_unported/gazebo_plugins/cfg/GazeboRosCamera.cfg similarity index 100% rename from gazebo_plugins/cfg/GazeboRosCamera.cfg rename to .ros1_unported/gazebo_plugins/cfg/GazeboRosCamera.cfg diff --git a/gazebo_plugins/cfg/GazeboRosOpenniKinect.cfg b/.ros1_unported/gazebo_plugins/cfg/GazeboRosOpenniKinect.cfg similarity index 100% rename from gazebo_plugins/cfg/GazeboRosOpenniKinect.cfg rename to .ros1_unported/gazebo_plugins/cfg/GazeboRosOpenniKinect.cfg diff --git a/gazebo_plugins/cfg/Hokuyo.cfg b/.ros1_unported/gazebo_plugins/cfg/Hokuyo.cfg similarity index 100% rename from gazebo_plugins/cfg/Hokuyo.cfg rename to .ros1_unported/gazebo_plugins/cfg/Hokuyo.cfg diff --git a/gazebo_plugins/include/gazebo_plugins/MultiCameraPlugin.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/MultiCameraPlugin.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/MultiCameraPlugin.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/MultiCameraPlugin.h diff --git a/gazebo_plugins/include/gazebo_plugins/PubQueue.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/PubQueue.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/PubQueue.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/PubQueue.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_block_laser.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_block_laser.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_block_laser.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_block_laser.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_bumper.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_bumper.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_bumper.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_bumper.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera_utils.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera_utils.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera_utils.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera_utils.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_depth_camera.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_depth_camera.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_depth_camera.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_depth_camera.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_diff_drive.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_diff_drive.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_diff_drive.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_diff_drive.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_elevator.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_elevator.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_elevator.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_elevator.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_f3d.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_f3d.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_f3d.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_f3d.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_force.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_force.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_force.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_force.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_ft_sensor.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_ft_sensor.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_ft_sensor.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_ft_sensor.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_gpu_laser.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_gpu_laser.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_gpu_laser.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_gpu_laser.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_hand_of_god.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_hand_of_god.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_hand_of_god.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_hand_of_god.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_harness.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_harness.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_harness.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_harness.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_imu.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_imu.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_imu.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_imu.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_imu_sensor.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_imu_sensor.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_imu_sensor.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_imu_sensor.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_joint_pose_trajectory.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_joint_pose_trajectory.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_joint_pose_trajectory.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_joint_pose_trajectory.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_joint_state_publisher.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_joint_state_publisher.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_joint_state_publisher.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_joint_state_publisher.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_laser.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_laser.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_laser.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_laser.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_multicamera.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_multicamera.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_multicamera.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_multicamera.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_openni_kinect.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_openni_kinect.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_openni_kinect.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_openni_kinect.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_p3d.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_p3d.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_p3d.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_p3d.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_planar_move.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_planar_move.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_planar_move.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_planar_move.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_projector.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_projector.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_projector.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_projector.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_prosilica.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_prosilica.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_prosilica.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_prosilica.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_range.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_range.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_range.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_range.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_skid_steer_drive.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_skid_steer_drive.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_skid_steer_drive.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_skid_steer_drive.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_template.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_template.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_template.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_template.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_tricycle_drive.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_tricycle_drive.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_tricycle_drive.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_tricycle_drive.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_triggered_camera.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_triggered_camera.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_triggered_camera.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_triggered_camera.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_triggered_multicamera.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_triggered_multicamera.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_triggered_multicamera.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_triggered_multicamera.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_utils.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_vacuum_gripper.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_vacuum_gripper.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_vacuum_gripper.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_vacuum_gripper.h diff --git a/gazebo_plugins/include/gazebo_plugins/gazebo_ros_video.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_video.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/gazebo_ros_video.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/gazebo_ros_video.h diff --git a/gazebo_plugins/include/gazebo_plugins/vision_reconfigure.h b/.ros1_unported/gazebo_plugins/include/gazebo_plugins/vision_reconfigure.h similarity index 100% rename from gazebo_plugins/include/gazebo_plugins/vision_reconfigure.h rename to .ros1_unported/gazebo_plugins/include/gazebo_plugins/vision_reconfigure.h diff --git a/gazebo_plugins/package.xml b/.ros1_unported/gazebo_plugins/package.xml similarity index 100% rename from gazebo_plugins/package.xml rename to .ros1_unported/gazebo_plugins/package.xml diff --git a/gazebo_plugins/scripts/gazebo_model b/.ros1_unported/gazebo_plugins/scripts/gazebo_model similarity index 100% rename from gazebo_plugins/scripts/gazebo_model rename to .ros1_unported/gazebo_plugins/scripts/gazebo_model diff --git a/gazebo_plugins/scripts/set_pose.py b/.ros1_unported/gazebo_plugins/scripts/set_pose.py similarity index 100% rename from gazebo_plugins/scripts/set_pose.py rename to .ros1_unported/gazebo_plugins/scripts/set_pose.py diff --git a/gazebo_plugins/scripts/set_wrench.py b/.ros1_unported/gazebo_plugins/scripts/set_wrench.py similarity index 100% rename from gazebo_plugins/scripts/set_wrench.py rename to .ros1_unported/gazebo_plugins/scripts/set_wrench.py diff --git a/gazebo_plugins/scripts/test_range.py b/.ros1_unported/gazebo_plugins/scripts/test_range.py similarity index 100% rename from gazebo_plugins/scripts/test_range.py rename to .ros1_unported/gazebo_plugins/scripts/test_range.py diff --git a/gazebo_plugins/setup.py b/.ros1_unported/gazebo_plugins/setup.py similarity index 100% rename from gazebo_plugins/setup.py rename to .ros1_unported/gazebo_plugins/setup.py diff --git a/gazebo_plugins/src/MultiCameraPlugin.cpp b/.ros1_unported/gazebo_plugins/src/MultiCameraPlugin.cpp similarity index 100% rename from gazebo_plugins/src/MultiCameraPlugin.cpp rename to .ros1_unported/gazebo_plugins/src/MultiCameraPlugin.cpp diff --git a/gazebo_plugins/src/camera_synchronizer.cpp b/.ros1_unported/gazebo_plugins/src/camera_synchronizer.cpp similarity index 100% rename from gazebo_plugins/src/camera_synchronizer.cpp rename to .ros1_unported/gazebo_plugins/src/camera_synchronizer.cpp diff --git a/.ros1_unported/gazebo_plugins/src/gazebo_plugins/__init__.py b/.ros1_unported/gazebo_plugins/src/gazebo_plugins/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/gazebo_plugins/src/gazebo_plugins/gazebo_plugins_interface.py b/.ros1_unported/gazebo_plugins/src/gazebo_plugins/gazebo_plugins_interface.py similarity index 100% rename from gazebo_plugins/src/gazebo_plugins/gazebo_plugins_interface.py rename to .ros1_unported/gazebo_plugins/src/gazebo_plugins/gazebo_plugins_interface.py diff --git a/gazebo_plugins/src/gazebo_ros_block_laser.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_block_laser.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_block_laser.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_block_laser.cpp diff --git a/gazebo_plugins/src/gazebo_ros_bumper.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_bumper.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_bumper.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_bumper.cpp diff --git a/gazebo_plugins/src/gazebo_ros_camera.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_camera.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_camera.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_camera.cpp diff --git a/gazebo_plugins/src/gazebo_ros_camera_utils.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_camera_utils.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_camera_utils.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_camera_utils.cpp diff --git a/gazebo_plugins/src/gazebo_ros_depth_camera.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_depth_camera.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_depth_camera.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_depth_camera.cpp diff --git a/gazebo_plugins/src/gazebo_ros_diff_drive.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_diff_drive.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_diff_drive.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_diff_drive.cpp diff --git a/gazebo_plugins/src/gazebo_ros_elevator.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_elevator.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_elevator.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_elevator.cpp diff --git a/gazebo_plugins/src/gazebo_ros_f3d.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_f3d.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_f3d.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_f3d.cpp diff --git a/gazebo_plugins/src/gazebo_ros_force.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_force.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_force.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_force.cpp diff --git a/gazebo_plugins/src/gazebo_ros_ft_sensor.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_ft_sensor.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_ft_sensor.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_ft_sensor.cpp diff --git a/gazebo_plugins/src/gazebo_ros_gpu_laser.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_gpu_laser.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_gpu_laser.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_gpu_laser.cpp diff --git a/gazebo_plugins/src/gazebo_ros_hand_of_god.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_hand_of_god.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_hand_of_god.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_hand_of_god.cpp diff --git a/gazebo_plugins/src/gazebo_ros_harness.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_harness.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_harness.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_harness.cpp diff --git a/gazebo_plugins/src/gazebo_ros_imu.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_imu.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_imu.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_imu.cpp diff --git a/gazebo_plugins/src/gazebo_ros_imu_sensor.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_imu_sensor.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_imu_sensor.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_imu_sensor.cpp diff --git a/gazebo_plugins/src/gazebo_ros_joint_pose_trajectory.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_joint_pose_trajectory.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_joint_pose_trajectory.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_joint_pose_trajectory.cpp diff --git a/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp diff --git a/gazebo_plugins/src/gazebo_ros_laser.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_laser.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_laser.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_laser.cpp diff --git a/gazebo_plugins/src/gazebo_ros_multicamera.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_multicamera.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_multicamera.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_multicamera.cpp diff --git a/gazebo_plugins/src/gazebo_ros_openni_kinect.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_openni_kinect.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_openni_kinect.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_openni_kinect.cpp diff --git a/gazebo_plugins/src/gazebo_ros_p3d.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_p3d.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_p3d.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_p3d.cpp diff --git a/gazebo_plugins/src/gazebo_ros_planar_move.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_planar_move.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_planar_move.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_planar_move.cpp diff --git a/gazebo_plugins/src/gazebo_ros_projector.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_projector.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_projector.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_projector.cpp diff --git a/gazebo_plugins/src/gazebo_ros_prosilica.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_prosilica.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_prosilica.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_prosilica.cpp diff --git a/gazebo_plugins/src/gazebo_ros_range.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_range.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_range.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_range.cpp diff --git a/gazebo_plugins/src/gazebo_ros_skid_steer_drive.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_skid_steer_drive.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_skid_steer_drive.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_skid_steer_drive.cpp diff --git a/gazebo_plugins/src/gazebo_ros_template.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_template.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_template.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_template.cpp diff --git a/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp diff --git a/gazebo_plugins/src/gazebo_ros_triggered_camera.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_triggered_camera.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_triggered_camera.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_triggered_camera.cpp diff --git a/gazebo_plugins/src/gazebo_ros_triggered_multicamera.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_triggered_multicamera.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_triggered_multicamera.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_triggered_multicamera.cpp diff --git a/gazebo_plugins/src/gazebo_ros_utils.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_utils.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_utils.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_utils.cpp diff --git a/gazebo_plugins/src/gazebo_ros_vacuum_gripper.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_vacuum_gripper.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_vacuum_gripper.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_vacuum_gripper.cpp diff --git a/gazebo_plugins/src/gazebo_ros_video.cpp b/.ros1_unported/gazebo_plugins/src/gazebo_ros_video.cpp similarity index 100% rename from gazebo_plugins/src/gazebo_ros_video.cpp rename to .ros1_unported/gazebo_plugins/src/gazebo_ros_video.cpp diff --git a/gazebo_plugins/src/hokuyo_node.cpp b/.ros1_unported/gazebo_plugins/src/hokuyo_node.cpp similarity index 100% rename from gazebo_plugins/src/hokuyo_node.cpp rename to .ros1_unported/gazebo_plugins/src/hokuyo_node.cpp diff --git a/gazebo_plugins/src/vision_reconfigure.cpp b/.ros1_unported/gazebo_plugins/src/vision_reconfigure.cpp similarity index 100% rename from gazebo_plugins/src/vision_reconfigure.cpp rename to .ros1_unported/gazebo_plugins/src/vision_reconfigure.cpp diff --git a/gazebo_plugins/test/bumper_test/gazebo_ros_bumper.world b/.ros1_unported/gazebo_plugins/test/bumper_test/gazebo_ros_bumper.world similarity index 100% rename from gazebo_plugins/test/bumper_test/gazebo_ros_bumper.world rename to .ros1_unported/gazebo_plugins/test/bumper_test/gazebo_ros_bumper.world diff --git a/gazebo_plugins/test/bumper_test/test_bumper.launch b/.ros1_unported/gazebo_plugins/test/bumper_test/test_bumper.launch similarity index 100% rename from gazebo_plugins/test/bumper_test/test_bumper.launch rename to .ros1_unported/gazebo_plugins/test/bumper_test/test_bumper.launch diff --git a/gazebo_plugins/test/bumper_test/test_bumper.py b/.ros1_unported/gazebo_plugins/test/bumper_test/test_bumper.py similarity index 100% rename from gazebo_plugins/test/bumper_test/test_bumper.py rename to .ros1_unported/gazebo_plugins/test/bumper_test/test_bumper.py diff --git a/gazebo_plugins/test/camera/camera.cpp b/.ros1_unported/gazebo_plugins/test/camera/camera.cpp similarity index 100% rename from gazebo_plugins/test/camera/camera.cpp rename to .ros1_unported/gazebo_plugins/test/camera/camera.cpp diff --git a/gazebo_plugins/test/camera/camera.h b/.ros1_unported/gazebo_plugins/test/camera/camera.h similarity index 100% rename from gazebo_plugins/test/camera/camera.h rename to .ros1_unported/gazebo_plugins/test/camera/camera.h diff --git a/gazebo_plugins/test/camera/camera.test b/.ros1_unported/gazebo_plugins/test/camera/camera.test similarity index 100% rename from gazebo_plugins/test/camera/camera.test rename to .ros1_unported/gazebo_plugins/test/camera/camera.test diff --git a/gazebo_plugins/test/camera/camera.world b/.ros1_unported/gazebo_plugins/test/camera/camera.world similarity index 100% rename from gazebo_plugins/test/camera/camera.world rename to .ros1_unported/gazebo_plugins/test/camera/camera.world diff --git a/gazebo_plugins/test/camera/camera16bit.cpp b/.ros1_unported/gazebo_plugins/test/camera/camera16bit.cpp similarity index 100% rename from gazebo_plugins/test/camera/camera16bit.cpp rename to .ros1_unported/gazebo_plugins/test/camera/camera16bit.cpp diff --git a/gazebo_plugins/test/camera/camera16bit.test b/.ros1_unported/gazebo_plugins/test/camera/camera16bit.test similarity index 100% rename from gazebo_plugins/test/camera/camera16bit.test rename to .ros1_unported/gazebo_plugins/test/camera/camera16bit.test diff --git a/gazebo_plugins/test/camera/camera16bit.world b/.ros1_unported/gazebo_plugins/test/camera/camera16bit.world similarity index 100% rename from gazebo_plugins/test/camera/camera16bit.world rename to .ros1_unported/gazebo_plugins/test/camera/camera16bit.world diff --git a/gazebo_plugins/test/camera/depth_camera.cpp b/.ros1_unported/gazebo_plugins/test/camera/depth_camera.cpp similarity index 100% rename from gazebo_plugins/test/camera/depth_camera.cpp rename to .ros1_unported/gazebo_plugins/test/camera/depth_camera.cpp diff --git a/gazebo_plugins/test/camera/depth_camera.test b/.ros1_unported/gazebo_plugins/test/camera/depth_camera.test similarity index 100% rename from gazebo_plugins/test/camera/depth_camera.test rename to .ros1_unported/gazebo_plugins/test/camera/depth_camera.test diff --git a/gazebo_plugins/test/camera/depth_camera.world b/.ros1_unported/gazebo_plugins/test/camera/depth_camera.world similarity index 100% rename from gazebo_plugins/test/camera/depth_camera.world rename to .ros1_unported/gazebo_plugins/test/camera/depth_camera.world diff --git a/gazebo_plugins/test/camera/distortion.h b/.ros1_unported/gazebo_plugins/test/camera/distortion.h similarity index 100% rename from gazebo_plugins/test/camera/distortion.h rename to .ros1_unported/gazebo_plugins/test/camera/distortion.h diff --git a/gazebo_plugins/test/camera/distortion_barrel.cpp b/.ros1_unported/gazebo_plugins/test/camera/distortion_barrel.cpp similarity index 100% rename from gazebo_plugins/test/camera/distortion_barrel.cpp rename to .ros1_unported/gazebo_plugins/test/camera/distortion_barrel.cpp diff --git a/gazebo_plugins/test/camera/distortion_barrel.test b/.ros1_unported/gazebo_plugins/test/camera/distortion_barrel.test similarity index 100% rename from gazebo_plugins/test/camera/distortion_barrel.test rename to .ros1_unported/gazebo_plugins/test/camera/distortion_barrel.test diff --git a/gazebo_plugins/test/camera/distortion_barrel.world b/.ros1_unported/gazebo_plugins/test/camera/distortion_barrel.world similarity index 100% rename from gazebo_plugins/test/camera/distortion_barrel.world rename to .ros1_unported/gazebo_plugins/test/camera/distortion_barrel.world diff --git a/gazebo_plugins/test/camera/distortion_pincushion.cpp b/.ros1_unported/gazebo_plugins/test/camera/distortion_pincushion.cpp similarity index 100% rename from gazebo_plugins/test/camera/distortion_pincushion.cpp rename to .ros1_unported/gazebo_plugins/test/camera/distortion_pincushion.cpp diff --git a/gazebo_plugins/test/camera/distortion_pincushion.test b/.ros1_unported/gazebo_plugins/test/camera/distortion_pincushion.test similarity index 100% rename from gazebo_plugins/test/camera/distortion_pincushion.test rename to .ros1_unported/gazebo_plugins/test/camera/distortion_pincushion.test diff --git a/gazebo_plugins/test/camera/distortion_pincushion.world b/.ros1_unported/gazebo_plugins/test/camera/distortion_pincushion.world similarity index 100% rename from gazebo_plugins/test/camera/distortion_pincushion.world rename to .ros1_unported/gazebo_plugins/test/camera/distortion_pincushion.world diff --git a/gazebo_plugins/test/camera/multicamera.cpp b/.ros1_unported/gazebo_plugins/test/camera/multicamera.cpp similarity index 100% rename from gazebo_plugins/test/camera/multicamera.cpp rename to .ros1_unported/gazebo_plugins/test/camera/multicamera.cpp diff --git a/gazebo_plugins/test/camera/multicamera.test b/.ros1_unported/gazebo_plugins/test/camera/multicamera.test similarity index 100% rename from gazebo_plugins/test/camera/multicamera.test rename to .ros1_unported/gazebo_plugins/test/camera/multicamera.test diff --git a/gazebo_plugins/test/camera/multicamera.world b/.ros1_unported/gazebo_plugins/test/camera/multicamera.world similarity index 100% rename from gazebo_plugins/test/camera/multicamera.world rename to .ros1_unported/gazebo_plugins/test/camera/multicamera.world diff --git a/gazebo_plugins/test/camera/triggered_camera.cpp b/.ros1_unported/gazebo_plugins/test/camera/triggered_camera.cpp similarity index 100% rename from gazebo_plugins/test/camera/triggered_camera.cpp rename to .ros1_unported/gazebo_plugins/test/camera/triggered_camera.cpp diff --git a/gazebo_plugins/test/camera/triggered_camera.test b/.ros1_unported/gazebo_plugins/test/camera/triggered_camera.test similarity index 100% rename from gazebo_plugins/test/camera/triggered_camera.test rename to .ros1_unported/gazebo_plugins/test/camera/triggered_camera.test diff --git a/gazebo_plugins/test/camera/triggered_camera.world b/.ros1_unported/gazebo_plugins/test/camera/triggered_camera.world similarity index 100% rename from gazebo_plugins/test/camera/triggered_camera.world rename to .ros1_unported/gazebo_plugins/test/camera/triggered_camera.world diff --git a/gazebo_plugins/test/config/example_models.yaml b/.ros1_unported/gazebo_plugins/test/config/example_models.yaml similarity index 100% rename from gazebo_plugins/test/config/example_models.yaml rename to .ros1_unported/gazebo_plugins/test/config/example_models.yaml diff --git a/gazebo_plugins/test/multi_robot_scenario/launch/multi_robot_scenario.launch b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/launch/multi_robot_scenario.launch similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/launch/multi_robot_scenario.launch rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/launch/multi_robot_scenario.launch diff --git a/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.gazebo.launch b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.gazebo.launch similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.gazebo.launch rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.gazebo.launch diff --git a/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.rviz b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.rviz similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.rviz rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.rviz diff --git a/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.urdf.launch b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.urdf.launch similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.urdf.launch rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.urdf.launch diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/laser/hokuyo.dae b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/laser/hokuyo.dae similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/laser/hokuyo.dae rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/laser/hokuyo.dae diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/Coordinates b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/Coordinates similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/Coordinates rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/Coordinates diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_rim.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_rim.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_rim.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_rim.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_sonar.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_sonar.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_sonar.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_sonar.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_hubcap.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_hubcap.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_hubcap.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_hubcap.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_wheel.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_wheel.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_wheel.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_wheel.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/chassis.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/chassis.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/chassis.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/chassis.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_rim.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_rim.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_rim.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_rim.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_sonar.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_sonar.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_sonar.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_sonar.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_hubcap.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_hubcap.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_hubcap.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_hubcap.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_wheel.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_wheel.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_wheel.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_wheel.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_hubcap.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_hubcap.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_hubcap.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_hubcap.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_wheel.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_wheel.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_wheel.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_wheel.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/swivel.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/swivel.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/swivel.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/swivel.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/top.stl b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/top.stl similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/top.stl rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/top.stl diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/camera/camera.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/camera/camera.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/camera/camera.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/camera/camera.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/laser/hokuyo.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/laser/hokuyo.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/laser/hokuyo.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/laser/hokuyo.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/laser/hokuyo_gpu.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/laser/hokuyo_gpu.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/laser/hokuyo_gpu.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/laser/hokuyo_gpu.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/materials.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/materials.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/materials.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/materials.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/battery_block.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/battery_block.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/battery_block.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/battery_block.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/inertia_tensors.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/inertia_tensors.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/inertia_tensors.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/inertia_tensors.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_body.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_body.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_body.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_body.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_chassis.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_chassis.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_chassis.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_chassis.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_plugins.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_plugins.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_plugins.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_plugins.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_sonar.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_sonar.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_sonar.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_sonar.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_swivel.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_swivel.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_swivel.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_swivel.xacro diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_wheel.xacro b/.ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_wheel.xacro similarity index 100% rename from gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_wheel.xacro rename to .ros1_unported/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_wheel.xacro diff --git a/gazebo_plugins/test/p3d_test/test_3_double_pendulums.launch b/.ros1_unported/gazebo_plugins/test/p3d_test/test_3_double_pendulums.launch similarity index 100% rename from gazebo_plugins/test/p3d_test/test_3_double_pendulums.launch rename to .ros1_unported/gazebo_plugins/test/p3d_test/test_3_double_pendulums.launch diff --git a/gazebo_plugins/test/p3d_test/test_3_single_pendulums.launch b/.ros1_unported/gazebo_plugins/test/p3d_test/test_3_single_pendulums.launch similarity index 100% rename from gazebo_plugins/test/p3d_test/test_3_single_pendulums.launch rename to .ros1_unported/gazebo_plugins/test/p3d_test/test_3_single_pendulums.launch diff --git a/gazebo_plugins/test/p3d_test/test_double_pendulum.launch b/.ros1_unported/gazebo_plugins/test/p3d_test/test_double_pendulum.launch similarity index 100% rename from gazebo_plugins/test/p3d_test/test_double_pendulum.launch rename to .ros1_unported/gazebo_plugins/test/p3d_test/test_double_pendulum.launch diff --git a/gazebo_plugins/test/p3d_test/test_link_pose.py b/.ros1_unported/gazebo_plugins/test/p3d_test/test_link_pose.py similarity index 100% rename from gazebo_plugins/test/p3d_test/test_link_pose.py rename to .ros1_unported/gazebo_plugins/test/p3d_test/test_link_pose.py diff --git a/gazebo_plugins/test/p3d_test/test_single_pendulum.launch b/.ros1_unported/gazebo_plugins/test/p3d_test/test_single_pendulum.launch similarity index 100% rename from gazebo_plugins/test/p3d_test/test_single_pendulum.launch rename to .ros1_unported/gazebo_plugins/test/p3d_test/test_single_pendulum.launch diff --git a/gazebo_plugins/test/p3d_test/worlds/3_double_pendulums.world b/.ros1_unported/gazebo_plugins/test/p3d_test/worlds/3_double_pendulums.world similarity index 100% rename from gazebo_plugins/test/p3d_test/worlds/3_double_pendulums.world rename to .ros1_unported/gazebo_plugins/test/p3d_test/worlds/3_double_pendulums.world diff --git a/gazebo_plugins/test/p3d_test/worlds/3_single_pendulums.world b/.ros1_unported/gazebo_plugins/test/p3d_test/worlds/3_single_pendulums.world similarity index 100% rename from gazebo_plugins/test/p3d_test/worlds/3_single_pendulums.world rename to .ros1_unported/gazebo_plugins/test/p3d_test/worlds/3_single_pendulums.world diff --git a/gazebo_plugins/test/p3d_test/worlds/double_pendulum.world b/.ros1_unported/gazebo_plugins/test/p3d_test/worlds/double_pendulum.world similarity index 100% rename from gazebo_plugins/test/p3d_test/worlds/double_pendulum.world rename to .ros1_unported/gazebo_plugins/test/p3d_test/worlds/double_pendulum.world diff --git a/gazebo_plugins/test/p3d_test/worlds/single_pendulum.world b/.ros1_unported/gazebo_plugins/test/p3d_test/worlds/single_pendulum.world similarity index 100% rename from gazebo_plugins/test/p3d_test/worlds/single_pendulum.world rename to .ros1_unported/gazebo_plugins/test/p3d_test/worlds/single_pendulum.world diff --git a/gazebo_plugins/test/pub_joint_trajectory_test.cpp b/.ros1_unported/gazebo_plugins/test/pub_joint_trajectory_test.cpp similarity index 100% rename from gazebo_plugins/test/pub_joint_trajectory_test.cpp rename to .ros1_unported/gazebo_plugins/test/pub_joint_trajectory_test.cpp diff --git a/gazebo_plugins/test/range/range_plugin.test b/.ros1_unported/gazebo_plugins/test/range/range_plugin.test similarity index 100% rename from gazebo_plugins/test/range/range_plugin.test rename to .ros1_unported/gazebo_plugins/test/range/range_plugin.test diff --git a/gazebo_plugins/test/set_model_state_test/set_model_state_test.cpp b/.ros1_unported/gazebo_plugins/test/set_model_state_test/set_model_state_test.cpp similarity index 100% rename from gazebo_plugins/test/set_model_state_test/set_model_state_test.cpp rename to .ros1_unported/gazebo_plugins/test/set_model_state_test/set_model_state_test.cpp diff --git a/gazebo_plugins/test/set_model_state_test/set_model_state_test.test b/.ros1_unported/gazebo_plugins/test/set_model_state_test/set_model_state_test.test similarity index 100% rename from gazebo_plugins/test/set_model_state_test/set_model_state_test.test rename to .ros1_unported/gazebo_plugins/test/set_model_state_test/set_model_state_test.test diff --git a/gazebo_plugins/test/set_model_state_test/set_model_state_test_p2dx.world b/.ros1_unported/gazebo_plugins/test/set_model_state_test/set_model_state_test_p2dx.world similarity index 100% rename from gazebo_plugins/test/set_model_state_test/set_model_state_test_p2dx.world rename to .ros1_unported/gazebo_plugins/test/set_model_state_test/set_model_state_test_p2dx.world diff --git a/gazebo_plugins/test/spawn_test/parameter_server_test.launch b/.ros1_unported/gazebo_plugins/test/spawn_test/parameter_server_test.launch similarity index 100% rename from gazebo_plugins/test/spawn_test/parameter_server_test.launch rename to .ros1_unported/gazebo_plugins/test/spawn_test/parameter_server_test.launch diff --git a/gazebo_plugins/test/spawn_test/spawn_robots.sh b/.ros1_unported/gazebo_plugins/test/spawn_test/spawn_robots.sh similarity index 100% rename from gazebo_plugins/test/spawn_test/spawn_robots.sh rename to .ros1_unported/gazebo_plugins/test/spawn_test/spawn_robots.sh diff --git a/gazebo_plugins/test/test_worlds/bumper_test.world b/.ros1_unported/gazebo_plugins/test/test_worlds/bumper_test.world similarity index 100% rename from gazebo_plugins/test/test_worlds/bumper_test.world rename to .ros1_unported/gazebo_plugins/test/test_worlds/bumper_test.world diff --git a/gazebo_plugins/test/test_worlds/elevator.world b/.ros1_unported/gazebo_plugins/test/test_worlds/elevator.world similarity index 100% rename from gazebo_plugins/test/test_worlds/elevator.world rename to .ros1_unported/gazebo_plugins/test/test_worlds/elevator.world diff --git a/gazebo_plugins/test/test_worlds/gazebo_ros_block_laser.world b/.ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_block_laser.world similarity index 100% rename from gazebo_plugins/test/test_worlds/gazebo_ros_block_laser.world rename to .ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_block_laser.world diff --git a/gazebo_plugins/test/test_worlds/gazebo_ros_camera.world b/.ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_camera.world similarity index 100% rename from gazebo_plugins/test/test_worlds/gazebo_ros_camera.world rename to .ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_camera.world diff --git a/gazebo_plugins/test/test_worlds/gazebo_ros_depth_camera.world b/.ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_depth_camera.world similarity index 100% rename from gazebo_plugins/test/test_worlds/gazebo_ros_depth_camera.world rename to .ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_depth_camera.world diff --git a/gazebo_plugins/test/test_worlds/gazebo_ros_gpu_laser.world b/.ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_gpu_laser.world similarity index 100% rename from gazebo_plugins/test/test_worlds/gazebo_ros_gpu_laser.world rename to .ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_gpu_laser.world diff --git a/gazebo_plugins/test/test_worlds/gazebo_ros_laser.world b/.ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_laser.world similarity index 100% rename from gazebo_plugins/test/test_worlds/gazebo_ros_laser.world rename to .ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_laser.world diff --git a/gazebo_plugins/test/test_worlds/gazebo_ros_range.world b/.ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_range.world similarity index 100% rename from gazebo_plugins/test/test_worlds/gazebo_ros_range.world rename to .ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_range.world diff --git a/gazebo_plugins/test/test_worlds/gazebo_ros_trimesh_collision.world b/.ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_trimesh_collision.world similarity index 100% rename from gazebo_plugins/test/test_worlds/gazebo_ros_trimesh_collision.world rename to .ros1_unported/gazebo_plugins/test/test_worlds/gazebo_ros_trimesh_collision.world diff --git a/gazebo_plugins/test/test_worlds/test_lasers.world b/.ros1_unported/gazebo_plugins/test/test_worlds/test_lasers.world similarity index 100% rename from gazebo_plugins/test/test_worlds/test_lasers.world rename to .ros1_unported/gazebo_plugins/test/test_worlds/test_lasers.world diff --git a/gazebo_plugins/test/tricycle_drive/launch/.directory b/.ros1_unported/gazebo_plugins/test/tricycle_drive/launch/.directory similarity index 100% rename from gazebo_plugins/test/tricycle_drive/launch/.directory rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/launch/.directory diff --git a/gazebo_plugins/test/tricycle_drive/launch/tricycle.gazebo.launch b/.ros1_unported/gazebo_plugins/test/tricycle_drive/launch/tricycle.gazebo.launch similarity index 100% rename from gazebo_plugins/test/tricycle_drive/launch/tricycle.gazebo.launch rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/launch/tricycle.gazebo.launch diff --git a/gazebo_plugins/test/tricycle_drive/launch/tricycle.rviz b/.ros1_unported/gazebo_plugins/test/tricycle_drive/launch/tricycle.rviz similarity index 100% rename from gazebo_plugins/test/tricycle_drive/launch/tricycle.rviz rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/launch/tricycle.rviz diff --git a/gazebo_plugins/test/tricycle_drive/launch/tricycle.urdf.launch b/.ros1_unported/gazebo_plugins/test/tricycle_drive/launch/tricycle.urdf.launch similarity index 100% rename from gazebo_plugins/test/tricycle_drive/launch/tricycle.urdf.launch rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/launch/tricycle.urdf.launch diff --git a/gazebo_plugins/test/tricycle_drive/launch/tricycle_drive_scenario.launch b/.ros1_unported/gazebo_plugins/test/tricycle_drive/launch/tricycle_drive_scenario.launch similarity index 100% rename from gazebo_plugins/test/tricycle_drive/launch/tricycle_drive_scenario.launch rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/launch/tricycle_drive_scenario.launch diff --git a/gazebo_plugins/test/tricycle_drive/launch/tricycle_rviz.launch b/.ros1_unported/gazebo_plugins/test/tricycle_drive/launch/tricycle_rviz.launch similarity index 100% rename from gazebo_plugins/test/tricycle_drive/launch/tricycle_rviz.launch rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/launch/tricycle_rviz.launch diff --git a/gazebo_plugins/test/tricycle_drive/xacro/.directory b/.ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/.directory similarity index 100% rename from gazebo_plugins/test/tricycle_drive/xacro/.directory rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/.directory diff --git a/gazebo_plugins/test/tricycle_drive/xacro/materials.xacro b/.ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/materials.xacro similarity index 100% rename from gazebo_plugins/test/tricycle_drive/xacro/materials.xacro rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/materials.xacro diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/inertia_tensors.xacro b/.ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/inertia_tensors.xacro similarity index 100% rename from gazebo_plugins/test/tricycle_drive/xacro/tricycle/inertia_tensors.xacro rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/inertia_tensors.xacro diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle.xacro b/.ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle.xacro similarity index 100% rename from gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle.xacro rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle.xacro diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_body.xacro b/.ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_body.xacro similarity index 100% rename from gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_body.xacro rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_body.xacro diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_chassis.xacro b/.ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_chassis.xacro similarity index 100% rename from gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_chassis.xacro rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_chassis.xacro diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_plugins.xacro b/.ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_plugins.xacro similarity index 100% rename from gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_plugins.xacro rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_plugins.xacro diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel.xacro b/.ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel.xacro similarity index 100% rename from gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel.xacro rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel.xacro diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel_actuated.xacro b/.ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel_actuated.xacro similarity index 100% rename from gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel_actuated.xacro rename to .ros1_unported/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel_actuated.xacro diff --git a/gazebo_plugins/test2/CMakeLists_tests_pkg.txt b/.ros1_unported/gazebo_plugins/test2/CMakeLists_tests_pkg.txt similarity index 100% rename from gazebo_plugins/test2/CMakeLists_tests_pkg.txt rename to .ros1_unported/gazebo_plugins/test2/CMakeLists_tests_pkg.txt diff --git a/gazebo_plugins/test2/contact_tolerance/contact_tolerance.cpp b/.ros1_unported/gazebo_plugins/test2/contact_tolerance/contact_tolerance.cpp similarity index 100% rename from gazebo_plugins/test2/contact_tolerance/contact_tolerance.cpp rename to .ros1_unported/gazebo_plugins/test2/contact_tolerance/contact_tolerance.cpp diff --git a/gazebo_plugins/test2/contact_tolerance/contact_tolerance.launch b/.ros1_unported/gazebo_plugins/test2/contact_tolerance/contact_tolerance.launch similarity index 100% rename from gazebo_plugins/test2/contact_tolerance/contact_tolerance.launch rename to .ros1_unported/gazebo_plugins/test2/contact_tolerance/contact_tolerance.launch diff --git a/gazebo_plugins/test2/large_models/large_model.launch b/.ros1_unported/gazebo_plugins/test2/large_models/large_model.launch similarity index 100% rename from gazebo_plugins/test2/large_models/large_model.launch rename to .ros1_unported/gazebo_plugins/test2/large_models/large_model.launch diff --git a/gazebo_plugins/test2/large_models/large_model.urdf.xacro b/.ros1_unported/gazebo_plugins/test2/large_models/large_model.urdf.xacro similarity index 100% rename from gazebo_plugins/test2/large_models/large_model.urdf.xacro rename to .ros1_unported/gazebo_plugins/test2/large_models/large_model.urdf.xacro diff --git a/gazebo_plugins/test2/large_models/large_models.world b/.ros1_unported/gazebo_plugins/test2/large_models/large_models.world similarity index 100% rename from gazebo_plugins/test2/large_models/large_models.world rename to .ros1_unported/gazebo_plugins/test2/large_models/large_models.world diff --git a/gazebo_plugins/test2/large_models/smaller_large_model.launch b/.ros1_unported/gazebo_plugins/test2/large_models/smaller_large_model.launch similarity index 100% rename from gazebo_plugins/test2/large_models/smaller_large_model.launch rename to .ros1_unported/gazebo_plugins/test2/large_models/smaller_large_model.launch diff --git a/gazebo_plugins/test2/large_models/smaller_large_model.urdf.xacro b/.ros1_unported/gazebo_plugins/test2/large_models/smaller_large_model.urdf.xacro similarity index 100% rename from gazebo_plugins/test2/large_models/smaller_large_model.urdf.xacro rename to .ros1_unported/gazebo_plugins/test2/large_models/smaller_large_model.urdf.xacro diff --git a/gazebo_plugins/test2/lcp_tests/balance.launch b/.ros1_unported/gazebo_plugins/test2/lcp_tests/balance.launch similarity index 100% rename from gazebo_plugins/test2/lcp_tests/balance.launch rename to .ros1_unported/gazebo_plugins/test2/lcp_tests/balance.launch diff --git a/gazebo_plugins/test2/lcp_tests/balance.world b/.ros1_unported/gazebo_plugins/test2/lcp_tests/balance.world similarity index 100% rename from gazebo_plugins/test2/lcp_tests/balance.world rename to .ros1_unported/gazebo_plugins/test2/lcp_tests/balance.world diff --git a/gazebo_plugins/test2/lcp_tests/stack.launch b/.ros1_unported/gazebo_plugins/test2/lcp_tests/stack.launch similarity index 100% rename from gazebo_plugins/test2/lcp_tests/stack.launch rename to .ros1_unported/gazebo_plugins/test2/lcp_tests/stack.launch diff --git a/gazebo_plugins/test2/lcp_tests/stack.world b/.ros1_unported/gazebo_plugins/test2/lcp_tests/stack.world similarity index 100% rename from gazebo_plugins/test2/lcp_tests/stack.world rename to .ros1_unported/gazebo_plugins/test2/lcp_tests/stack.world diff --git a/gazebo_plugins/test2/lcp_tests/stacks.launch b/.ros1_unported/gazebo_plugins/test2/lcp_tests/stacks.launch similarity index 100% rename from gazebo_plugins/test2/lcp_tests/stacks.launch rename to .ros1_unported/gazebo_plugins/test2/lcp_tests/stacks.launch diff --git a/gazebo_plugins/test2/lcp_tests/stacks.world b/.ros1_unported/gazebo_plugins/test2/lcp_tests/stacks.world similarity index 100% rename from gazebo_plugins/test2/lcp_tests/stacks.world rename to .ros1_unported/gazebo_plugins/test2/lcp_tests/stacks.world diff --git a/gazebo_plugins/test2/meshes/cube.wings b/.ros1_unported/gazebo_plugins/test2/meshes/cube.wings similarity index 100% rename from gazebo_plugins/test2/meshes/cube.wings rename to .ros1_unported/gazebo_plugins/test2/meshes/cube.wings diff --git a/gazebo_plugins/test2/meshes/cube_20k.stl b/.ros1_unported/gazebo_plugins/test2/meshes/cube_20k.stl similarity index 100% rename from gazebo_plugins/test2/meshes/cube_20k.stl rename to .ros1_unported/gazebo_plugins/test2/meshes/cube_20k.stl diff --git a/gazebo_plugins/test2/meshes/cube_30k.stl b/.ros1_unported/gazebo_plugins/test2/meshes/cube_30k.stl similarity index 100% rename from gazebo_plugins/test2/meshes/cube_30k.stl rename to .ros1_unported/gazebo_plugins/test2/meshes/cube_30k.stl diff --git a/gazebo_plugins/test2/spawn_model/check_model.cpp b/.ros1_unported/gazebo_plugins/test2/spawn_model/check_model.cpp similarity index 100% rename from gazebo_plugins/test2/spawn_model/check_model.cpp rename to .ros1_unported/gazebo_plugins/test2/spawn_model/check_model.cpp diff --git a/gazebo_plugins/test2/spawn_model/spawn_box.cpp b/.ros1_unported/gazebo_plugins/test2/spawn_model/spawn_box.cpp similarity index 100% rename from gazebo_plugins/test2/spawn_model/spawn_box.cpp rename to .ros1_unported/gazebo_plugins/test2/spawn_model/spawn_box.cpp diff --git a/gazebo_plugins/test2/spawn_model/spawn_box.launch b/.ros1_unported/gazebo_plugins/test2/spawn_model/spawn_box.launch similarity index 100% rename from gazebo_plugins/test2/spawn_model/spawn_box.launch rename to .ros1_unported/gazebo_plugins/test2/spawn_model/spawn_box.launch diff --git a/gazebo_plugins/test2/spawn_model/spawn_box_file.launch b/.ros1_unported/gazebo_plugins/test2/spawn_model/spawn_box_file.launch similarity index 100% rename from gazebo_plugins/test2/spawn_model/spawn_box_file.launch rename to .ros1_unported/gazebo_plugins/test2/spawn_model/spawn_box_file.launch diff --git a/gazebo_plugins/test2/spawn_model/spawn_box_param.launch b/.ros1_unported/gazebo_plugins/test2/spawn_model/spawn_box_param.launch similarity index 100% rename from gazebo_plugins/test2/spawn_model/spawn_box_param.launch rename to .ros1_unported/gazebo_plugins/test2/spawn_model/spawn_box_param.launch diff --git a/gazebo_plugins/test2/trimesh_tests/test_trimesh.launch b/.ros1_unported/gazebo_plugins/test2/trimesh_tests/test_trimesh.launch similarity index 100% rename from gazebo_plugins/test2/trimesh_tests/test_trimesh.launch rename to .ros1_unported/gazebo_plugins/test2/trimesh_tests/test_trimesh.launch diff --git a/gazebo_plugins/test2/urdf/box.urdf b/.ros1_unported/gazebo_plugins/test2/urdf/box.urdf similarity index 100% rename from gazebo_plugins/test2/urdf/box.urdf rename to .ros1_unported/gazebo_plugins/test2/urdf/box.urdf diff --git a/gazebo_plugins/test2/urdf/cube.urdf b/.ros1_unported/gazebo_plugins/test2/urdf/cube.urdf similarity index 100% rename from gazebo_plugins/test2/urdf/cube.urdf rename to .ros1_unported/gazebo_plugins/test2/urdf/cube.urdf diff --git a/gazebo_plugins/test2/worlds/empty.world b/.ros1_unported/gazebo_plugins/test2/worlds/empty.world similarity index 100% rename from gazebo_plugins/test2/worlds/empty.world rename to .ros1_unported/gazebo_plugins/test2/worlds/empty.world diff --git a/gazebo_ros/.idea/gazebo_ros.iml b/.ros1_unported/gazebo_ros/.idea/gazebo_ros.iml similarity index 100% rename from gazebo_ros/.idea/gazebo_ros.iml rename to .ros1_unported/gazebo_ros/.idea/gazebo_ros.iml diff --git a/gazebo_ros/CHANGELOG.rst b/.ros1_unported/gazebo_ros/CHANGELOG.rst similarity index 100% rename from gazebo_ros/CHANGELOG.rst rename to .ros1_unported/gazebo_ros/CHANGELOG.rst diff --git a/gazebo_ros/CMakeLists.txt b/.ros1_unported/gazebo_ros/CMakeLists.txt similarity index 100% rename from gazebo_ros/CMakeLists.txt rename to .ros1_unported/gazebo_ros/CMakeLists.txt diff --git a/gazebo_ros/cfg/Physics.cfg b/.ros1_unported/gazebo_ros/cfg/Physics.cfg similarity index 100% rename from gazebo_ros/cfg/Physics.cfg rename to .ros1_unported/gazebo_ros/cfg/Physics.cfg diff --git a/gazebo_ros/include/gazebo_ros/gazebo_ros_api_plugin.h b/.ros1_unported/gazebo_ros/include/gazebo_ros/gazebo_ros_api_plugin.h similarity index 100% rename from gazebo_ros/include/gazebo_ros/gazebo_ros_api_plugin.h rename to .ros1_unported/gazebo_ros/include/gazebo_ros/gazebo_ros_api_plugin.h diff --git a/gazebo_ros/launch/elevator_world.launch b/.ros1_unported/gazebo_ros/launch/elevator_world.launch similarity index 100% rename from gazebo_ros/launch/elevator_world.launch rename to .ros1_unported/gazebo_ros/launch/elevator_world.launch diff --git a/gazebo_ros/launch/empty_world.launch b/.ros1_unported/gazebo_ros/launch/empty_world.launch similarity index 100% rename from gazebo_ros/launch/empty_world.launch rename to .ros1_unported/gazebo_ros/launch/empty_world.launch diff --git a/gazebo_ros/launch/mud_world.launch b/.ros1_unported/gazebo_ros/launch/mud_world.launch similarity index 100% rename from gazebo_ros/launch/mud_world.launch rename to .ros1_unported/gazebo_ros/launch/mud_world.launch diff --git a/gazebo_ros/launch/range_world.launch b/.ros1_unported/gazebo_ros/launch/range_world.launch similarity index 100% rename from gazebo_ros/launch/range_world.launch rename to .ros1_unported/gazebo_ros/launch/range_world.launch diff --git a/gazebo_ros/launch/rubble_world.launch b/.ros1_unported/gazebo_ros/launch/rubble_world.launch similarity index 100% rename from gazebo_ros/launch/rubble_world.launch rename to .ros1_unported/gazebo_ros/launch/rubble_world.launch diff --git a/gazebo_ros/launch/shapes_world.launch b/.ros1_unported/gazebo_ros/launch/shapes_world.launch similarity index 100% rename from gazebo_ros/launch/shapes_world.launch rename to .ros1_unported/gazebo_ros/launch/shapes_world.launch diff --git a/gazebo_ros/launch/willowgarage_world.launch b/.ros1_unported/gazebo_ros/launch/willowgarage_world.launch similarity index 100% rename from gazebo_ros/launch/willowgarage_world.launch rename to .ros1_unported/gazebo_ros/launch/willowgarage_world.launch diff --git a/gazebo_ros/package.xml b/.ros1_unported/gazebo_ros/package.xml similarity index 100% rename from gazebo_ros/package.xml rename to .ros1_unported/gazebo_ros/package.xml diff --git a/gazebo_ros/scripts/debug b/.ros1_unported/gazebo_ros/scripts/debug similarity index 100% rename from gazebo_ros/scripts/debug rename to .ros1_unported/gazebo_ros/scripts/debug diff --git a/gazebo_ros/scripts/gazebo b/.ros1_unported/gazebo_ros/scripts/gazebo similarity index 100% rename from gazebo_ros/scripts/gazebo rename to .ros1_unported/gazebo_ros/scripts/gazebo diff --git a/gazebo_ros/scripts/gdbrun b/.ros1_unported/gazebo_ros/scripts/gdbrun similarity index 100% rename from gazebo_ros/scripts/gdbrun rename to .ros1_unported/gazebo_ros/scripts/gdbrun diff --git a/gazebo_ros/scripts/gzclient b/.ros1_unported/gazebo_ros/scripts/gzclient similarity index 100% rename from gazebo_ros/scripts/gzclient rename to .ros1_unported/gazebo_ros/scripts/gzclient diff --git a/gazebo_ros/scripts/gzserver b/.ros1_unported/gazebo_ros/scripts/gzserver similarity index 100% rename from gazebo_ros/scripts/gzserver rename to .ros1_unported/gazebo_ros/scripts/gzserver diff --git a/gazebo_ros/scripts/libcommon.sh b/.ros1_unported/gazebo_ros/scripts/libcommon.sh similarity index 100% rename from gazebo_ros/scripts/libcommon.sh rename to .ros1_unported/gazebo_ros/scripts/libcommon.sh diff --git a/gazebo_ros/scripts/perf b/.ros1_unported/gazebo_ros/scripts/perf similarity index 100% rename from gazebo_ros/scripts/perf rename to .ros1_unported/gazebo_ros/scripts/perf diff --git a/gazebo_ros/scripts/spawn_model b/.ros1_unported/gazebo_ros/scripts/spawn_model similarity index 100% rename from gazebo_ros/scripts/spawn_model rename to .ros1_unported/gazebo_ros/scripts/spawn_model diff --git a/gazebo_ros/setup.py b/.ros1_unported/gazebo_ros/setup.py similarity index 100% rename from gazebo_ros/setup.py rename to .ros1_unported/gazebo_ros/setup.py diff --git a/.ros1_unported/gazebo_ros/src/gazebo_ros/__init__.py b/.ros1_unported/gazebo_ros/src/gazebo_ros/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/gazebo_ros/src/gazebo_ros/gazebo_interface.py b/.ros1_unported/gazebo_ros/src/gazebo_ros/gazebo_interface.py similarity index 100% rename from gazebo_ros/src/gazebo_ros/gazebo_interface.py rename to .ros1_unported/gazebo_ros/src/gazebo_ros/gazebo_interface.py diff --git a/gazebo_ros/src/gazebo_ros_api_plugin.cpp b/.ros1_unported/gazebo_ros/src/gazebo_ros_api_plugin.cpp similarity index 100% rename from gazebo_ros/src/gazebo_ros_api_plugin.cpp rename to .ros1_unported/gazebo_ros/src/gazebo_ros_api_plugin.cpp diff --git a/gazebo_ros/src/gazebo_ros_paths_plugin.cpp b/.ros1_unported/gazebo_ros/src/gazebo_ros_paths_plugin.cpp similarity index 100% rename from gazebo_ros/src/gazebo_ros_paths_plugin.cpp rename to .ros1_unported/gazebo_ros/src/gazebo_ros_paths_plugin.cpp diff --git a/gazebo_ros/test/CMakeLists.txt b/.ros1_unported/gazebo_ros/test/CMakeLists.txt similarity index 100% rename from gazebo_ros/test/CMakeLists.txt rename to .ros1_unported/gazebo_ros/test/CMakeLists.txt diff --git a/gazebo_ros/test/ros_network/gazebo_network_api.yaml b/.ros1_unported/gazebo_ros/test/ros_network/gazebo_network_api.yaml similarity index 100% rename from gazebo_ros/test/ros_network/gazebo_network_api.yaml rename to .ros1_unported/gazebo_ros/test/ros_network/gazebo_network_api.yaml diff --git a/gazebo_ros/test/ros_network/no_gazebo_network_api.yaml b/.ros1_unported/gazebo_ros/test/ros_network/no_gazebo_network_api.yaml similarity index 100% rename from gazebo_ros/test/ros_network/no_gazebo_network_api.yaml rename to .ros1_unported/gazebo_ros/test/ros_network/no_gazebo_network_api.yaml diff --git a/gazebo_ros/test/ros_network/ros_api_checker b/.ros1_unported/gazebo_ros/test/ros_network/ros_api_checker similarity index 100% rename from gazebo_ros/test/ros_network/ros_api_checker rename to .ros1_unported/gazebo_ros/test/ros_network/ros_api_checker diff --git a/gazebo_ros/test/ros_network/ros_network_default.test b/.ros1_unported/gazebo_ros/test/ros_network/ros_network_default.test similarity index 100% rename from gazebo_ros/test/ros_network/ros_network_default.test rename to .ros1_unported/gazebo_ros/test/ros_network/ros_network_default.test diff --git a/gazebo_ros/test/ros_network/ros_network_disabled.test b/.ros1_unported/gazebo_ros/test/ros_network/ros_network_disabled.test similarity index 100% rename from gazebo_ros/test/ros_network/ros_network_disabled.test rename to .ros1_unported/gazebo_ros/test/ros_network/ros_network_disabled.test diff --git a/gazebo_ros_control/CHANGELOG.rst b/.ros1_unported/gazebo_ros_control/CHANGELOG.rst similarity index 100% rename from gazebo_ros_control/CHANGELOG.rst rename to .ros1_unported/gazebo_ros_control/CHANGELOG.rst diff --git a/gazebo_ros_control/CMakeLists.txt b/.ros1_unported/gazebo_ros_control/CMakeLists.txt similarity index 100% rename from gazebo_ros_control/CMakeLists.txt rename to .ros1_unported/gazebo_ros_control/CMakeLists.txt diff --git a/gazebo_ros_control/README.md b/.ros1_unported/gazebo_ros_control/README.md similarity index 100% rename from gazebo_ros_control/README.md rename to .ros1_unported/gazebo_ros_control/README.md diff --git a/gazebo_ros_control/include/gazebo_ros_control/default_robot_hw_sim.h b/.ros1_unported/gazebo_ros_control/include/gazebo_ros_control/default_robot_hw_sim.h similarity index 100% rename from gazebo_ros_control/include/gazebo_ros_control/default_robot_hw_sim.h rename to .ros1_unported/gazebo_ros_control/include/gazebo_ros_control/default_robot_hw_sim.h diff --git a/gazebo_ros_control/include/gazebo_ros_control/gazebo_ros_control_plugin.h b/.ros1_unported/gazebo_ros_control/include/gazebo_ros_control/gazebo_ros_control_plugin.h similarity index 100% rename from gazebo_ros_control/include/gazebo_ros_control/gazebo_ros_control_plugin.h rename to .ros1_unported/gazebo_ros_control/include/gazebo_ros_control/gazebo_ros_control_plugin.h diff --git a/gazebo_ros_control/include/gazebo_ros_control/robot_hw_sim.h b/.ros1_unported/gazebo_ros_control/include/gazebo_ros_control/robot_hw_sim.h similarity index 100% rename from gazebo_ros_control/include/gazebo_ros_control/robot_hw_sim.h rename to .ros1_unported/gazebo_ros_control/include/gazebo_ros_control/robot_hw_sim.h diff --git a/gazebo_ros_control/package.xml b/.ros1_unported/gazebo_ros_control/package.xml similarity index 100% rename from gazebo_ros_control/package.xml rename to .ros1_unported/gazebo_ros_control/package.xml diff --git a/gazebo_ros_control/robot_hw_sim_plugins.xml b/.ros1_unported/gazebo_ros_control/robot_hw_sim_plugins.xml similarity index 100% rename from gazebo_ros_control/robot_hw_sim_plugins.xml rename to .ros1_unported/gazebo_ros_control/robot_hw_sim_plugins.xml diff --git a/gazebo_ros_control/src/default_robot_hw_sim.cpp b/.ros1_unported/gazebo_ros_control/src/default_robot_hw_sim.cpp similarity index 100% rename from gazebo_ros_control/src/default_robot_hw_sim.cpp rename to .ros1_unported/gazebo_ros_control/src/default_robot_hw_sim.cpp diff --git a/gazebo_ros_control/src/gazebo_ros_control_plugin.cpp b/.ros1_unported/gazebo_ros_control/src/gazebo_ros_control_plugin.cpp similarity index 100% rename from gazebo_ros_control/src/gazebo_ros_control_plugin.cpp rename to .ros1_unported/gazebo_ros_control/src/gazebo_ros_control_plugin.cpp diff --git a/gazebo_ros_pkgs/CHANGELOG.rst b/.ros1_unported/gazebo_ros_pkgs/CHANGELOG.rst similarity index 100% rename from gazebo_ros_pkgs/CHANGELOG.rst rename to .ros1_unported/gazebo_ros_pkgs/CHANGELOG.rst diff --git a/gazebo_ros_pkgs/CMakeLists.txt b/.ros1_unported/gazebo_ros_pkgs/CMakeLists.txt similarity index 100% rename from gazebo_ros_pkgs/CMakeLists.txt rename to .ros1_unported/gazebo_ros_pkgs/CMakeLists.txt diff --git a/gazebo_ros_pkgs/documentation/gazebo_ros_api.odg b/.ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_api.odg similarity index 100% rename from gazebo_ros_pkgs/documentation/gazebo_ros_api.odg rename to .ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_api.odg diff --git a/gazebo_ros_pkgs/documentation/gazebo_ros_api.pdf b/.ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_api.pdf similarity index 100% rename from gazebo_ros_pkgs/documentation/gazebo_ros_api.pdf rename to .ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_api.pdf diff --git a/gazebo_ros_pkgs/documentation/gazebo_ros_api.png b/.ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_api.png similarity index 100% rename from gazebo_ros_pkgs/documentation/gazebo_ros_api.png rename to .ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_api.png diff --git a/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.odg b/.ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.odg similarity index 100% rename from gazebo_ros_pkgs/documentation/gazebo_ros_transmission.odg rename to .ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.odg diff --git a/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.pdf b/.ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.pdf similarity index 100% rename from gazebo_ros_pkgs/documentation/gazebo_ros_transmission.pdf rename to .ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.pdf diff --git a/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.png b/.ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.png similarity index 100% rename from gazebo_ros_pkgs/documentation/gazebo_ros_transmission.png rename to .ros1_unported/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.png diff --git a/gazebo_ros_pkgs/package.xml b/.ros1_unported/gazebo_ros_pkgs/package.xml similarity index 100% rename from gazebo_ros_pkgs/package.xml rename to .ros1_unported/gazebo_ros_pkgs/package.xml From aa446d07233166366453f84ef3d154146484ba49 Mon Sep 17 00:00:00 2001 From: Kevin Allen Date: Tue, 17 Jul 2018 15:12:10 -0700 Subject: [PATCH 3/3] Switch rosidl_default_generators to buildtool_depend --- gazebo_msgs/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gazebo_msgs/package.xml b/gazebo_msgs/package.xml index 95c59d78e..51557194c 100644 --- a/gazebo_msgs/package.xml +++ b/gazebo_msgs/package.xml @@ -12,8 +12,8 @@ BSD ament_cmake + rosidl_default_generators - rosidl_default_generators builtin_interfaces geometry_msgs trajectory_msgs