diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md index dc00d300..354ba263 100644 --- a/ros_gz_sim_demos/README.md +++ b/ros_gz_sim_demos/README.md @@ -68,9 +68,9 @@ Trigger the camera: Send commands to a differential drive vehicle and listen to its odometry. - ros2 launch ros_gz_sim_demos diff_drive.launch.py + ros2 launch ros_gz_sim_demos diff_drive.launch.xml -Then unpause and send a command +Then send a command ros2 topic pub /model/vehicle_blue/cmd_vel geometry_msgs/msg/Twist "{linear: {x: 5.0}, angular: {z: 0.5}}" diff --git a/ros_gz_sim_demos/config/diff_drive.yaml b/ros_gz_sim_demos/config/diff_drive.yaml new file mode 100644 index 00000000..96d656c2 --- /dev/null +++ b/ros_gz_sim_demos/config/diff_drive.yaml @@ -0,0 +1,36 @@ +# Diff drive configuration. +- topic_name: "/model/vehicle_blue/cmd_vel" + ros_type_name: "geometry_msgs/msg/Twist" + gz_type_name: "gz.msgs.Twist" + lazy: true + direction: ROS_TO_GZ + +- topic_name: "/model/vehicle_blue/odometry" + ros_type_name: "nav_msgs/msg/Odometry" + gz_type_name: "gz.msgs.Odometry" + lazy: true + direction: GZ_TO_ROS + +- topic_name: "/model/vehicle_green/cmd_vel" + ros_type_name: "geometry_msgs/msg/Twist" + gz_type_name: "gz.msgs.Twist" + lazy: true + direction: ROS_TO_GZ + +- topic_name: "/model/vehicle_green/odometry" + ros_type_name: "nav_msgs/msg/Odometry" + gz_type_name: "gz.msgs.Odometry" + lazy: true + direction: GZ_TO_ROS + +- ros_topic_name: "/tf" + gz_topic_name: "/model/vehicle_green/tf" + ros_type_name: "tf2_msgs/msg/TFMessage" + gz_type_name: "gz.msgs.Pose_V" + direction: GZ_TO_ROS + +- ros_topic_name: "/tf" + gz_topic_name: "/model/vehicle_blue/tf" + ros_type_name: "tf2_msgs/msg/TFMessage" + gz_type_name: "gz.msgs.Pose_V" + direction: GZ_TO_ROS diff --git a/ros_gz_sim_demos/launch/diff_drive.launch.py b/ros_gz_sim_demos/launch/diff_drive.launch.py deleted file mode 100644 index 2d656d1e..00000000 --- a/ros_gz_sim_demos/launch/diff_drive.launch.py +++ /dev/null @@ -1,69 +0,0 @@ -# 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@gz.msgs.Twist', - '/model/vehicle_blue/odometry@nav_msgs/msg/Odometry@gz.msgs.Odometry', - '/model/vehicle_green/cmd_vel@geometry_msgs/msg/Twist@gz.msgs.Twist', - '/model/vehicle_green/odometry@nav_msgs/msg/Odometry@gz.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_sim_demos/launch/diff_drive.launch.xml b/ros_gz_sim_demos/launch/diff_drive.launch.xml new file mode 100644 index 00000000..c09bab7f --- /dev/null +++ b/ros_gz_sim_demos/launch/diff_drive.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + diff --git a/ros_gz_sim_demos/package.xml b/ros_gz_sim_demos/package.xml index 414af4fe..433f3f23 100644 --- a/ros_gz_sim_demos/package.xml +++ b/ros_gz_sim_demos/package.xml @@ -25,6 +25,7 @@ rviz_imu_plugin rviz2 sdformat_urdf + tf2_ros xacro ament_lint_auto diff --git a/ros_gz_sim_demos/rviz/diff_drive.rviz b/ros_gz_sim_demos/rviz/diff_drive.rviz index e647f4c9..a43e216a 100644 --- a/ros_gz_sim_demos/rviz/diff_drive.rviz +++ b/ros_gz_sim_demos/rviz/diff_drive.rviz @@ -6,14 +6,13 @@ Panels: Expanded: - /Global Options1 - /Odometry1 - - /Odometry1/Status1 + - /Odometry2 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 @@ -25,6 +24,24 @@ Panels: 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 - Angle Tolerance: 0.10000000149011612 Class: rviz_default_plugins/Odometry Covariance: @@ -56,13 +73,57 @@ Visualization Manager: Shaft Length: 1 Shaft Radius: 0.05000000074505806 Value: Arrow - Topic: /model/vehicle_blue/odometry - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /model/vehicle_blue/odometry + Value: true + - 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: 100 + 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: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /model/vehicle_green/odometry Value: true Enabled: true Global Options: Background Color: 48; 48; 48 - Fixed Frame: vehicle_blue/odom + Fixed Frame: world Frame Rate: 30 Name: root Tools: @@ -72,12 +133,30 @@ Visualization Manager: - Class: rviz_default_plugins/Measure Line color: 128; 128; 0 - Class: rviz_default_plugins/SetInitialPose - Topic: /initialpose + 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: /move_base_simple/goal + 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: /clicked_point + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point Transformation: Current: Class: rviz_default_plugins/TF @@ -85,25 +164,25 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 68.66040802001953 + Distance: 21.00491714477539 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 + X: -0.4080231189727783 + Y: 0.40098077058792114 + Z: 2.436375617980957 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 + Pitch: 0.5847957730293274 Target Frame: Value: Orbit (rviz) - Yaw: 0.8253979682922363 + Yaw: 0.4803982973098755 Saved: ~ Window Geometry: Displays: @@ -119,5 +198,5 @@ Window Geometry: Views: collapsed: false Width: 1200 - X: 325 - Y: 158 + X: 554 + Y: 154