Add support to Gazebo Ignition.
authorWalter Fetter Lages <w.fetter@ieee.org>
Mon, 3 Jul 2023 04:41:58 +0000 (01:41 -0300)
committerWalter Fetter Lages <w.fetter@ieee.org>
Mon, 3 Jul 2023 04:41:58 +0000 (01:41 -0300)
12 files changed:
tatuira_bringup/launch/gazebo.launch.xml
tatuira_bringup/launch/gazebo8.launch.xml
tatuira_description/CMakeLists.txt
tatuira_description/config/gz_bridge.yaml [new file with mode: 0644]
tatuira_description/env-hooks/tatuira_description.dsv.in [new file with mode: 0644]
tatuira_description/launch/ignition.launch.xml [new file with mode: 0644]
tatuira_description/urdf/d435.xacro [new file with mode: 0644]
tatuira_description/urdf/gazebo_control.xacro
tatuira_description/urdf/ground_truth.xacro [new file with mode: 0644]
tatuira_description/urdf/ros2_control.xacro
tatuira_description/urdf/tatuira.urdf.xacro
tatuira_ident/launch/gazebo.launch.xml

index 65345c6..bd04304 100644 (file)
        <arg name="pause" default="true"/>
        <arg name="gui" default="true"/>
        <arg name="use_sim_time" default="true"/>
-       <arg name="world" default ="worlds/empty_sky.world"/>
+       <arg name="world" default="worlds/empty_sky.world"/>
        <arg name="d435" default="false"/>
-
+       <arg name="ignition" default="false"/>
+       
        <arg name="controller" default="pid"/>
        <arg name="config" default="$(find-pkg-share tatuira_bringup)/config/$(var controller).yaml"/>
 
@@ -33,7 +34,7 @@
 
        <!--remap unless="$(var odometry)" from="$(var controller)/odom" to="/odom"/-->
 
-       <include file="$(find-pkg-share tatuira_description)/launch/gazebo.launch.xml">
+       <include unless="$(var ignition)" file="$(find-pkg-share tatuira_description)/launch/gazebo.launch.xml">
                <arg name="pause" value="$(var pause)"/>
                <arg name="gui" value="$(var gui)"/>
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
                <arg name="d435" value="$(var d435)"/>
        </include>
 
+       <include if="$(var ignition)" file="$(find-pkg-share tatuira_description)/launch/ignition.launch.xml">
+               <arg name="pause" value="$(var pause)"/>
+               <arg name="gui" value="$(var gui)"/>
+               <arg name="use_sim_time" value="$(var use_sim_time)"/>
+               <arg name="world" value="empty.sdf"/>
+               <arg name="d435" value="$(var d435)"/>
+       </include>
+
        <include file="$(find-pkg-share tatuira_bringup)/launch/$(var controller).launch.xml">
                <arg name="config" value="$(var config)"/>
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
index dc1f7f3..1433c21 100644 (file)
@@ -23,6 +23,7 @@
        <arg name="pause" default="true"/>
        <arg name="gui" default="true"/>
        <arg name="use_sim_time" default="true"/>
+       <arg name="ignition" default="false"/>
 
        <arg name="controller" default="nonsmooth_backstep_controller"/>
        <arg name="config" default="$(find-pkg-share tatuira_bringup)/config/$(var controller).yaml"/>
@@ -33,6 +34,7 @@
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
                <arg name="controller" value="$(var controller)"/>
                <arg name="config" value="$(var config)"/>
+               <arg name="ignition" value="$(var ignition)"/>
        </include>
 
        <node name="eight_trajectory" pkg="pose2d_trajectories" exec="eight_trajectory">
                <remap from="command" to="/$(var controller)/command"/>
        </node>
 
+
        <node name="pose2d_stamp" pkg="pose2d_trajectories" exec="pose2d_stamp" args="_frame_id:=map"/>
 
+       <group>
        <include file="$(find-pkg-share tatuira_description)/launch/display.launch.xml">
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
+               <arg name="gui" value="false"/>
        </include>
+       </group>
 </launch>
index be4fc38..0189f25 100644 (file)
@@ -27,4 +27,6 @@ if(BUILD_TESTING)
   ament_lint_auto_find_test_dependencies()
 endif()
 
+ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/env-hooks/${PROJECT_NAME}.dsv.in")
+
 ament_package()
diff --git a/tatuira_description/config/gz_bridge.yaml b/tatuira_description/config/gz_bridge.yaml
new file mode 100644 (file)
index 0000000..ccc687c
--- /dev/null
@@ -0,0 +1,46 @@
+- ros_topic_name: "/clock"
+  gz_topic_name: "/clock"
+  ros_type_name: "rosgraph_msgs/msg/Clock"
+  gz_type_name: "ignition.msgs.Clock"
+#  subscriber_queue: 5       # Default 10
+#  publisher_queue: 6        # Default 10
+#  lazy: true                # Default "false"
+  direction: GZ_TO_ROS      # Default "BIDIRECTIONAL" - Bridge both directions
+                            # "GZ_TO_ROS" - Bridge Ignition topic to ROS
+                            # "ROS_TO_GZ" - Bridge ROS topic to Ignition
+  
+- ros_topic_name: "/ground_truth"
+  gz_topic_name: "/model/tatuira/pose"
+  ros_type_name: "geometry_msgs/msg/PoseArray"
+  gz_type_name: "ignition.msgs.Pose_V"
+  direction: GZ_TO_ROS
+
+#- ros_topic_name: "/gnss/fix"
+#  gz_topic_name: "/gnss/fix"
+#  ros_type_name: "sensor_msgs/msg/NavSatFix"
+#  gz_type_name: "ignition.msgs.NavSat"
+#  direction: GZ_TO_ROS
+
+#- ros_topic_name: "/imu/data"
+#  gz_topic_name: "/imu/data"
+#  ros_type_name: "sensor_msgs/msg/Imu"
+#  gz_type_name: "ignition.msgs.IMU"
+#  direction: GZ_TO_ROS
+
+#- ros_topic_name: "/imu/mag"
+#  gz_topic_name: "/imu/mag"
+#  ros_type_name: "sensor_msgs/msg/MagneticField"
+#  gz_type_name: "ignition.msgs.Magnetometer"
+#  direction: GZ_TO_ROS
+
+- ros_topic_name: "/camera/camera_info"
+  gz_topic_name: "/camera/camera_info"
+  ros_type_name: "sensor_msgs/msg/CameraInfo"
+  gz_type_name: "ignition.msgs.CameraInfo"
+  direction: GZ_TO_ROS
+
+- ros_topic_name: "/camera/image_raw"
+  gz_topic_name: "/camera/image_raw"
+  ros_type_name: "sensor_msgs/msg/Image"
+  gz_type_name: "ignition.msgs.Image"
+  direction: GZ_TO_ROS
diff --git a/tatuira_description/env-hooks/tatuira_description.dsv.in b/tatuira_description/env-hooks/tatuira_description.dsv.in
new file mode 100644 (file)
index 0000000..30a6001
--- /dev/null
@@ -0,0 +1,3 @@
+prepend-non-duplicate;IGN_GAZEBO_RESOURCE_PATH;share
+
+set-if-unset;MESA_GL_VERSION_OVERRIDE;3.3
diff --git a/tatuira_description/launch/ignition.launch.xml b/tatuira_description/launch/ignition.launch.xml
new file mode 100644 (file)
index 0000000..c799c46
--- /dev/null
@@ -0,0 +1,51 @@
+<!--******************************************************************************
+                           Tatuira Description
+                          Ignition Gazebo Launch File
+          Copyright (C) 2023 Walter Fetter Lages <w.fetter@ieee.org>
+
+        This program is free software: you can redistribute it and/or modify
+        it under the terms of the GNU General Public License as published by
+        the Free Software Foundation, either version 3 of the License, or
+        (at your option) any later version.
+
+        This program is distributed in the hope that it will be useful, but
+        WITHOUT ANY WARRANTY; without even the implied warranty of
+        MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+        Geneal Public License for more details.
+
+        You should have received a copy of the GNU General Public License
+        along with this program.  If not, see
+        <http://www.gnu.org/licenses/>.
+        
+*******************************************************************************-->
+
+<launch>
+       <arg name="pause" default="true"/>
+       <arg name="gui" default="true"/>
+       <arg name="use_sim_time" default="true"/>
+       <arg name="d435" default="false"/>
+       <arg name="world" default ="empty.sdf"/>
+
+       <arg unless="$(var pause)" name="gz_pause" default="-r"/>
+       <arg if="$(var pause)" name="gz_pause" default=""/>
+               
+       <arg unless="$(var gui)" name="gz_gui" default="-s"/>
+       <arg if="$(var gui)" name="gz_gui" default=""/>
+
+       <include file="$(find-pkg-share ros_gz_sim)/launch/gz_sim.launch.py">
+               <arg name="gz_args" value="$(var gz_pause) $(var gz_gui) $(var world)"/>
+       </include>
+
+       <include file="$(find-pkg-share tatuira_description)/launch/tatuira.launch.xml">
+               <arg name="use_sim_time" value="$(var use_sim_time)"/>
+               <arg name="hardware" value="ignition"/>
+               <arg name="d435" value="$(var d435)"/>
+       </include>
+
+       <node name="tatuira_spawner" pkg="ros_gz_sim" exec="create" args="-topic robot_description -name tatuira"/>
+
+       <node name="gz_bridge" pkg="ros_gz_bridge" exec="parameter_bridge">
+               <param name="config_file" value="$(find-pkg-share tatuira_description)/config/gz_bridge.yaml"/>
+               <param name="use_sim_time" value="$(var use_sim_time)"/>
+       </node>
+</launch>
diff --git a/tatuira_description/urdf/d435.xacro b/tatuira_description/urdf/d435.xacro
new file mode 100644 (file)
index 0000000..eda5179
--- /dev/null
@@ -0,0 +1,82 @@
+<?xml version="1.0"?>
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+       <xacro:arg name="hardware" default="gazebo"/>
+       <xacro:property name="hardware" value="$(arg hardware)"/>
+
+       <xacro:arg name="d435" default="false"/>
+
+       <xacro:if value="$(arg d435)">
+               <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />
+               <xacro:sensor_d435 parent="awac_link">
+                       <origin xyz="0 0 0.175" rpy="0.0 0.0 ${pi/2}" />
+               </xacro:sensor_d435>
+
+               <link name="plugin_camera_link" />
+
+               <joint name="plugin_camera_joint" type="fixed">
+                       <parent link="camera_link"/>
+                       <child link="plugin_camera_link" />
+                       <origin xyz="0.0 0.0 0.0" rpy="${-pi/2} 0.0 ${-pi/2}" />
+               </joint>
+
+               <gazebo reference="camera_link">
+                       <sensor name="camera" type="depth">
+                       <!--sensor name="camera" type="depth_camera"-->
+                               <always_on>trun</always_on>
+                               <update_rate>15</update_rate> <!--or 6 or 30 -->
+                               <visualize>false</visualize>
+                               <triggered>false</triggered>
+                               <trigger_topic>trigger</trigger_topic>
+                               <topic>depth_camera</topic> <!-- This is only used by Gazebo Ignition -->
+                               <ignition_frame_id>camera_link</ignition_frame_id>
+                               <camera>
+                                       <horizontal_fov>1.309</horizontal_fov> <!--75 deg at 480p  or 87 deg at 720p-->
+                                       <image>
+                                               <width>640</width> <!--or 1280 -->
+                                               <height>480</height> <!--or 720 -->
+                                               <format>R8G8B8</format>
+                                               <!--format>R_FLOAT32</format-->
+                                       </image>
+                                       <clip>
+                                               <near>0.05</near>
+                                               <far>10</far>
+                                       </clip>
+                                       <noise>
+                                               <type>gaussian</type>
+                                               <mean>0.0</mean>
+                                               <stddev>0.02</stddev>
+                                       </noise>
+                               </camera>
+
+                               <!-- Gazebo Classic -->
+                               <xacro:if value="${hardware == 'gazebo'}">
+                                       <plugin name="camera_plugin" filename="libgazebo_ros_camera.so">
+                                               <baseline>0.05</baseline>  <!-- dist between sensors -->
+                                               <!-- Keep this zero, update_rate in the parent <sensor> tag 
+                                               will control the frame rate. -->
+                                               <update_rate>0.0</update_rate>
+                                               <camera_name>camera</camera_name>
+                                               <frame_name>camera_link</frame_name>
+                                               <hack_baseline>0.05</hack_baseline>
+                                               <!--P_cx>0.0</P_cx?
+                                               <P_cy>0.0</P_cy>
+                                               <P_fy>0.0</P_fy>
+                                               <Tx>0.0</Tx>
+                                               <Ty>0.0</Ty>
+                                               <rectification_matrix>1 0 0 0 1 0 0 0 1</rectification_matrix-->
+                                               <ros>
+                                                       <!--namespace>namespace</namespace-->
+                                                       <remapping>/camera/image_raw:=/camera/color/image_raw</remapping>
+                                                       <remapping>/camera/camera_info:=camera/color/camera_info</remapping>
+                                                       <remapping>/camera/depth/image_raw:=/camera/depth/image_raw</remapping>
+                                                       <remapping>/camera_depth/camera_info:=/camera/depth/camera_info</remapping>
+                                                       <remapping>/camera/points:=camera/depth/points</remapping>
+                                               </ros>
+                                               <!--pointCloudCutoff>0.175</pointCloudCutoff--> <!-- or 0.28 at 720p -->
+                                       </plugin>
+                               </xacro:if>
+                       </sensor>
+               </gazebo>
+       </xacro:if>
+</robot>
index 36399a9..6836671 100644 (file)
@@ -1,11 +1,25 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
+       <xacro:arg name="hardware" default="gazebo"/>
+       <xacro:property name="hardware" value="$(arg hardware)"/>
+
        <gazebo>
-               <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
-                       <robot_param>robot_description</robot_param>
-                       <robot_param_node>robot_state_publisher</robot_param_node>
-                       <parameters>$(find tatuira_description)/config/controller_manager.yaml</parameters>
-               </plugin>
+               <xacro:if value="${hardware == 'gazebo'}">
+                       <!-- Gazebo Classic -->
+                       <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
+                               <robot_param>robot_description</robot_param>
+                               <robot_param_node>robot_state_publisher</robot_param_node>
+                               <parameters>$(find tatuira_description)/config/controller_manager.yaml</parameters>
+                       </plugin>
+               </xacro:if>
+               <xacro:if value="${hardware == 'ignition'}">
+                       <!-- Gazebo Ignition -->
+                       <plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
+                               <robot_param>robot_description</robot_param>
+                               <robot_param_node>robot_state_publisher</robot_param_node>
+                               <parameters>$(find tatuira_description)/config/controller_manager.yaml</parameters>
+                       </plugin>
+               </xacro:if>
        </gazebo>
 </robot>
diff --git a/tatuira_description/urdf/ground_truth.xacro b/tatuira_description/urdf/ground_truth.xacro
new file mode 100644 (file)
index 0000000..271678a
--- /dev/null
@@ -0,0 +1,39 @@
+<?xml version="1.0"?>
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+       <xacro:arg name="hardware" default="gazebo"/>
+       <xacro:property name="hardware" value="$(arg hardware)"/>
+
+       <gazebo>
+               <!-- Gazebo Classic -->
+               <xacro:if value="${hardware == 'gazebo'}">
+                       <plugin name="gound_truth" filename="libgazebo_ros_p3d.so">
+                               <update_rate>100.0</update_rate>
+                               <body_name>origin_link</body_name>
+                               <ros>
+                                       <remapping>odom:=ground_truth</remapping>
+                               </ros>
+                               <gaussian_noise>0.0</gaussian_noise>
+                               <frame_name>world</frame_name>
+                               <xyz_offset>0 0 0</xyz_offset>
+                               <rpy_offset>0 0 ${pi/2}</rpy_offset>
+                       </plugin>
+               </xacro:if>
+               <!-- Gazebo Ignition -->
+               <xacro:if value="${hardware == 'ignition'}">
+                       <!-- Publish Ignition (not ROS!) topics -->
+                       <plugin filename="ignition-gazebo-pose-publisher-system" name="ignition::gazebo::systems::PosePublisher">
+                               <publish_model_pose>true</publish_model_pose>
+                               <publish_link_pose>false</publish_link_pose>
+                               <publish_sensor_pose>false</publish_sensor_pose>
+                               <publish_collision_pose>false</publish_collision_pose>
+                               <publish_visual_pose>false</publish_visual_pose>
+                               <publish_nested_model_pose>true</publish_nested_model_pose>
+                               <use_pose_vector_msg>true</use_pose_vector_msg>
+                               <update_frequency>100</update_frequency>
+                               <static_publisher>false</static_publisher>
+                               <static_update_frequency>100</static_update_frequency>
+                       </plugin>
+               </xacro:if>
+       </gazebo>
+</robot>
index 12128e5..ff6a85e 100644 (file)
@@ -1,10 +1,22 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
 
+       <xacro:arg name="hardware" default="gazebo"/>
+       <xacro:property name="hardware" value="$(arg hardware)"/>
+
        <ros2_control name="GazeboSystem" type="system">
-               <hardware>
-                       <plugin>gazebo_ros2_control/GazeboSystem</plugin>
-               </hardware>
+               <xacro:if value="${hardware == 'gazebo'}">
+                       <!-- Gazebo Classic -->
+                       <hardware>
+                               <plugin>gazebo_ros2_control/GazeboSystem</plugin>
+                       </hardware>
+               </xacro:if>
+               <xacro:if value="${hardware == 'ignition'}">
+                       <!-- Gazebo Ignition -->
+                       <hardware>
+                               <plugin>ign_ros2_control/IgnitionSystem</plugin>
+                       </hardware>
+               </xacro:if>
 
                <joint name="right_rim_joint">
                        <command_interface name="effort">
index f783f6d..602e718 100644 (file)
@@ -1,6 +1,9 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="tatuira">
 
+       <xacro:arg name="hardware" default="gazebo"/>
+       <xacro:property name="hardware" value="$(arg hardware)"/>
+
        <xacro:include filename="$(find tatuira_description)/urdf/back.urdf.xacro"/>
        <xacro:include filename="$(find tatuira_description)/urdf/front.urdf.xacro"/>
        <xacro:include filename="$(find tatuira_description)/urdf/link_joint.urdf.xacro"/>
        <xacro:include filename="ros2_control.xacro"/>
        <xacro:include filename="gazebo_control.xacro"/>
 
-       <gazebo>
-               <plugin name="gound_truth" filename="libgazebo_ros_p3d.so">
-                       <update_rate>100.0</update_rate>
-                       <body_name>origin_link</body_name>
-                       <ros>
-                               <remapping>odom:=ground_truth</remapping>
-                       </ros>
-                       <gaussian_noise>0.0</gaussian_noise>
-                       <frame_name>world</frame_name>
-                       <xyz_offset>0 0 0</xyz_offset>
-                       <rpy_offset>0 0 ${pi/2}</rpy_offset>
-               </plugin>
-       </gazebo>
-       
-       <xacro:if value="$(arg d435)">
-               <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />
-               <xacro:sensor_d435 parent="awac_link">
-               <origin xyz="0 0 0.175" rpy="0.0 0.0 ${pi/2}" />
-               </xacro:sensor_d435>
-
-               <link name="plugin_camera_link" />
-
-               <joint name="plugin_camera_joint" type="fixed">
-                       <parent link="camera_link"/>
-                       <child link="plugin_camera_link" />
-                       <origin xyz="0.0 0.0 0.0" rpy="${-pi/2} 0.0 ${-pi/2}" />
-               </joint>
-
-               <gazebo reference="camera_link">
-                       <sensor name="camera" type="depth">
-                               <update_rate>15</update_rate> <!--or 6 or 30 -->
-                               <camera>
-                                       <horizontal_fov>1.309</horizontal_fov> <!--75 deg at 480p  or 87 deg at 720p-->
-                                       <image>
-                                               <width>640</width> <!--or 1280 -->
-                                               <height>480</height> <!--or 720 -->
-                                               <format>R8G8B8</format>
-                                       </image>
-                                       <clip>
-                                               <near>0.05</near>
-                                               <far>10</far>
-                                       </clip>
-                                       <noise>
-                                               <type>gaussian</type>
-                                               <mean>0.0</mean>
-                                               <stddev>0.02</stddev>
-                                       </noise>
-                               </camera>
-
-                               <plugin name="camera_plugin" filename="libgazebo_ros_openni_kinect.so">
-                                       <baseline>0.05</baseline>  <!-- dist between sensors -->
-                                       <alwaysOn>true</alwaysOn>
-                                       <!-- Keep this zero, update_rate in the parent <sensor> tag 
-                                       will control the frame rate. -->
-                                       <updateRate>0.0</updateRate>
-                                       <cameraName>camera</cameraName>
-                                       <imageTopicName>/camera/color/image_raw</imageTopicName>
-                                       <cameraInfoTopicName>/camera/color/camera_info</cameraInfoTopicName>
-                                       <depthImageTopicName>/camera/depth/image_raw</depthImageTopicName>
-                                       <depthImageInfoTopicName>/camera/depth/camera_info</depthImageInfoTopicName>
-                                       <pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
-                                       <frameName>plugin_camera_link</frameName>
-                                       <pointCloudCutoff>0.175</pointCloudCutoff> <!-- or 0.28 at 720p -->
-                                       <pointCloudCutoffMax>10.0</pointCloudCutoffMax>
-                                       <distortionK1>0</distortionK1>
-                                       <distortionK2>0</distortionK2>
-                                       <distortionK3>0</distortionK3>
-                                       <distortionT1>0</distortionT1>
-                                       <distortionT2>0</distortionT2>
-                                       <CxPrime>0</CxPrime>
-                                       <Cx>0</Cx>
-                                       <Cy>0</Cy>
-                                       <focalLength>0</focalLength>
-                                       <hackBaseline>0</hackBaseline>
-                               </plugin>
-                       </sensor>
-               </gazebo>
-       </xacro:if>
+       <xacro:include filename="ground_truth.xacro"/>
 
+       <xacro:include filename="d435.xacro"/>
 </robot>
index b0053dc..fa23d35 100644 (file)
        <arg name="pause" default="true"/>
        <arg name="gui" default="true"/>
        <arg name="use_sim_time" default="true"/>
+       <arg name="ignition" default="false"/>
 
        <include file="$(find-pkg-share tatuira_bringup)/launch/gazebo.launch.xml">
                <arg name="pause" value="$(var pause)"/>
                <arg name="gui" value="$(var gui)"/>
                <arg name="use_sim_time" value="$(var use_sim_time)"/>
                <arg name="controller" value="bypass"/>
+               <arg name="ignition" value="$(var ignition)"/>
        </include>
 
        <include file="$(find-pkg-share tatuira_ident)/launch/ident.launch.xml">