From 1ac6afee35b4d585a0862964d74c249deaf8a400 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Mon, 25 Jul 2022 16:08:09 -0700 Subject: [PATCH] Implement shims Signed-off-by: methylDragon --- ros_gz_shims/README.md | 13 + ros_gz_shims/ros_ign/CMakeLists.txt | 10 + ros_gz_shims/ros_ign/README.md | 2 + ros_gz_shims/ros_ign/package.xml | 28 ++ ros_gz_shims/ros_ign_bridge/CMakeLists.txt | 29 ++ ros_gz_shims/ros_ign_bridge/README.md | 2 + ros_gz_shims/ros_ign_bridge/package.xml | 19 ++ .../src/parameter_bridge_shim.cpp | 30 ++ .../ros_ign_bridge/src/static_bridge_shim.cpp | 30 ++ ros_gz_shims/ros_ign_gazebo/CMakeLists.txt | 45 +++ .../launch/ign_gazebo.launch.py.in | 63 +++++ ros_gz_shims/ros_ign_gazebo/package.xml | 19 ++ .../ros_ign_gazebo/src/create_shim.cpp | 30 ++ .../ros_ign_gazebo_demos/CMakeLists.txt | 29 ++ ros_gz_shims/ros_ign_gazebo_demos/README.md | 2 + .../launch/air_pressure.launch.py | 63 +++++ .../launch/battery.launch.py | 69 +++++ .../launch/camera.launch.py | 63 +++++ .../launch/depth_camera.launch.py | 77 +++++ .../launch/diff_drive.launch.py | 69 +++++ .../launch/gpu_lidar.launch.py | 65 +++++ .../launch/gpu_lidar_bridge.launch.py | 65 +++++ .../launch/image_bridge.launch.py | 65 +++++ .../ros_ign_gazebo_demos/launch/imu.launch.py | 78 +++++ .../launch/joint_states.launch.py | 98 +++++++ .../launch/magnetometer.launch.py | 63 +++++ .../launch/rgbd_camera.launch.py | 63 +++++ .../launch/rgbd_camera_bridge.launch.py | 70 +++++ .../robot_description_publisher.launch.py | 93 ++++++ .../launch/tf_bridge.launch.py | 59 ++++ .../launch/triggered_camera.launch.py | 64 +++++ .../models/double_pendulum_model.sdf | 266 ++++++++++++++++++ .../ros_ign_gazebo_demos/models/rrbot.xacro | 165 +++++++++++ ros_gz_shims/ros_ign_gazebo_demos/package.xml | 17 ++ .../ros_ign_gazebo_demos/rviz/camera.rviz | 137 +++++++++ .../rviz/depth_camera.rviz | 147 ++++++++++ .../ros_ign_gazebo_demos/rviz/diff_drive.rviz | 123 ++++++++ .../ros_ign_gazebo_demos/rviz/gpu_lidar.rviz | 181 ++++++++++++ .../rviz/gpu_lidar_bridge.rviz | 167 +++++++++++ .../ros_ign_gazebo_demos/rviz/imu.rviz | 130 +++++++++ .../rviz/joint_states.rviz | 190 +++++++++++++ .../rviz/rgbd_camera.rviz | 159 +++++++++++ .../rviz/rgbd_camera_bridge.rviz | 142 ++++++++++ .../rviz/robot_description_publisher.rviz | 148 ++++++++++ .../ros_ign_gazebo_demos/rviz/tf_bridge.rviz | 163 +++++++++++ ros_gz_shims/ros_ign_image/CMakeLists.txt | 26 ++ ros_gz_shims/ros_ign_image/README.md | 2 + ros_gz_shims/ros_ign_image/package.xml | 19 ++ .../ros_ign_image/src/image_bridge_shim.cpp | 30 ++ .../ros_ign_interfaces/CMakeLists.txt | 49 ++++ ros_gz_shims/ros_ign_interfaces/README.md | 2 + .../ros_ign_interfaces/msg/Contact.msg | 6 + .../ros_ign_interfaces/msg/Contacts.msg | 2 + .../ros_ign_interfaces/msg/Entity.msg | 13 + .../ros_ign_interfaces/msg/EntityFactory.msg | 11 + .../ros_ign_interfaces/msg/GuiCamera.msg | 12 + .../ros_ign_interfaces/msg/JointWrench.msg | 8 + ros_gz_shims/ros_ign_interfaces/msg/Light.msg | 29 ++ .../ros_ign_interfaces/msg/StringVec.msg | 7 + .../ros_ign_interfaces/msg/TrackVisual.msg | 33 +++ .../ros_ign_interfaces/msg/VideoRecord.msg | 16 ++ .../ros_ign_interfaces/msg/WorldControl.msg | 7 + .../ros_ign_interfaces/msg/WorldReset.msg | 3 + ros_gz_shims/ros_ign_interfaces/package.xml | 27 ++ .../ros_ign_interfaces/srv/ControlWorld.srv | 3 + .../ros_ign_interfaces/srv/DeleteEntity.srv | 3 + .../ros_ign_interfaces/srv/SetEntityPose.srv | 4 + .../ros_ign_interfaces/srv/SpawnEntity.srv | 3 + 68 files changed, 3925 insertions(+) create mode 100644 ros_gz_shims/README.md create mode 100644 ros_gz_shims/ros_ign/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign/README.md create mode 100644 ros_gz_shims/ros_ign/package.xml create mode 100644 ros_gz_shims/ros_ign_bridge/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_bridge/README.md create mode 100644 ros_gz_shims/ros_ign_bridge/package.xml create mode 100644 ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp create mode 100644 ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp create mode 100644 ros_gz_shims/ros_ign_gazebo/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in create mode 100644 ros_gz_shims/ros_ign_gazebo/package.xml create mode 100644 ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/README.md create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py create mode 100755 ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/package.xml create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz create mode 100644 ros_gz_shims/ros_ign_image/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_image/README.md create mode 100644 ros_gz_shims/ros_ign_image/package.xml create mode 100644 ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp create mode 100644 ros_gz_shims/ros_ign_interfaces/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_interfaces/README.md create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Contact.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Entity.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Light.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/package.xml create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv diff --git a/ros_gz_shims/README.md b/ros_gz_shims/README.md new file mode 100644 index 00000000..b653a6fc --- /dev/null +++ b/ros_gz_shims/README.md @@ -0,0 +1,13 @@ +# Description + +These are shim packages for `ros_gz` that redirect executable calls to the related `ros_gz` executable. +These require `ros_gz` to be installed though, but are set up to depend on `ros_gz`. + +This allows users to do either of these and get equivalent behavior: + +```bash +ros2 run ros_gz parameter_bridge [...] +ros2 run ros_ign parameter_bridge [...] # Will emit deprecation warning +``` + +Additionally, installed files like launchfiles, message interfaces etc. are **duplicated** versions of the ones in `ros_gz` (but renamed as appropriate), and point to `ros_gz` dependencies as well (e.g. launchfiles pointing to `ros_gz` nodes.) diff --git a/ros_gz_shims/ros_ign/CMakeLists.txt b/ros_gz_shims/ros_ign/CMakeLists.txt new file mode 100644 index 00000000..80524e92 --- /dev/null +++ b/ros_gz_shims/ros_ign/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign) +find_package(ament_cmake REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/ros_gz_shims/ros_ign/README.md b/ros_gz_shims/ros_ign/README.md new file mode 100644 index 00000000..d6f36599 --- /dev/null +++ b/ros_gz_shims/ros_ign/README.md @@ -0,0 +1,2 @@ +# This is a shim meta-package +For [ros_gz](https://github.com/gazebosim/ros_gz) diff --git a/ros_gz_shims/ros_ign/package.xml b/ros_gz_shims/ros_ign/package.xml new file mode 100644 index 00000000..03e41bcb --- /dev/null +++ b/ros_gz_shims/ros_ign/package.xml @@ -0,0 +1,28 @@ + + + + + ros_ign + 0.0.1 + Shim meta-package to redirect to ros_gz. + Brandon Ong + Apache 2.0 + + ament_cmake + ros_gz + + ros_ign_bridge + ros_ign_gazebo + ros_ign_gazebo_demos + ros_ign_image + + + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_bridge/CMakeLists.txt b/ros_gz_shims/ros_ign_bridge/CMakeLists.txt new file mode 100644 index 00000000..7be505b0 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_bridge) + +# 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") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_index_cpp REQUIRED) + +add_executable(parameter_bridge src/parameter_bridge_shim.cpp) +ament_target_dependencies(parameter_bridge ament_index_cpp) + +add_executable(static_bridge src/static_bridge_shim.cpp) +ament_target_dependencies(static_bridge ament_index_cpp) + +ament_export_dependencies(ament_index_cpp ros_gz_bridge) + +install(TARGETS + parameter_bridge + static_bridge + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_bridge/README.md b/ros_gz_shims/ros_ign_bridge/README.md new file mode 100644 index 00000000..e93d8f26 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_bridge](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge) diff --git a/ros_gz_shims/ros_ign_bridge/package.xml b/ros_gz_shims/ros_ign_bridge/package.xml new file mode 100644 index 00000000..c85b8c97 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/package.xml @@ -0,0 +1,19 @@ + + + + ros_ign_bridge + 0.0.1 + Shim package to redirect to ros_gz_bridge. + Brandon Ong + + Apache 2.0 + + ament_cmake + ament_index_cpp + + ros_gz_bridge + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp b/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp new file mode 100644 index 00000000..b6b613e5 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_bridge parameter_bridge" call to "ros_gz_bridge parameter_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_bridge") + << "/lib/ros_gz_bridge/parameter_bridge"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_bridge] is deprecated! " + << "Redirecting to use [ros_gz_bridge] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp b/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp new file mode 100644 index 00000000..56c577b8 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_bridge static_bridge" call to "ros_gz_bridge static_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_bridge") + << "/lib/ros_gz_bridge/static_bridge"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_bridge] is deprecated! " + << "Redirecting to use [ros_gz_bridge] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt b/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt new file mode 100644 index 00000000..86974a76 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt @@ -0,0 +1,45 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_gazebo) + +# 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") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_index_cpp REQUIRED) + +add_executable(create + src/create_shim.cpp +) +ament_target_dependencies(create ament_index_cpp) + +ament_export_dependencies( + ament_index_cpp + ros_gz_bridge +) + +configure_file( + launch/ign_gazebo.launch.py.in + launch/ign_gazebo.launch.py.configured + @ONLY +) +file(GENERATE + OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py" + INPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py.configured" +) + +install(FILES + "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py" + DESTINATION share/${PROJECT_NAME}/launch +) + +install(TARGETS + create + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in b/ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in new file mode 100644 index 00000000..e8ff4909 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in @@ -0,0 +1,63 @@ +# Copyright 2020 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Launch Gazebo Sim with command line arguments.""" + +from os import environ + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import ExecuteProcess +from launch.substitutions import LaunchConfiguration + + +def generate_launch_description(): + env = {'GZ_SIM_SYSTEM_PLUGIN_PATH': + ':'.join([environ.get('GZ_SIM_SYSTEM_PLUGIN_PATH', default=''), + environ.get('LD_LIBRARY_PATH', default='')]), + 'IGN_GAZEBO_SYSTEM_PLUGIN_PATH': # TODO(CH3): To support pre-garden. Deprecated. + ':'.join([environ.get('IGN_GAZEBO_SYSTEM_PLUGIN_PATH', default=''), + environ.get('LD_LIBRARY_PATH', default='')])} + + return LaunchDescription([ + DeclareLaunchArgument('gz_args', default_value='', + description='Arguments to be passed to Gazebo Sim'), + # Gazebo Sim's major version + DeclareLaunchArgument('gz_version', default_value='@GZ_SIM_VER@', + description='Gazebo Sim\'s major version'), + + # TODO(CH3): Deprecated. Remove on tock. + DeclareLaunchArgument( + 'ign_args', default_value='', + description='Deprecated: Arguments to be passed to Gazebo Sim' + ), + # Gazebo Sim's major version + DeclareLaunchArgument( + 'ign_version', default_value='@GZ_SIM_VER@', + description='Deprecated: Gazebo Sim\'s major version' + ), + + ExecuteProcess( + cmd=['gz sim', + LaunchConfiguration('gz_args'), + LaunchConfiguration('ign_args'), + '--force-version', + LaunchConfiguration('gz_version'), + LaunchConfiguration('ign_version'), + ], + output='screen', + additional_env=env, + shell=True + ) + ]) diff --git a/ros_gz_shims/ros_ign_gazebo/package.xml b/ros_gz_shims/ros_ign_gazebo/package.xml new file mode 100644 index 00000000..c0683a53 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/package.xml @@ -0,0 +1,19 @@ + + + + ros_ign_gazebo + 0.0.1 + Shim package to redirect to ros_gz_sim. + Brandon Ong + + Apache 2.0 + + ament_cmake + ament_index_cpp + + ros_gz_sim + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp b/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp new file mode 100644 index 00000000..dbaa029e --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_bridge parameter_bridge" call to "ros_gz_sim parameter_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_sim") + << "/lib/ros_gz_sim/create"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_gazebo] is deprecated! " + << "Redirecting to use [ros_gz_sim] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt b/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt new file mode 100644 index 00000000..0a7ae4fe --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_gazebo_demos) + +find_package(ament_cmake REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +install( + DIRECTORY + launch/ + DESTINATION share/${PROJECT_NAME}/launch +) + +install( + DIRECTORY + rviz/ + DESTINATION share/${PROJECT_NAME}/rviz +) + +install( + DIRECTORY + models/ + DESTINATION share/${PROJECT_NAME}/models +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_gazebo_demos/README.md b/ros_gz_shims/ros_ign_gazebo_demos/README.md new file mode 100644 index 00000000..b2ce4368 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_sim_demos](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_gazebo_demos) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py new file mode 100644 index 00000000..272d6eb1 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Launch Gazebo Sim with command line arguments.""" + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/air_pressure@sensor_msgs/msg/FluidPressure@ignition.msgs.FluidPressure'], + parameters=[{'qos_overrides./air_pressure.publisher.reliability': 'best_effort'}], + output='screen' + ) + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r sensors.sdf'}.items(), + ) + + # RQt + rqt = Node( + package='rqt_topic', + executable='rqt_topic', + arguments=['-t'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py new file mode 100644 index 00000000..4e32322a --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py @@ -0,0 +1,69 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + # RQt + rqt = Node( + package='rqt_plot', + executable='rqt_plot', + # FIXME: Why isn't the topic being populated on the UI? RQt issue? + arguments=['--force-discover', + '/model/vehicle_blue/battery/linear_battery/state/percentage'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r -z 1000000 linear_battery_demo.sdf' + }.items(), + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + '/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', + '/model/vehicle_blue/battery/linear_battery/state@sensor_msgs/msg/BatteryState@' + 'ignition.msgs.BatteryState' + ], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py new file mode 100644 index 00000000..1bd9a8a0 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r camera_sensor.sdf'}.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'camera.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/camera@sensor_msgs/msg/Image@ignition.msgs.Image', + '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo'], + output='screen' + ) + + return LaunchDescription([ + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + gz_sim, + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py new file mode 100644 index 00000000..d42ce862 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py @@ -0,0 +1,77 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') + ), + # launch_arguments={ + # 'gz_args': '-r depth_camera.sdf' + # }.items(), + ) + + # RQt + rqt = Node( + package='rqt_image_view', + executable='rqt_image_view', + arguments=['/camera'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + # FIXME: Generate new RViz config once this demo is usable again + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'depth_camera.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/depth_camera@sensor_msgs/msg/Image@ignition.msgs.Image'], + output='screen' + ) + + # FIXME: need a SDF file (depth_camera.sdf) inside ros_gz_point_cloud + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rviz, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py new file mode 100644 index 00000000..8a297567 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py @@ -0,0 +1,69 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r diff_drive.sdf' + }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'diff_drive.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', + '/model/vehicle_blue/odometry@nav_msgs/msg/Odometry@ignition.msgs.Odometry', + '/model/vehicle_green/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', + '/model/vehicle_green/odometry@nav_msgs/msg/Odometry@ignition.msgs.Odometry'], + parameters=[{'qos_overrides./model/vehicle_blue.subscriber.reliability': 'reliable', + 'qos_overrides./model/vehicle_green.subscriber.reliability': 'reliable'}], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py new file mode 100644 index 00000000..5cfdb08f --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py @@ -0,0 +1,65 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + # launch_arguments={ + # 'gz_args': '-r gpu_lidar.sdf' + # }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + # FIXME: Generate new RViz config once this demo is usable again + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan/'], + output='screen' + ) + + # FIXME: need a SDF file (gpu_lidar.sdf) inside ros_gz_point_cloud/ + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py new file mode 100644 index 00000000..26bd36b8 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py @@ -0,0 +1,65 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r gpu_lidar_sensor.sdf' + }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar_bridge.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan', + '/lidar/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz, + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py new file mode 100644 index 00000000..91e81e33 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py @@ -0,0 +1,65 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors_demo.sdf' + }.items(), + ) + + # RQt + rqt = Node( + package='rqt_image_view', + executable='rqt_image_view', + arguments=[LaunchConfiguration('image_topic')], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # Bridge + bridge = Node( + package='ros_gz_image', + executable='image_bridge', + arguments=['camera', 'depth_camera', 'rgbd_camera/image', 'rgbd_camera/depth_image'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + DeclareLaunchArgument('image_topic', default_value='/camera', + description='Topic to start viewing in RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py new file mode 100644 index 00000000..649ad359 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py @@ -0,0 +1,78 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors.sdf' + }.items(), + ) + + # RQt + rqt = Node( + package='rqt_topic', + executable='rqt_topic', + arguments=['-t'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # RViz + # FIXME: Add once there's an IMU display for RViz2 + # pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + # rviz = Node( + # package='rviz2', + # executable='rviz2', + # # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'imu.rviz')], + # condition=IfCondition(LaunchConfiguration('rviz')) + # ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/imu@sensor_msgs/msg/Imu@ignition.msgs.IMU'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument( + 'rqt', default_value='true', description='Open RQt.' + ), + DeclareLaunchArgument( + 'rviz', default_value='true', description='Open RViz.' + ), + bridge, + rqt + # rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py new file mode 100644 index 00000000..20b330ec --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py @@ -0,0 +1,98 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node +import xacro + + +def generate_launch_description(): + + # Package Directories + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + + # Parse robot description from xacro + robot_description_file = os.path.join(pkg_ros_gz_sim_demos, 'models', 'rrbot.xacro') + robot_description_config = xacro.process_file( + robot_description_file + ) + robot_description = {'robot_description': robot_description_config.toxml()} + + # Robot state publisher + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='both', + parameters=[robot_description], + ) + + # Gazebo Sim + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') + ), + launch_arguments={'gz_args': '-r empty.sdf'}.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'joint_states.rviz')], + ) + + # Spawn + spawn = Node( + package='ros_gz_sim', + executable='create', + arguments=[ + '-name', 'rrbot', + '-topic', 'robot_description', + ], + output='screen', + ) + + # Gz - ROS Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + # Clock (IGN -> ROS2) + '/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock', + # Joint states (IGN -> ROS2) + '/world/empty/model/rrbot/joint_state@sensor_msgs/msg/JointState[ignition.msgs.Model', + ], + remappings=[ + ('/world/empty/model/rrbot/joint_state', 'joint_states'), + ], + output='screen' + ) + + return LaunchDescription( + [ + # Nodes and Launches + gazebo, + spawn, + bridge, + robot_state_publisher, + rviz, + ] + ) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py new file mode 100644 index 00000000..0e026676 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors.sdf' + }.items(), + ) + + # RQt + rqt = Node( + package='rqt_topic', + executable='rqt_topic', + arguments=['-t'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/magnetometer@sensor_msgs/msg/MagneticField@ignition.msgs.Magnetometer'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py new file mode 100644 index 00000000..1ec8409b --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + # launch_arguments={ + # 'gz_args': '-r rgbd_camera.sdf' + # }.items(), + ) + + # FIXME: need rviz configuration migration + # rviz = Node( + # package='rviz2', + # executable='rviz2', + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera.rviz')], + # condition=IfCondition(LaunchConfiguration('rviz')) + # ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image', + '/rgbd_camera/depth_image@sensor_msgs/msg/Image@ignition.msgs.Image'], + output='screen' + ) + + # FIXME: need a SDF file (depth_camera.sdf) inside ros_gz_point_cloud/ + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + # rviz, + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py new file mode 100644 index 00000000..a318f682 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py @@ -0,0 +1,70 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors_demo.sdf' + }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=[ + '-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera_bridge.rviz') + ], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + '/rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image', + '/rgbd_camera/depth_image@sensor_msgs/msg/Image@ignition.msgs.Image', + '/rgbd_camera/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked' + ], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz, + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py new file mode 100755 index 00000000..882cdee3 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py @@ -0,0 +1,93 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch_ros.actions import Node + + +def generate_launch_description(): + # Import the model urdf (load from file, xacro ...) + robot_desc = \ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + '' + + # Robot state publisher + params = {'use_sim_time': True, 'robot_description': robot_desc} + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='screen', + parameters=[params], + arguments=[]) + + # Gazebo Sim + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r empty.sdf'}.items(), + ) + + # RViz + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=[ + '-d', + os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'robot_description_publisher.rviz') + ] + ) + + # Spawn + spawn = Node(package='ros_gz_sim', executable='create', + arguments=[ + '-name', 'my_custom_model', + '-x', '1.2', + '-z', '2.3', + '-Y', '3.4', + '-topic', '/robot_description'], + output='screen') + + return LaunchDescription([ + gazebo, + robot_state_publisher, + rviz, + spawn + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py new file mode 100644 index 00000000..3b2171d0 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py @@ -0,0 +1,59 @@ +# Copyright 2022 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import ExecuteProcess +from launch_ros.actions import Node + + +def generate_launch_description(): + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + return LaunchDescription([ + # Launch gazebo + ExecuteProcess( + cmd=[ + 'ign', 'gazebo', '-r', + os.path.join( + pkg_ros_gz_sim_demos, + 'models', + 'double_pendulum_model.sdf' + ) + ] + ), + # Launch a bridge to forward tf and joint states to ros2 + Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + '/world/default/model/double_pendulum_with_base0/joint_state@' + 'sensor_msgs/msg/JointState[ignition.msgs.Model', + '/model/double_pendulum_with_base0/pose@' + 'tf2_msgs/msg/TFMessage[ignition.msgs.Pose_V' + ], + remappings=[ + ('/model/double_pendulum_with_base0/pose', '/tf'), + ('/world/default/model/double_pendulum_with_base0/joint_state', '/joint_states') + ] + ), + # Launch rviz + Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'tf_bridge.rviz')] + ) + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py new file mode 100644 index 00000000..9e6362a2 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py @@ -0,0 +1,64 @@ +# Copyright 2022 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r triggered_camera_sensor.sdf'}.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'camera.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/camera@sensor_msgs/msg/Image@ignition.msgs.Image', + '/camera/trigger@std_msgs/msg/Bool@ignition.msgs.Boolean', + '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo'], + output='screen' + ) + + return LaunchDescription([ + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + gz_sim, + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf b/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf new file mode 100644 index 00000000..91e072e4 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf @@ -0,0 +1,266 @@ + + + + + 0.001 + 1 + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0 0 0 0 + + + + 100 + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + -0.275 0 1.1 0 0 0 + + + 0.2 0.2 2.2 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + + -0.275 0 1.1 0 0 0 + + + 0.2 0.2 2.2 + + + + + + + 0 0 2.1 -1.5708 0 0 + 0 + + 0 0 0.5 0 0 0 + + + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.2 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.2 + + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + 0.25 1.0 2.1 -2 0 0 + 0 + + 0 0 0.5 0 0 0 + + + 0 0 0 0 1.5708 0 + + + 0.08 + 0.3 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0 0 1.5708 0 + + + 0.08 + 0.3 + + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + base + upper_link + + 1.0 0 0 + + + + + upper_link + lower_link + + 1.0 0 0 + + + + + + + + true + + true + + + + + + diff --git a/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro b/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro new file mode 100644 index 00000000..00680c14 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro @@ -0,0 +1,165 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + + + + + + 0.2 + 0.2 + + 0 0 0 1 + 0 0 0 1 + 0 0 0 1 + + + + + + 0.2 + 0.2 + + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + + + + + + + + + \ No newline at end of file diff --git a/ros_gz_shims/ros_ign_gazebo_demos/package.xml b/ros_gz_shims/ros_ign_gazebo_demos/package.xml new file mode 100644 index 00000000..55bf4a5c --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/package.xml @@ -0,0 +1,17 @@ + + ros_ign_gazebo_demos + 0.0.1 + Shim package to redirect to ros_gz_sim_demos. + Apache 2.0 + Brandon Ong + + ament_cmake + ros_gz_sim_demos + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz new file mode 100644 index 00000000..81398197 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz @@ -0,0 +1,137 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Camera1 + - /Camera1/Status1 + - /Image1 + Splitter Ratio: 0.5 + Tree Height: 557 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz_default_plugins/Camera + Enabled: true + Image Rendering: background and overlay + Name: Camera + Overlay Alpha: 0.5 + Queue Size: 10 + Topic: /camera + Unreliable: false + Value: true + Visibility: + Grid: true + Image: true + Value: true + Zoom Factor: 1 + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 10 + Topic: /camera + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: camera/link/camera + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 19.73822784423828 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7903980016708374 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Camera: + collapsed: false + Displays: + collapsed: false + Height: 702 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000015600000268fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000268000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001c700000268fc0200000005fb0000000c00430061006d006500720061010000003b0000011f0000002800fffffffb0000000a0049006d0061006700650100000160000001430000002800fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000000320000026800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 859 + X: 517 + Y: 361 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz new file mode 100644 index 00000000..6957e15f --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz @@ -0,0 +1,147 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Image1 + - /PointCloud21 + Splitter Ratio: 0.5 + Tree Height: 423 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Class: rviz/Image + Enabled: true + Image Topic: /depth_camera + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.019999999552965164 + Style: Flat Squares + Topic: /depth_camera/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 255; 255; 255 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 6.307931423187256 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.024829570204019547 + Y: -0.440496027469635 + Z: 1.0747597217559814 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: -1.3397971391677856 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.723598957061768 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 568 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001e2fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001e2000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610000000272000000c1000000000000000000000001000001b8000001e2fc0200000006fb0000000a0049006d006100670065010000003b000001e20000001600fffffffb0000000c00430061006d00650072006100000001ae000001850000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d0065010000000000000450000000000000000000000196000001e200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 405 + Y: 378 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz new file mode 100644 index 00000000..e647f4c9 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz @@ -0,0 +1,123 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Odometry1 + - /Odometry1/Status1 + Splitter Ratio: 0.5 + Tree Height: 701 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1000 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Arrow + Topic: /model/vehicle_blue/odometry + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: vehicle_blue/odom + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 68.66040802001953 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -1.2689772844314575 + Y: 10.203336715698242 + Z: -2.8907392024993896 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.5697963237762451 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.8253979682922363 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000023d000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000026d000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 325 + Y: 158 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz new file mode 100644 index 00000000..9161d0c8 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz @@ -0,0 +1,181 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /LaserScan1 + - /PointCloud21 + Splitter Ratio: 0.5 + Tree Height: 366 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /lidar + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /custom_params/pc2 + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: custom_params/link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 10.596034049987793 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 1.855783224105835 + Y: -0.6233639717102051 + Z: 0.7489486932754517 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5402030348777771 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.7535903453826904 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 511 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001a9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001b8000002f8fc0200000006fb0000000a0049006d006100670065000000003b0000016d0000000000000000fb0000000c00430061006d006500720061000000003b000002f80000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d0065010000000000000450000000000000000000000161000001a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 701 + X: 352 + Y: 269 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz new file mode 100644 index 00000000..42968c2b --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz @@ -0,0 +1,167 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /LaserScan1/Status1 + - /PointCloud21/Status1 + Splitter Ratio: 0.504601240158081 + Tree Height: 701 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /lidar + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: "" + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /lidar + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: model_with_lidar/link/gpu_lidar + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 15.735194206237793 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 2.550645589828491 + Y: -0.290515273809433 + Z: -1.1467934846878052 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7253980040550232 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.7385823726654053 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd0000000400000000000001ef000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000002ed00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000002bb000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1200 + X: 338 + Y: 1176 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz new file mode 100644 index 00000000..0169390a --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz @@ -0,0 +1,130 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Imu1 + - /Imu1/Status1 + Splitter Ratio: 0.5 + Tree Height: 352 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_plugin_tutorials/Imu + Color: 204; 51; 204 + Enabled: true + History Length: 1 + Name: Imu + Topic: /imu + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: sensors/sensors_box/link/imu + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 33.22251510620117 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -1.7206333875656128 + Y: -0.9246708154678345 + Z: 1.870512843132019 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.785398006439209 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 575 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000191000001e9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001e9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002b4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003d70000003efc0100000002fb0000000800540069006d00650000000000000003d70000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000001a2000001e900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 825 + X: 751 + Y: 92 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz new file mode 100644 index 00000000..06920d70 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz @@ -0,0 +1,190 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + - /TF1 + Splitter Ratio: 0.5 + Tree Height: 802 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.800000011920929 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + link1: + Value: true + link2: + Value: true + link3: + Value: true + world: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + link1: + link2: + link3: + {} + world: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 6.524543762207031 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.106326624751091 + Y: 0.5023337006568909 + Z: 1.1979976892471313 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7303980588912964 + Target Frame: + Value: Orbit (rviz) + Yaw: 5.698581218719482 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1025 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000003abfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003ab000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003abfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000003ab000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004cc000003ab00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1853 + X: 67 + Y: 27 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz new file mode 100644 index 00000000..d6933fc6 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz @@ -0,0 +1,159 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /PointCloud21 + - /Image2 + Splitter Ratio: 0.5 + Tree Height: 317 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Class: rviz/Image + Enabled: true + Image Topic: /rgbd_camera/depth_image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /default_params/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /rgbd_camera/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: default_params + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 3.1044178009033203 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.04919945076107979 + Y: -0.08779548853635788 + Z: 2.6499500274658203 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: -1.3547965288162231 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.718593597412109 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 540 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001c6fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001c6000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000012d000001c6fc0200000007fb0000000a0049006d006100670065010000003b000000d60000001600fffffffb0000000a0049006d0061006700650100000117000000ea0000001600fffffffc000001ce000001650000000000fffffffa000000000100000002fb0000000a0049006d0061006700650100000000ffffffff0000000000000000fb0000000c00430061006d006500720061000000044c000000640000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d006501000000000000045000000000000000000000011a000001c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 937 + X: 147 + Y: 349 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz new file mode 100644 index 00000000..58955045 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz @@ -0,0 +1,142 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /PointCloud21/Status1 + Splitter Ratio: 0.3251533806324005 + Tree Height: 701 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Flat Squares + Topic: /rgbd_camera/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 10 + Topic: /rgbd_camera/depth_image + Unreliable: false + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 10 + Topic: /rgbd_camera/image + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: rgbd_camera/link/rgbd_camera + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 5.996953964233398 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.10905617475509644 + Y: 0.08000272512435913 + Z: 0.346417099237442 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.29039809107780457 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.0753986835479736 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000174000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000002ed00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000005fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0049006d006100670065010000003b000002020000002800fffffffb0000000a0049006d0061006700650100000243000000f00000002800fffffffb0000000a0056006900650077007300000000cf00000264000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000221000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 375 + Y: 1116 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz new file mode 100644 index 00000000..058a47f4 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz @@ -0,0 +1,148 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /RobotModel1/Description Topic1 + Splitter Ratio: 0.5 + Tree Height: 878 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 77; 77; 79 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 50 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 207; 207; 207 + Fixed Frame: link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 49.51093292236328 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.8779783248901367 + Y: 0.15285056829452515 + Z: 0.762141764163971 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.6602023243904114 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.142223358154297 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1023 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000222000003a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003a9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000198000003a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 960 + X: 898 + Y: 27 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz new file mode 100644 index 00000000..76c42557 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz @@ -0,0 +1,163 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /TF1 + - /TF1/Frames1 + Splitter Ratio: 0.516339898109436 + Tree Height: 549 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + double_pendulum_with_base0: + Value: true + double_pendulum_with_base0/base: + Value: true + double_pendulum_with_base0/lower_link: + Value: true + double_pendulum_with_base0/upper_link: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + double_pendulum_with_base0: + double_pendulum_with_base0/base: + {} + double_pendulum_with_base0/lower_link: + {} + double_pendulum_with_base0/upper_link: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: double_pendulum_with_base0 + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 8.114859580993652 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3453984260559082 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.2535715103149414 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000002ff000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000066f0000003efc0100000002fb0000000800540069006d006501000000000000066f000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000255000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1647 + X: 251 + Y: 169 diff --git a/ros_gz_shims/ros_ign_image/CMakeLists.txt b/ros_gz_shims/ros_ign_image/CMakeLists.txt new file mode 100644 index 00000000..5fa4b91b --- /dev/null +++ b/ros_gz_shims/ros_ign_image/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.5) + +project(ros_ign_image) + +# 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") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_index_cpp REQUIRED) + +add_executable(image_bridge src/image_bridge_shim.cpp) +ament_target_dependencies(image_bridge ament_index_cpp) + +ament_export_dependencies(ament_index_cpp ros_gz_image) + +install(TARGETS + image_bridge + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_image/README.md b/ros_gz_shims/ros_ign_image/README.md new file mode 100644 index 00000000..517ccdd8 --- /dev/null +++ b/ros_gz_shims/ros_ign_image/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_image](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_image) diff --git a/ros_gz_shims/ros_ign_image/package.xml b/ros_gz_shims/ros_ign_image/package.xml new file mode 100644 index 00000000..7b621801 --- /dev/null +++ b/ros_gz_shims/ros_ign_image/package.xml @@ -0,0 +1,19 @@ + + + + ros_ign_image + 0.0.1 + Shim package to redirect to ros_gz_image. + Brandon Ong + + Apache 2.0 + + ament_cmake + ament_index_cpp + + ros_gz_image + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp b/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp new file mode 100644 index 00000000..c004a7dc --- /dev/null +++ b/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_image image_bridge" call to "ros_gz_image image_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_image") + << "/lib/ros_gz_image/image_bridge"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_bridge] is deprecated! " + << "Redirecting to use [ros_gz_image] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_interfaces/CMakeLists.txt b/ros_gz_shims/ros_ign_interfaces/CMakeLists.txt new file mode 100644 index 00000000..b397466b --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/CMakeLists.txt @@ -0,0 +1,49 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_interfaces) + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(builtin_interfaces REQUIRED) +find_package(std_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(ros_gz_interfaces REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +set(msg_files + "msg/Contact.msg" + "msg/Contacts.msg" + "msg/Entity.msg" + "msg/EntityFactory.msg" + "msg/GuiCamera.msg" + "msg/JointWrench.msg" + "msg/Light.msg" + "msg/StringVec.msg" + "msg/TrackVisual.msg" + "msg/VideoRecord.msg" + "msg/WorldControl.msg" + "msg/WorldReset.msg" +) + +set(srv_files + "srv/ControlWorld.srv" + "srv/DeleteEntity.srv" + "srv/SetEntityPose.srv" + "srv/SpawnEntity.srv" +) + +rosidl_generate_interfaces(${PROJECT_NAME} + ${msg_files} + ${srv_files} + DEPENDENCIES builtin_interfaces std_msgs geometry_msgs ros_gz_interfaces + ADD_LINTER_TESTS +) + +ament_export_dependencies(rosidl_default_runtime) +ament_package() diff --git a/ros_gz_shims/ros_ign_interfaces/README.md b/ros_gz_shims/ros_ign_interfaces/README.md new file mode 100644 index 00000000..b2ce4368 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_sim_demos](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_gazebo_demos) diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Contact.msg b/ros_gz_shims/ros_ign_interfaces/msg/Contact.msg new file mode 100644 index 00000000..98d2cef8 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Contact.msg @@ -0,0 +1,6 @@ +ros_gz_interfaces/Entity collision1 # Contact collision1 +ros_gz_interfaces/Entity collision2 # Contact collision2 +geometry_msgs/Vector3[] positions # List of contact position +geometry_msgs/Vector3[] normals # List of contact normals +float64[] depths # List of penetration depths +ros_gz_interfaces/JointWrench[] wrenches # List of joint wrenches including forces/torques diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg b/ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg new file mode 100644 index 00000000..40232e51 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg @@ -0,0 +1,2 @@ +std_msgs/Header header # Time stamp +ros_gz_interfaces/Contact[] contacts # List of contacts diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Entity.msg b/ros_gz_shims/ros_ign_interfaces/msg/Entity.msg new file mode 100644 index 00000000..b785c7ed --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Entity.msg @@ -0,0 +1,13 @@ +# Entity type: constant definition +uint8 NONE = 0 +uint8 LIGHT = 1 +uint8 MODEL = 2 +uint8 LINK = 3 +uint8 VISUAL = 4 +uint8 COLLISION = 5 +uint8 SENSOR = 6 +uint8 JOINT = 7 + +uint64 id # Entity unique identifier accross all types. Defaults to 0 +string name # Entity name, which is not guaranteed to be unique. +uint8 type # Entity type. diff --git a/ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg b/ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg new file mode 100644 index 00000000..4576c003 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg @@ -0,0 +1,11 @@ +string name # New name for the entity, overrides the name on the SDF +bool allow_renaming false # Whether the server is allowed to rename the entity in case of + # overlap with existing entities. + +# Only one method is supported at a time (sdf,sdf_filename,clone_name) +string sdf # SDF description in string format +string sdf_filename # Full path to SDF file. +string clone_name # Name of entity to clone + +geometry_msgs/Pose pose # Pose where the entity will be spawned in the world. +string relative_to "world" # Pose is defined relative to the frame of this entity. diff --git a/ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg b/ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg new file mode 100644 index 00000000..d45fd9b8 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg @@ -0,0 +1,12 @@ +# Message for a GUI Camera. + +# Optional header data. +std_msgs/Header header + +string name +string view_controller +geometry_msgs/Pose pose +TrackVisual track + +# Type of projection: "perspective" or "orthographic". +string projection_type diff --git a/ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg b/ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg new file mode 100644 index 00000000..2da89094 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg @@ -0,0 +1,8 @@ +std_msgs/Header header # Time stamp +std_msgs/String body_1_name # Body 1 name string +std_msgs/UInt32 body_1_id # Body 1 id +std_msgs/String body_2_name # Body 2 name string +std_msgs/UInt32 body_2_id # Body 2 id + +geometry_msgs/Wrench body_1_wrench # Body 1 wrench +geometry_msgs/Wrench body_2_wrench # Body 2 wrench diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Light.msg b/ros_gz_shims/ros_ign_interfaces/msg/Light.msg new file mode 100644 index 00000000..911e20bd --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Light.msg @@ -0,0 +1,29 @@ +std_msgs/Header header # Optional header data + +string name # Light name + +# Light type: constant definition +uint8 POINT = 0 +uint8 SPOT = 1 +uint8 DIRECTIONAL = 2 + +uint8 type # Light type (from constant definitions) + +geometry_msgs/Pose pose # Light pose +std_msgs/ColorRGBA diffuse # Light diffuse emission +std_msgs/ColorRGBA specular # Light specular emission +float32 attenuation_constant # Constant variable in attenuation formula +float32 attenuation_linear # Linear variable in attenuation formula +float32 attenuation_quadratic # Quadratic variable in attenuation formula +geometry_msgs/Vector3 direction # Light direction +float32 range # Light range +bool cast_shadows # Enable/disable shadow casting +float32 spot_inner_angle # Spotlight inner cone angle +float32 spot_outer_angle # Spotlight outer cone angle +float32 spot_falloff # Falloff between inner and outer cone + +uint32 id # Unique id of the light + +uint32 parent_id # Unique id of the light's parent + +float32 intensity # Light intensity diff --git a/ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg b/ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg new file mode 100644 index 00000000..15a7dda9 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg @@ -0,0 +1,7 @@ +# A message for a vector of string data. + +# Optional header data. +std_msgs/Header header + +# The vector of strings. +string[] data diff --git a/ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg b/ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg new file mode 100644 index 00000000..c09f4785 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg @@ -0,0 +1,33 @@ +# Message for a tracking a rendering::Visual with a rendering::Camera. + +# Optional header data. +std_msgs/Header header + +# Name of the visual to track. +string name + +# Id of the visual to track. +uint32 id + +# True to have the tracking camera inherit the orientation of +# the tracked visual. +bool inherit_orientation + +# Minimum follow distance. +float64 min_dist + +# Maximum follow distance. +float64 max_dist + +# If set to true, the position of the camera is fixed. +bool is_static + +# If set to true, the position of the camera is relative to the. +# model reference frame. +bool use_model_frame + +# Position of the camera. +geometry_msgs/Vector3 xyz + +# If set to true, the camera inherits the yaw rotation of the model. +bool inherit_yaw diff --git a/ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg b/ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg new file mode 100644 index 00000000..02bafde0 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg @@ -0,0 +1,16 @@ +# A message that allows for control of video recording functions. + +# Optional header data. +std_msgs/Header header + +# True to start video recording. +bool start + +# True to stop video recording. +bool stop + +# Video encoding format, e.g. "mp4", "ogv". +string format + +# filename of the recorded video. +string save_filename diff --git a/ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg b/ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg new file mode 100644 index 00000000..efa22fb9 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg @@ -0,0 +1,7 @@ +bool pause # Paused state. +bool step # +uint32 multi_step 0 # Paused after stepping multi_step. +ros_gz_interfaces/WorldReset reset # +uint32 seed # +builtin_interfaces/Time run_to_sim_time # A simulation time in the future to run to and + # then pause. diff --git a/ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg b/ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg new file mode 100644 index 00000000..46f5971f --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg @@ -0,0 +1,3 @@ +bool all false # Reset time and model +bool time_only false # Reset time only +bool model_only false # Reset model only diff --git a/ros_gz_shims/ros_ign_interfaces/package.xml b/ros_gz_shims/ros_ign_interfaces/package.xml new file mode 100644 index 00000000..4c0909e1 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/package.xml @@ -0,0 +1,27 @@ + + ros_ign_interfaces + 0.0.1 + Shim package to redirect to ros_gz_interfaces. + Apache 2.0 + Brandon Ong + Zhenpeng Ge + ament_cmake + rosidl_default_generators + + builtin_interfaces + ros_gz_interfaces + std_msgs + geometry_msgs + + builtin_interfaces + ros_gz_interfaces + std_msgs + geometry_msgs + rosidl_default_runtime + + ament_lint_common + rosidl_interface_packages + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv b/ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv new file mode 100644 index 00000000..d8e41f24 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv @@ -0,0 +1,3 @@ +ros_gz_interfaces/WorldControl world_control # Message to Control world in Gazebo Sim +--- +bool success # Return true if control is successful. diff --git a/ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv b/ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv new file mode 100644 index 00000000..13b3e1fd --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv @@ -0,0 +1,3 @@ +ros_gz_interfaces/Entity entity # Gazebo Sim entity to be deleted. +--- +bool success # Return true if deletion is successful. diff --git a/ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv b/ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv new file mode 100644 index 00000000..b749488c --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv @@ -0,0 +1,4 @@ +ros_gz_interfaces/Entity entity # Gazebo Sim entity. +geometry_msgs/Pose pose # Pose of entity. +--- +bool success # Return true if set successfully. diff --git a/ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv b/ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv new file mode 100644 index 00000000..35d5df59 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv @@ -0,0 +1,3 @@ +ros_gz_interfaces/EntityFactory entity_factory # Message to create a new entity +--- +bool success # Return true if spawned successfully.