turtlebot/turtlebot4_simulator

Cannot add VLP-16 to Turtlebot4 Simulator

Closed this issue · 7 comments

Please provide the following information:

  • OS: Ubuntu 22.04
  • ROS Distro: Humble
  • Built from source or installed:
  • Package version: [c27f15d (https://github.com/turtlebot/turtlebot4_simulator/commit/c27f15d4e0c612efb799ac81e398137c5f9b154c)

Expected behaviour
I tried adding VLP-16 to the urdf in turtlebot4_description from the repo (https://bitbucket.org/DataspeedInc/velodyne_simulator.git) which works in gazebo by itself. The resulting URDF is:

<?xml version="1.0" ?>
<robot name="turtlebot4" xmlns:xacro="http://ros.org/wiki/xacro">
  <!-- Base create3 model -->
  <xacro:include filename="$(find irobot_create_description)/urdf/create3.urdf.xacro" />
  <xacro:include filename="$(find turtlebot4_description)/urdf/sensors/rplidar.urdf.xacro" />
  <xacro:include filename="$(find turtlebot4_description)/urdf/sensors/oakd.urdf.xacro" />
  <xacro:include filename="$(find turtlebot4_description)/urdf/sensors/camera_bracket.urdf.xacro" />
  <xacro:include filename="$(find velodyne_description)/urdf/VLP-16.urdf.xacro" />


  <!-- Mechanical properties -->
  <xacro:property name="rplidar_x_offset"              value="${0.393584*cm2m}"/>
  <xacro:property name="rplidar_y_offset"              value="${0*cm2m}"/>
  <xacro:property name="rplidar_z_offset"              value="${7.529272*cm2m}"/>

  <xacro:property name="camera_mount_x_offset"         value="${-9*cm2m}"/>
  <xacro:property name="camera_mount_y_offset"         value="${0*cm2m}"/>
  <xacro:property name="camera_mount_z_offset"         value="${2.914772*cm2m}"/>

  <xacro:property name="oakd_lite_x_offset"             value="${5.294026*cm2m}"/>
  <xacro:property name="oakd_lite_y_offset"             value="${0*cm2m}"/>
  <xacro:property name="oakd_lite_z_offset"             value="${9.25385*cm2m}"/>
  
  <xacro:property name="vlp16_x_offset"             value="${5.294026*cm2m}"/>
  <xacro:property name="vlp16_y_offset"             value="${0*cm2m}"/>
  <xacro:property name="vlp16_z_offset"             value="${10.25385*cm2m}"/>

  <!-- Turtlebot4 sensor definitions -->

  <xacro:rplidar name="rplidar" parent_link="base_link" gazebo="$(arg gazebo)">
    <origin xyz="${rplidar_x_offset} ${rplidar_y_offset} ${rplidar_z_offset + base_link_z_offset}"
            rpy="0 0 ${pi/2}"/>
  </xacro:rplidar>
  
  <xacro:camera_bracket name="oakd_camera_bracket" parent_link="base_link">
    <origin xyz="${camera_mount_x_offset} ${camera_mount_y_offset} ${camera_mount_z_offset + base_link_z_offset}"/>
  </xacro:camera_bracket>

  <xacro:oakd model="lite" parent_link="oakd_camera_bracket">
    <origin xyz="${oakd_lite_x_offset} ${oakd_lite_y_offset} ${oakd_lite_z_offset}"/>
  </xacro:oakd>

  <xacro:VLP-16>
    <origin xyz="${vlp16_x_offset} ${vlp16_y_offset} ${vlp16_z_offset}"/>
  </xacro:VLP-16>

  <xacro:VLP-16 parent="base_link" name="velodyne" topic="/velodyne_points" organize_cloud="false" hz="10" samples="440" gpu="false">
    <origin xyz="${vlp16_x_offset} ${vlp16_y_offset} ${vlp16_z_offset}" rpy="0 0 0" />
  </xacro:VLP-16>
</robot>

Actual behaviour
The robot does not spawn in Ignition Gazebo and here is what it shows:

[spawner-42] [ERROR] [1689259153.405254391] [spawner_diffdrive_controller]: Controller manager not available
[create-7] [INFO] [1689259153.551385455] [ros_gz_sim]: Waiting messages on topic [robot_description].
[ERROR] [spawner-42]: process has died [pid 175739, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner diffdrive_controller -c controller_manager --ros-args -r __ns:=/ --params-file /opt/ros/humble/share/irobot_create_control/config/control.yaml'].

Other notes
Is there anything wrong I am doing? Is there a guide on adding links to turtlebot4 simulator?

Hi Yazan,

Can you please provide the full terminal output? (including how you are launching gazebo)

Hi @hilary-luo,
I am launching gazebo with the command below:
source ~/turtlebot4_ws/install/setup.bash ros2 launch turtlebot4_ignition_bringup turtlebot4_ignition.launch.py model:=lite

Also, the colcon workspace builds successfully.

here's the full terminal output of the launch:
[INFO] [launch]: All log files can be found below /home/rihanadm/.ros/log/2023-07-13-20-56-15-113600-innb02903-10265 [INFO] [launch]: Default logging verbosity is set to INFO ign_args is deprecated, migrate to gz_args! [INFO] [ruby $(which ign) gazebo-1]: process started with pid [10268] [INFO] [parameter_bridge-2]: process started with pid [10270] [INFO] [robot_state_publisher-3]: process started with pid [10273] [INFO] [joint_state_publisher-4]: process started with pid [10276] [INFO] [robot_state_publisher-5]: process started with pid [10278] [INFO] [static_transform_publisher-6]: process started with pid [10280] [INFO] [create-7]: process started with pid [10282] [INFO] [create-8]: process started with pid [10284] [INFO] [parameter_bridge-9]: process started with pid [10286] [INFO] [parameter_bridge-10]: process started with pid [10289] [INFO] [parameter_bridge-11]: process started with pid [10293] [INFO] [parameter_bridge-12]: process started with pid [10296] [INFO] [parameter_bridge-13]: process started with pid [10298] [INFO] [parameter_bridge-14]: process started with pid [10300] [INFO] [parameter_bridge-15]: process started with pid [10302] [INFO] [parameter_bridge-16]: process started with pid [10307] [INFO] [parameter_bridge-17]: process started with pid [10309] [INFO] [parameter_bridge-18]: process started with pid [10311] [INFO] [parameter_bridge-19]: process started with pid [10322] [INFO] [parameter_bridge-20]: process started with pid [10348] [INFO] [parameter_bridge-21]: process started with pid [10366] [INFO] [parameter_bridge-22]: process started with pid [10387] [INFO] [parameter_bridge-23]: process started with pid [10425] [INFO] [parameter_bridge-24]: process started with pid [10472] [INFO] [parameter_bridge-25]: process started with pid [10493] [INFO] [parameter_bridge-26]: process started with pid [10506] [INFO] [turtlebot4_node-27]: process started with pid [10515] [INFO] [spawner-28]: process started with pid [10520] [INFO] [hazards_vector_publisher-29]: process started with pid [10542] [INFO] [ir_intensity_vector_publisher-30]: process started with pid [10564] [INFO] [motion_control-31]: process started with pid [10582] [INFO] [wheel_status_publisher-32]: process started with pid [10584] [INFO] [mock_publisher-33]: process started with pid [10599] [INFO] [robot_state-34]: process started with pid [10628] [INFO] [kidnap_estimator_publisher-35]: process started with pid [10650] [INFO] [ui_mgr-36]: process started with pid [10659] [INFO] [pose_republisher_node-37]: process started with pid [10663] [INFO] [sensors_node-38]: process started with pid [10676] [INFO] [interface_buttons_node-39]: process started with pid [10681] [INFO] [static_transform_publisher-40]: process started with pid [10684] [INFO] [static_transform_publisher-41]: process started with pid [10688] [parameter_bridge-2] [INFO] [1689274577.696489977] [clock_bridge]: Creating GZ->ROS Bridge: [/clock (ignition.msgs.Clock) -> /clock (rosgraph_msgs/msg/Clock)] (Lazy 0) [robot_state_publisher-3] Error: link 'velodyne_base_link' is not unique. [robot_state_publisher-3] at line 178 in ./urdf_parser/src/model.cpp [robot_state_publisher-3] Failed to parse robot description using: urdf_xml_parser/URDFXMLParser [robot_state_publisher-3] terminate called after throwing an instance of 'std::runtime_error' [robot_state_publisher-3] what(): Unable to initialize urdf::model from robot description [robot_state_publisher-5] [WARN] [1689274577.633940852] [kdl_parser]: The root link std_dock_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [robot_state_publisher-5] [INFO] [1689274577.634086807] [dock_state_publisher]: got segment green_buoy_link [robot_state_publisher-5] [INFO] [1689274577.634153632] [dock_state_publisher]: got segment halo_link [robot_state_publisher-5] [INFO] [1689274577.634165180] [dock_state_publisher]: got segment red_buoy_link [robot_state_publisher-5] [INFO] [1689274577.634172815] [dock_state_publisher]: got segment std_dock_link [robot_state_publisher-5] [INFO] [1689274577.634180190] [dock_state_publisher]: got segment yellow_buoy_link [static_transform_publisher-6] [WARN] [1689274577.502713175] []: Old-style arguments are deprecated; see --help for new-style arguments [static_transform_publisher-6] [INFO] [1689274577.554278407] [tf_odom_std_dock_link_publisher]: Spinning until stopped - publishing transform [static_transform_publisher-6] translation: ('0.157000', '0.000000', '0.000000') [static_transform_publisher-6] rotation: ('0.000000', '0.000000', '1.000000', '0.000000') [static_transform_publisher-6] from 'odom' to 'std_dock_link' [create-7] [ros_ign_gazebo] is deprecated! Redirecting to use [ros_gz_sim] instead! [create-7] [create-7] [INFO] [1689274577.656479712] [ros_gz_sim]: Requesting list of world names. [create-8] [ros_ign_gazebo] is deprecated! Redirecting to use [ros_gz_sim] instead! [create-8] [create-8] [INFO] [1689274577.662458397] [ros_gz_sim]: Requesting list of world names. [parameter_bridge-10] [INFO] [1689274577.726174174] [pose_bridge]: Creating GZ->ROS Bridge: [/model/turtlebot4/pose (ignition.msgs.Pose_V) -> /model/turtlebot4/pose (tf2_msgs/msg/TFMessage)] (Lazy 0) [parameter_bridge-10] [INFO] [1689274577.738937068] [pose_bridge]: Creating GZ->ROS Bridge: [/model/standard_dock/pose (ignition.msgs.Pose_V) -> /model/standard_dock/pose (tf2_msgs/msg/TFMessage)] (Lazy 0) [parameter_bridge-11] [INFO] [1689274577.705801473] [odom_base_tf_bridge]: Creating GZ->ROS Bridge: [/model/turtlebot4/tf (ignition.msgs.Pose_V) -> /model/turtlebot4/tf (tf2_msgs/msg/TFMessage)] (Lazy 0) [parameter_bridge-12] [INFO] [1689274577.965465288] [bumper_contact_bridge]: Creating GZ->ROS Bridge: [/bumper_contact (ignition.msgs.Contacts) -> /bumper_contact (ros_gz_interfaces/msg/Contacts)] (Lazy 0) [parameter_bridge-13] [INFO] [1689274577.913732595] [cliff_front_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_front_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_front_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-14] [INFO] [1689274577.698919483] [cliff_front_right_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_front_right/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_front_right/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-15] [INFO] [1689274577.694750651] [cliff_side_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_side_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_side_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-16] [INFO] [1689274577.876800543] [cliff_side_right_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_side_right/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_side_right/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-17] [INFO] [1689274577.797945217] [ir_intensity_front_center_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_front_center_left/sensor/ir_intensity_front_center_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_front_center_left/sensor/ir_intensity_front_center_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-18] [INFO] [1689274577.741808706] [ir_intensity_front_center_right_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_front_center_right/sensor/ir_intensity_front_center_right/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_front_center_right/sensor/ir_intensity_front_center_right/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-22] [INFO] [1689274577.904854897] [ir_intensity_right_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_right/sensor/ir_intensity_right/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_right/sensor/ir_intensity_right/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [static_transform_publisher-40] [WARN] [1689274577.982066570] []: Old-style arguments are deprecated; see --help for new-style arguments [static_transform_publisher-41] [WARN] [1689274578.004139224] []: Old-style arguments are deprecated; see --help for new-style arguments [hazards_vector_publisher-29] [INFO] [1689274578.005464712] [hazards_vector_publisher]: Advertised topic: hazard_detection [hazards_vector_publisher-29] [INFO] [1689274578.007017893] [hazards_vector_publisher]: Subscription to topic: _internal/bumper/event [hazards_vector_publisher-29] [INFO] [1689274578.013939784] [hazards_vector_publisher]: Subscription to topic: _internal/cliff_front_left/event [hazards_vector_publisher-29] [INFO] [1689274578.025358138] [hazards_vector_publisher]: Subscription to topic: _internal/cliff_front_right/event [hazards_vector_publisher-29] [INFO] [1689274578.037142009] [hazards_vector_publisher]: Subscription to topic: _internal/cliff_side_left/event [parameter_bridge-20] [INFO] [1689274578.037495431] [ir_intensity_front_right_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_front_right/sensor/ir_intensity_front_right/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_front_right/sensor/ir_intensity_front_right/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-23] [INFO] [1689274578.039517921] [ir_intensity_side_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_side_left/sensor/ir_intensity_side_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_side_left/sensor/ir_intensity_side_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-9] [INFO] [1689274578.044283459] [cmd_vel_bridge]: Creating GZ->ROS Bridge: [/cmd_vel (ignition.msgs.Twist) -> /cmd_vel (geometry_msgs/msg/Twist)] (Lazy 0) [parameter_bridge-25] [INFO] [1689274578.062003396] [lidar_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/rplidar_link/sensor/rplidar/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/rplidar_link/sensor/rplidar/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [hazards_vector_publisher-29] [INFO] [1689274578.065813632] [hazards_vector_publisher]: Subscription to topic: _internal/cliff_side_right/event [hazards_vector_publisher-29] [INFO] [1689274578.076542295] [hazards_vector_publisher]: Subscription to topic: _internal/wheel_drop/left_wheel/event [hazards_vector_publisher-29] [INFO] [1689274578.081495888] [hazards_vector_publisher]: Subscription to topic: _internal/wheel_drop/right_wheel/event [hazards_vector_publisher-29] [INFO] [1689274578.081849360] [hazards_vector_publisher]: Subscription to topic: _internal/backup_limit [turtlebot4_node-27] [INFO] [1689274578.085487643] [turtlebot4_node]: Init Turtlebot4 Node Main [parameter_bridge-9] [INFO] [1689274578.094126307] [cmd_vel_bridge]: Creating ROS->GZ Bridge: [/model/turtlebot4/cmd_vel (geometry_msgs/msg/Twist) -> /model/turtlebot4/cmd_vel (ignition.msgs.Twist)] (Lazy 0) [mock_publisher-33] [INFO] [1689274578.157692076] [mock_publisher]: Advertised mocked topic: slip_status [ir_intensity_vector_publisher-30] [INFO] [1689274578.163513225] [ir_intensity_vector_publisher]: Advertised topic: ir_intensity [ir_intensity_vector_publisher-30] [INFO] [1689274578.164051002] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_front_center_left [ir_intensity_vector_publisher-30] [INFO] [1689274578.164313889] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_front_center_right [ir_intensity_vector_publisher-30] [INFO] [1689274578.164532595] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_front_left [ir_intensity_vector_publisher-30] [INFO] [1689274578.164732048] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_front_right [ir_intensity_vector_publisher-30] [INFO] [1689274578.164925833] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_left [ir_intensity_vector_publisher-30] [INFO] [1689274578.165134110] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_right [ir_intensity_vector_publisher-30] [INFO] [1689274578.165325046] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_side_left [parameter_bridge-26] [INFO] [1689274578.214824719] [camera_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/image (ignition.msgs.Image) -> /world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/image (sensor_msgs/msg/Image)] (Lazy 0) [parameter_bridge-19] [INFO] [1689274578.285086685] [ir_intensity_front_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_front_left/sensor/ir_intensity_front_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_front_left/sensor/ir_intensity_front_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-24] [INFO] [1689274578.301245286] [buttons_msg_bridge]: Creating GZ->ROS Bridge: [/create3_buttons (ignition.msgs.Int32) -> /create3_buttons (std_msgs/msg/Int32)] (Lazy 0) [robot_state-34] [INFO] [1689274578.312868697] [robot_state]: Advertised topic: battery_state [robot_state-34] [INFO] [1689274578.314148229] [robot_state]: Subscription to topic: dock_status [parameter_bridge-26] [INFO] [1689274578.330528731] [camera_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/depth_image (ignition.msgs.Image) -> /world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/depth_image (sensor_msgs/msg/Image)] (Lazy 0) [static_transform_publisher-41] [INFO] [1689274578.352971890] [camera_stf]: Spinning until stopped - publishing transform [static_transform_publisher-41] translation: ('0.000000', '0.000000', '0.000000') [static_transform_publisher-41] rotation: ('0.499952', '-0.500000', '0.500000', '0.500048') [static_transform_publisher-41] from 'oakd_rgb_camera_optical_frame' to 'turtlebot4/oakd_rgb_camera_frame/rgbd_camera' [ui_mgr-36] [INFO] [1689274578.361080956] [ui_mgr]: Subscription to topic: cmd_lightring [ui_mgr-36] [INFO] [1689274578.390749053] [ui_mgr]: Subscription to topic: cmd_audio [parameter_bridge-26] [INFO] [1689274578.397861219] [camera_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/points (ignition.msgs.PointCloudPacked) -> /world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/points (sensor_msgs/msg/PointCloud2)] (Lazy 0) [parameter_bridge-26] [INFO] [1689274578.401521664] [camera_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/camera_info (ignition.msgs.CameraInfo) -> /world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/camera_info (sensor_msgs/msg/CameraInfo)] (Lazy 0) [static_transform_publisher-40] [INFO] [1689274578.426736081] [rplidar_stf]: Spinning until stopped - publishing transform [static_transform_publisher-40] translation: ('0.000000', '0.000000', '0.000000') [static_transform_publisher-40] rotation: ('0.000000', '0.000000', '0.000000', '1.000000') [static_transform_publisher-40] from 'rplidar_link' to 'turtlebot4/rplidar_link/rplidar' [parameter_bridge-21] [INFO] [1689274578.448901347] [ir_intensity_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_left/sensor/ir_intensity_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_left/sensor/ir_intensity_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [robot_state-34] [INFO] [1689274578.458025113] [robot_state]: Advertised topic: stop_status [motion_control-31] [INFO] [1689274578.467462403] [motion_control]: Enabling REFLEX_BUMP [motion_control-31] [INFO] [1689274578.467755311] [motion_control]: Enabling REFLEX_CLIFF [motion_control-31] [INFO] [1689274578.468742616] [motion_control]: Enabling REFLEX_STUCK [motion_control-31] [INFO] [1689274578.469081885] [motion_control]: Enabling REFLEX_WHEEL_DROP [robot_state-34] [INFO] [1689274578.510092117] [robot_state]: Subscription to topic: odom [kidnap_estimator_publisher-35] [INFO] [1689274578.520335543] [kidnap_estimator_publisher]: Advertised topic: kidnap_status [wheel_status_publisher-32] [INFO] [1689274578.527854626] [wheel_status_publisher]: Advertised topic: wheel_vels [kidnap_estimator_publisher-35] [INFO] [1689274578.528292609] [kidnap_estimator_publisher]: Subscription to topic: hazard_detection [wheel_status_publisher-32] [INFO] [1689274578.571705753] [wheel_status_publisher]: Advertised topic: wheel_ticks [ERROR] [robot_state_publisher-3]: process has died [pid 10273, exit code -6, cmd '/opt/ros/humble/lib/robot_state_publisher/robot_state_publisher --ros-args -r __node:=robot_state_publisher -r __ns:=/ --params-file /tmp/launch_params_v79l5_h9 --params-file /tmp/launch_params_i5713c98 -r /tf:=tf -r /tf_static:=tf_static']. [turtlebot4_node-27] [INFO] [1689274578.986701817] [turtlebot4_node]: Buttons Init [turtlebot4_node-27] [INFO] [1689274579.033193589] [turtlebot4_node]: Turtlebot4 lite running. [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Warehouse�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/OpenRobotics/models/Warehouse�[0m�[1;33m�[0m [joint_state_publisher-4] [INFO] [1689274579.368272839] [joint_state_publisher]: Waiting for robot_description to be published on the robot_description topic... [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/pallet_box_mobile�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/pallet_box_mobile�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf_big�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf_big�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf_big�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf_big�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf_big�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf_big�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] qrc:/qml/StyleDialog.qml:112:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] qrc:/qml/StyleDialog.qml:105:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] qrc:/qml/StyleDialog.qml:98:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf_big�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf_big�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] qrc:qml/Main.qml:102:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] qrc:/qml/PluginMenu.qml:27:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf_big�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf_big�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/Gazebo/GazeboDrawer.qml:241:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/Gazebo/GazeboDrawer.qml:147:3: QML Dialog: Binding loop detected for property "implicitHeight"�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/Gazebo/GazeboDrawer.qml:147:3: QML Dialog: Binding loop detected for property "implicitHeight"�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/shelf�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Chair�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/OpenRobotics/models/Chair�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Chair�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/OpenRobotics/models/Chair�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/foldable_chair�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/OpenRobotics/models/foldable_chair�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/foldable_chair�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/OpenRobotics/models/foldable_chair�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Table�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/OpenRobotics/models/Table�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Artifact Proximity Detector�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/OpenRobotics/models/Artifact Proximity Detector�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [ign.cc:161] �[0m�[1;36mSubscribing to [�[0m�[1;36m/gazebo/starting_world�[0m�[1;36m].�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [ign.cc:163] �[0m�[1;36mWaiting for a world to be set from the GUI...�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mReceived world [�[0m�[1;32mwarehouse.sdf�[0m�[1;32m] from the GUI.�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [ign.cc:167] �[0m�[1;36mUnsubscribing from [�[0m�[1;36m/gazebo/starting_world�[0m�[1;36m].�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mIgnition Gazebo Server v�[0m�[1;32m6.14.0�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mLoading SDF world file[�[0m�[1;32m/home/rihanadm/turtlebot4_ws/install/turtlebot4_ignition_bringup/share/turtlebot4_ignition_bringup/worlds/warehouse.sdf�[0m�[1;32m].�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mServing entity system service on [�[0m�[1;32m/�[0m�[1;32mentity/system/add�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [Physics.cc:803] �[0m�[1;36mLoaded [�[0m�[1;36mignition::physics::dartsim::Plugin�[0m�[1;36m] from library [�[0m�[1;36m/usr/lib/x86_64-linux-gnu/ign-physics-5/engine-plugins/libignition-physics-dartsim-plugin.so�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SystemManager.cc:70] �[0m�[1;36mLoaded system [�[0m�[1;36mignition::gazebo::systems::Physics�[0m�[1;36m] for entity [�[0m�[1;36m1�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mCreate service on [�[0m�[1;32m/world/warehouse/create�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mRemove service on [�[0m�[1;32m/world/warehouse/remove�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mPose service on [�[0m�[1;32m/world/warehouse/set_pose�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mPose service on [�[0m�[1;32m/world/warehouse/set_pose_vector�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mLight configuration service on [�[0m�[1;32m/world/warehouse/light_config�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mPhysics service on [�[0m�[1;32m/world/warehouse/set_physics�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mSphericalCoordinates service on [�[0m�[1;32m/world/warehouse/set_spherical_coordinates�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mEnable collision service on [�[0m�[1;32m/world/warehouse/enable_collision�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mDisable collision service on [�[0m�[1;32m/world/warehouse/disable_collision�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mMaterial service on [�[0m�[1;32m/world/warehouse/visual_config�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mMaterial service on [�[0m�[1;32m/world/warehouse/wheel_slip�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SystemManager.cc:70] �[0m�[1;36mLoaded system [�[0m�[1;36mignition::gazebo::systems::UserCommands�[0m�[1;36m] for entity [�[0m�[1;36m1�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SystemManager.cc:70] �[0m�[1;36mLoaded system [�[0m�[1;36mignition::gazebo::systems::SceneBroadcaster�[0m�[1;36m] for entity [�[0m�[1;36m1�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SystemManager.cc:70] �[0m�[1;36mLoaded system [�[0m�[1;36mignition::gazebo::systems::PosePublisher�[0m�[1;36m] for entity [�[0m�[1;36m12�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mPerformerDetector publishing messages on �[0m�[1;32m[�[0m�[1;32m/subt_performer_detector�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SystemManager.cc:70] �[0m�[1;36mLoaded system [�[0m�[1;36mignition::gazebo::systems::PerformerDetector�[0m�[1;36m] for entity [�[0m�[1;36m141�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [Thermal.cc:112] �[0m�[1;36mThermal plugin, heat signature: using a minimum temperature of �[0m�[1;36m288.15�[0m�[1;36m kelvin, and a max temperature of �[0m�[1;36m305�[0m�[1;36m kelvin.�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SystemManager.cc:70] �[0m�[1;36mLoaded system [�[0m�[1;36mignition::gazebo::systems::Thermal�[0m�[1;36m] for entity [�[0m�[1;36m139�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mLoaded level [�[0m�[1;32m3�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mServing world controls on [�[0m�[1;32m/world/warehouse�[0m�[1;32m/control], [�[0m�[1;32m/world/warehouse�[0m�[1;32m/control/state] and [�[0m�[1;32m/world/warehouse�[0m�[1;32m/playback/control]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/openrobotics/models/chair/2/files/meshes/Chair.obj�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/openrobotics/models/chair/2/files/meshes/Chair.obj�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/openrobotics/models/chair/2/files/meshes/Chair.obj�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/openrobotics/models/chair/2/files/meshes/Chair.obj�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [OBJLoader.cc:91] �[0m�[1;33mBoth dandTrparameters defined for "Chair". Use the value ofd for dissolve (line 8 in .mtl.)�[0m [ruby $(which ign) gazebo-1] �[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Scene3D.cc:2941] �[0m�[1;33mThe GzScene3D plugin is deprecated on v6 and will be removed on �[0m�[1;33mv7. Use MinimalScene together with other plugins as needed.�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/GzScene3D/GzScene3D.qml:108:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/GzScene3D/GzScene3D.qml:63:5: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [create-7] [INFO] [1689274580.401324756] [ros_gz_sim]: Waiting messages on topic [robot_description]. [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/WorldControl/WorldControl.qml:30:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg]�[1;32m[Msg] �[0m�[1;32mIgnition Gazebo GUI v�[0m�[1;32m6.14.0�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [Gui.cc:253] �[0m�[1;36mWaiting for subscribers to [�[0m�[1;36m/gazebo/starting_world�[0m�[1;36m]...�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [Application.cc:92] �[0m�[1;36mInitializing application.�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[GUI] [Dbg] [Application.cc:555] �[0m�[1;36mCreate main window�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[GUI] [Dbg] [PathManager.cc:66] �[0m�[1;36mRequesting resource paths through [�[0m�[1;36m/gazebo/resource_paths/get�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[GUI] [Dbg] [Gui.cc:333] �[0m�[1;36mGUI requesting list of world names. The server may be busy �[0m�[1;36mdownloading resources. Please be patient.�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[GUI] [Dbg] [GuiRunner.cc:145] �[0m�[1;36mRequesting initial state from [�[0m�[1;36m/world/warehouse/state�[0m�[1;36m]...�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mLoading config [�[0m�[1;32m/home/rihanadm/turtlebot4_ws/install/turtlebot4_ignition_bringup/share/turtlebot4_ignition_bringup/gui/lite/gui.config�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;36m[GUI] [Dbg] [Application.cc:426] �[0m�[1;36mLoading plugin [�[0m�[1;36mGzScene3D�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mVideo recorder stats topic advertised on [�[0m�[1;32m/gui/record_video/stats�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mTransform mode service on [�[0m�[1;32m/gui/transform_mode�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mRecord video service on [�[0m�[1;32m/gui/record_video�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mMove to service on [�[0m�[1;32m/gui/move_to�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mFollow service on [�[0m�[1;32m/gui/follow�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mFollow offset service on [�[0m�[1;32m/gui/follow/offset�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mView angle service on [�[0m�[1;32m/gui/view_angle�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mMove to pose service on [�[0m�[1;32m/gui/move_to/pose�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mCamera pose topic advertised on [�[0m�[1;32m/gui/camera/pose�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mView as transparent service on [�[0m�[1;32m/gui/view/transparent�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mView center of mass service on [�[0m�[1;32m/gui/view/com�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mView inertia service on [�[0m�[1;32m/gui/view/inertia�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mView joints service on [�[0m�[1;32m/gui/view/joints�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mView wireframes service on [�[0m�[1;32m/gui/view/wireframes�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mView collisions service on [�[0m�[1;32m/gui/view/collisions�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mCamera view controller topic advertised on [�[0m�[1;32m/gui/camera/view_control�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mAdded plugin [�[0m�[1;32m3D View�[0m�[1;32m] to main window�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mLoaded plugin [�[0m�[1;32mGzScene3D�[0m�[1;32m] from path [�[0m�[1;32m/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/gui/libGzScene3D.so�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;36m[GUI] [Dbg] [Application.cc:426] �[0m�[1;36mLoading plugin [�[0m�[1;36mWorldControl�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mUsing world control service [�[0m�[1;32m/world/warehouse/control�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mListening to stats on [�[0m�[1;32m/world/warehouse/stats�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;36m[GUI] [Dbg] [WorldControl.cc:248] �[0m�[1;36mUsing a service to share WorldControl msgs with the server�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/TransformControl/TransformControl.qml:104:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/TransformControl/TransformControl.qml:99:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/TransformControl/TransformControl.qml:94:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/TransformControl/TransformControl.qml:89:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... }�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/Create3Hmi/Create3Hmi.qml:49:7: Unable to assign [undefined] to QString�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] QObject::connect: No such signal ignition::gui::Create3Hmi::AddMsg(QString)�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [Model.hh:69] �[0m�[1;33mSkipping serialization / deserialization for models [Wrn] [Model.hh:69] �[0m�[1;33mSkipping serialization / deserialization for models �[0m�[1;33mwith //pose/@relative_to attribute.�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [Model.hh:69] �[0m�[1;33mSkipping serialization / deserialization for models �[0m�[1;33mwith //pose/@relative_to attribute.�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [Model.hh:69] �[0m�[1;33mSkipping serialization / deserialization for models �[0m�[1;33mwith //pose/@relative_to attribute.�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [Model.hh:69] �[0m�[1;33mSkipping serialization / deserialization for models �[0m�[1;33mwith //pose/@relative_to attribute.�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [Component.hh:144] �[0m�[1;33mTrying to serialize component with data type [�[0m�[1;33mN3sdf3v125WorldE�[0m�[1;33m], which doesn't have �[0m�[1;33moperator<<. Component will not be serialized.�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [Model.hh:69] �[0m�[1;33mSkipping serialization / deserialization for models �[0m�[1;33mwith //pose/@relative_to attribute.�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33mSkipping serialization / deserialization for models �[0m�[1;33mwith //pose/@relative_to attribute.�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[Wrn] [Model.hh:69] �[0m�[1;33mSkipping serialization / deserialization for models �[0m�[1;33mwith //pose/@relative_to attribute.�[0m�[1;33m�[0m [create-8] [INFO] [1689274580.602898276] [ros_gz_sim]: Waiting messages on topic [standard_dock_description]. [create-8] [INFO] [1689274580.616642235] [ros_gz_sim]: Requested creation of entity. [create-8] [INFO] [1689274580.616686095] [ros_gz_sim]: OK creation of entity. [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Component.hh:189] �[0m�[1;33mTrying to deserialize component with data type [�[0m�[1;33mN3sdf3v125WorldE�[0m�[1;33m], which doesn't have �[0m�[1;33moperator>>. Component will not be deserialized.�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;32m[GUI] �[0m�[1;32m[Msg] �[0m�[1;32mAdded plugin [�[0m�[1;32mWorld control�[0m�[1;32m] to main �[0m�[1;32mServing GUI information on [�[0m�[1;32m/world/warehouse�[0m�[1;32m/�[0m�[1;32mgui/info�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mWorld [�[0m�[1;32mwarehouse�[0m�[1;32m] initialized with [�[0m�[1;32mdefault_physics�[0m�[1;32m] physics profile.�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mServing world SDF generation service on [�[0m�[1;32m/world/warehouse�[0m�[1;32m/�[0m�[1;32mgenerate_world_sdf�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mServing world names on [�[0m�[1;32m/gazebo/worlds�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mResource path add service on [�[0m�[1;32m/gazebo/resource_paths/add�[0m�[1;32m].�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mResource path get service on [�[0m�[1;32m/gazebo/resource_paths/get�[0m�[1;32m].�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mResource path resolve service on [�[0m�[1;32m/gazebo/resource_paths/resolve�[0m�[1;32m].�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mResource paths published on [�[0m�[1;32m/gazebo/resource_paths�[0m�[1;32m].�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mServer control service on [�[0m�[1;32m/server_control�[0m�[1;32m].�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mFound no publishers on /stats, adding root stats topic�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mFound no publishers on /clock, adding root clock topic�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SimulationRunner.cc:496] �[0m�[1;36mCreating PostUpdate worker threads: �[0m�[1;36m4�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SimulationRunner.cc:507] �[0m�[1;36mCreating postupdate worker thread (�[0m�[1;36m0�[0m�[1;36m)�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SimulationRunner.cc:507] �[0m�[1;36mCreating postupdate worker thread (�[0m�[1;36m1�[0m�[1;36m)�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SimulationRunner.cc:507] �[0m�[1;36mCreating postupdate worker thread (�[0m�[1;36m2�[0m�[1;36m)�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mServing scene information on [�[0m�[1;32m/world/warehouse�[0m�[1;32m/�[0m�[1;32mscene/info�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mServing graph information on [�[0m�[1;32m/world/warehouse�[0m�[1;32m/�[0m�[1;32mscene/graph�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mServing full state on [�[0m�[1;32m/world/warehouse�[0m�[1;32m/�[0m�[1;32mstate�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mServing full state (async) on [�[0m�[1;32m/world/warehouse�[0m�[1;32m/�[0m�[1;32mstate_async�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mPublishing scene information on [�[0m�[1;32m/world/warehouse/scene/info�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mPublishing entity deletions on [�[0m�[1;32m/world/warehouse/scene/deletion�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mPublishing state changes on [�[0m�[1;32m/world/warehouse/state�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mPublishing pose messages on [�[0m�[1;32m/world/warehouse�[0m�[1;32m/�[0m�[1;32mpose/info�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;32m[Msg] �[0m�[1;32mPublishing dynamic pose messages on [�[0m�[1;32m/world/warehouse�[0m�[1;32m/�[0m�[1;32mdynamic_pose/info�[0m�[1;32m]�[0m�[1;32m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [EntityComponentManager.cc:1587] �[0m�[1;36mUpdated state thread iterators: �[0m�[1;36m8�[0m�[1;36m threads processing around �[0m�[1;36m19�[0m�[1;36m entities each.�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SystemManager.cc:70] �[0m�[1;36mLoaded system [�[0m�[1;36mignition::gazebo::systems::PosePublisher�[0m�[1;36m] for entity [�[0m�[1;36m150�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [UserCommands.cc:1303] �[0m�[1;36mCreated entity [�[0m�[1;36m150�[0m�[1;36m] named [�[0m�[1;36mstandard_dock�[0m�[1;36m]�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SimulationRunner.cc:523] �[0m�[1;36mExiting postupdate worker thread (�[0m�[1;36m0�[0m�[1;36m)[Dbg] [SimulationRunner.cc:523] �[0m�[1;36mExiting postupdate worker thread (�[0m�[1;36m1�[0m�[1;36m)�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m)�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SimulationRunner.cc:523] �[0m�[1;36mExiting postupdate worker thread (�[0m�[1;36m2�[0m�[1;36m)�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;36m[Dbg] [SimulationRunner.cc:496] �[0m�[1;36mCreating PostUpdate worker threads: �[0m�[1;36m5�[0m�[1;36m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [INFO] [create-8]: process has finished cleanly [pid 10284] [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [spawner-28] [INFO] [1689274581.256162742] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' node to exist [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [create-7] [INFO] [1689274581.401454867] [ros_gz_sim]: Waiting messages on topic [robot_description]. [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Model.hh:98] �[0m�[1;33mUnable to deserialize sdf::Model�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/WorldStats/WorldStats.qml:53:3: QML RowLayout: Binding loop detected for property "x"�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] libEGL warning: egl: failed to create dri2 screen [ruby $(which ign) gazebo-1] libEGL warning: egl: failed to create dri2 screen [create-7] [INFO] [1689274582.401602951] [ros_gz_sim]: Waiting messages on topic [robot_description]. [ruby $(which ign) gazebo-1] �[1;31m[GUI] [Err] [Ogre2Camera.cc:390] �[0m�[1;31mOgre2Camera::SetVisibilityMask: Mask bits �[0m�[1;31mc0000000�[0m�[1;31m are set but will be ignored by ogre2 backend.�[0m�[1;31m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/pallet/tip/files/meshes/pallet.dae�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/pallet/tip/files/meshes/pallet.dae�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/MovAi/models/pallet/tip/files/meshes/pallet.dae�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/MovAi/models/pallet/tip/files/meshes/pallet.dae�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/movai/models/pallet_box_mobile/3/files/meshes/boxes.dae�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/movai/models/pallet_box_mobile/3/files/meshes/boxes.dae�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/movai/models/pallet_box_mobile/3/files/meshes/boxes.dae�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/movai/models/pallet_box_mobile/3/files/meshes/boxes.dae�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/openrobotics/models/chair/2/files/meshes/Chair.obj�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/openrobotics/models/chair/2/files/meshes/Chair.obj�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/openrobotics/models/chair/2/files/meshes/Chair.obj�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/openrobotics/models/chair/2/files/meshes/Chair.obj�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [OBJLoader.cc:91] �[0m�[1;33mBoth dandTrparameters defined for "Chair". Use the value ofd for dissolve (line 8 in .mtl.)�[0m [ruby $(which ign) gazebo-1] �[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/openrobotics/models/table/3/files/Table_Diffuse.jpg�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/openrobotics/models/table/3/files/Table_Diffuse.jpg�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [FuelClient.cc:1978] �[0m�[1;33mThe �[0m�[1;33mfuel.ignitionrobotics.org�[0m�[1;33m URL is deprecrated. Pleasse change �[0m�[1;33mhttps://fuel.ignitionrobotics.org/1.0/openrobotics/models/table/3/files/Table_Diffuse.jpg�[0m�[1;33m to �[0m�[1;33mhttps://fuel.gazebosim.org/1.0/openrobotics/models/table/3/files/Table_Diffuse.jpg�[0m�[1;33m�[0m [spawner-28] [INFO] [1689274583.265213910] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' node to exist [create-7] [INFO] [1689274583.401810149] [ros_gz_sim]: Waiting messages on topic [robot_description]. [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [ColladaLoader.cc:2394] �[0m�[1;33mTriangle input semantic: '�[0m�[1;33mCOLOR�[0m�[1;33m' is currently�[0m�[1;33m not supported�[0m�[1;33m�[0m [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [ColladaLoader.cc:2394] �[0m�[1;33mTriangle input semantic: '�[0m�[1;33mCOLOR�[0m�[1;33m' is currently�[0m�[1;33m not supported�[0m�[1;33m�[0m [create-7] [INFO] [1689274584.401943757] [ros_gz_sim]: Waiting messages on topic [robot_description]. [spawner-28] [INFO] [1689274585.273267585] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' node to exist [create-7] [INFO] [1689274585.402101011] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274586.402241157] [ros_gz_sim]: Waiting messages on topic [robot_description]. [spawner-28] [INFO] [1689274587.282243087] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' node to exist [ruby $(which ign) gazebo-1] �[1;33m[GUI] [Wrn] [Application.cc:797] �[0m�[1;33m[QT] file::/Gazebo/GazeboDrawer.qml:147:3: QML Dialog: Binding loop detected for property "implicitHeight"�[0m�[1;33m�[0m [create-7] [INFO] [1689274587.402375619] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274588.402513665] [ros_gz_sim]: Waiting messages on topic [robot_description]. [spawner-28] [ERROR] [1689274589.290727487] [spawner_joint_state_broadcaster]: Controller manager not available [create-7] [INFO] [1689274589.402692603] [ros_gz_sim]: Waiting messages on topic [robot_description]. [ERROR] [spawner-28]: process has died [pid 10520, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner joint_state_broadcaster -c controller_manager --ros-args -r __ns:=/']. [INFO] [spawner-42]: process started with pid [11020] [create-7] [INFO] [1689274590.402836133] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274591.403010100] [ros_gz_sim]: Waiting messages on topic [robot_description]. [spawner-42] [INFO] [1689274592.230988563] [spawner_diffdrive_controller]: Waiting for '/controller_manager' node to exist [create-7] [INFO] [1689274592.403151597] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274593.403303900] [ros_gz_sim]: Waiting messages on topic [robot_description]. [spawner-42] [INFO] [1689274594.239927482] [spawner_diffdrive_controller]: Waiting for '/controller_manager' node to exist [create-7] [INFO] [1689274594.403459740] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274595.403638109] [ros_gz_sim]: Waiting messages on topic [robot_description]. [spawner-42] [INFO] [1689274596.249587973] [spawner_diffdrive_controller]: Waiting for '/controller_manager' node to exist [create-7] [INFO] [1689274596.403770585] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274597.403915497] [ros_gz_sim]: Waiting messages on topic [robot_description]. [spawner-42] [INFO] [1689274598.258167592] [spawner_diffdrive_controller]: Waiting for '/controller_manager' node to exist [create-7] [INFO] [1689274598.404083908] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274599.404259565] [ros_gz_sim]: Waiting messages on topic [robot_description]. [spawner-42] [ERROR] [1689274600.267121335] [spawner_diffdrive_controller]: Controller manager not available [create-7] [INFO] [1689274600.404402166] [ros_gz_sim]: Waiting messages on topic [robot_description]. [ERROR] [spawner-42]: process has died [pid 11020, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner diffdrive_controller -c controller_manager --ros-args -r __ns:=/ --params-file /opt/ros/humble/share/irobot_create_control/config/control.yaml']. [create-7] [INFO] [1689274601.404562024] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274602.404730960] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274603.404859619] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274604.405014316] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274605.405185899] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274606.405331470] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274607.405453471] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274608.405604976] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274609.405741371] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274610.405875203] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274611.406012467] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274612.406175506] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274613.406325874] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274614.406495224] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274615.406649437] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274616.406832518] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274617.406990248] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274618.407163332] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274619.407308855] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274620.407491246] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274621.407632012] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274622.407814010] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274623.408007961] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274624.408172103] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274625.408380274] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274626.408550108] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274627.408721136] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274628.408960214] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274629.409141454] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274630.409292826] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274631.409460116] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274632.409619717] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274633.409791330] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274634.409950312] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274635.410122500] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274636.410252204] [ros_gz_sim]: Waiting messages on topic [robot_description]. [create-7] [INFO] [1689274637.410390601] [ros_gz_sim]: Waiting messages on topic [robot_description].

And here is the log file from ~/.ros:
1689274575.1148376 [INFO] [launch]: All log files can be found below /home/rihanadm/.ros/log/2023-07-13-20-56-15-113600-innb02903-10265 1689274575.1149635 [INFO] [launch]: Default logging verbosity is set to INFO 1689274577.9897318 [INFO] [ruby $(which ign) gazebo-1]: process started with pid [10268] 1689274577.9924200 [INFO] [parameter_bridge-2]: process started with pid [10270] 1689274577.9926167 [INFO] [robot_state_publisher-3]: process started with pid [10273] 1689274577.9927480 [INFO] [joint_state_publisher-4]: process started with pid [10276] 1689274577.9928813 [INFO] [robot_state_publisher-5]: process started with pid [10278] 1689274577.9929922 [INFO] [static_transform_publisher-6]: process started with pid [10280] 1689274577.9930983 [INFO] [create-7]: process started with pid [10282] 1689274577.9932075 [INFO] [create-8]: process started with pid [10284] 1689274577.9933195 [INFO] [parameter_bridge-9]: process started with pid [10286] 1689274577.9934583 [INFO] [parameter_bridge-10]: process started with pid [10289] 1689274577.9935713 [INFO] [parameter_bridge-11]: process started with pid [10293] 1689274577.9936817 [INFO] [parameter_bridge-12]: process started with pid [10296] 1689274577.9937871 [INFO] [parameter_bridge-13]: process started with pid [10298] 1689274577.9938979 [INFO] [parameter_bridge-14]: process started with pid [10300] 1689274577.9940057 [INFO] [parameter_bridge-15]: process started with pid [10302] 1689274577.9941142 [INFO] [parameter_bridge-16]: process started with pid [10307] 1689274577.9943130 [INFO] [parameter_bridge-17]: process started with pid [10309] 1689274577.9944458 [INFO] [parameter_bridge-18]: process started with pid [10311] 1689274577.9945185 [INFO] [parameter_bridge-19]: process started with pid [10322] 1689274577.9945843 [INFO] [parameter_bridge-20]: process started with pid [10348] 1689274577.9946494 [INFO] [parameter_bridge-21]: process started with pid [10366] 1689274577.9947116 [INFO] [parameter_bridge-22]: process started with pid [10387] 1689274577.9947739 [INFO] [parameter_bridge-23]: process started with pid [10425] 1689274577.9948359 [INFO] [parameter_bridge-24]: process started with pid [10472] 1689274577.9948988 [INFO] [parameter_bridge-25]: process started with pid [10493] 1689274577.9949622 [INFO] [parameter_bridge-26]: process started with pid [10506] 1689274577.9950230 [INFO] [turtlebot4_node-27]: process started with pid [10515] 1689274577.9950871 [INFO] [spawner-28]: process started with pid [10520] 1689274577.9951522 [INFO] [hazards_vector_publisher-29]: process started with pid [10542] 1689274577.9952343 [INFO] [ir_intensity_vector_publisher-30]: process started with pid [10564] 1689274577.9953365 [INFO] [motion_control-31]: process started with pid [10582] 1689274577.9954443 [INFO] [wheel_status_publisher-32]: process started with pid [10584] 1689274577.9955487 [INFO] [mock_publisher-33]: process started with pid [10599] 1689274577.9956565 [INFO] [robot_state-34]: process started with pid [10628] 1689274577.9957569 [INFO] [kidnap_estimator_publisher-35]: process started with pid [10650] 1689274577.9958553 [INFO] [ui_mgr-36]: process started with pid [10659] 1689274577.9959888 [INFO] [pose_republisher_node-37]: process started with pid [10663] 1689274577.9960947 [INFO] [sensors_node-38]: process started with pid [10676] 1689274577.9962032 [INFO] [interface_buttons_node-39]: process started with pid [10681] 1689274577.9963093 [INFO] [static_transform_publisher-40]: process started with pid [10684] 1689274577.9964278 [INFO] [static_transform_publisher-41]: process started with pid [10688] 1689274578.8228681 [ERROR] [robot_state_publisher-3]: process has died [pid 10273, exit code -6, cmd '/opt/ros/humble/lib/robot_state_publisher/robot_state_publisher --ros-args -r __node:=robot_state_publisher -r __ns:=/ --params-file /tmp/launch_params_v79l5_h9 --params-file /tmp/launch_params_i5713c98 -r /tf:=tf -r /tf_static:=tf_static']. 1689274580.7482462 [INFO] [create-8]: process has finished cleanly [pid 10284] 1689274589.4567237 [ERROR] [spawner-28]: process has died [pid 10520, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner joint_state_broadcaster -c controller_manager --ros-args -r __ns:=/']. 1689274589.4599102 [INFO] [spawner-42]: process started with pid [11020] 1689274600.4230089 [ERROR] [spawner-42]: process has died [pid 11020, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner diffdrive_controller -c controller_manager --ros-args -r __ns:=/ --params-file /opt/ros/humble/share/irobot_create_control/config/control.yaml']. 1689274638.0476348 [WARNING] [launch]: user interrupted with ctrl-c (SIGINT) 1689274638.2346888 [INFO] [mock_publisher-33]: process has finished cleanly [pid 10599] 1689274638.2349067 [INFO] [wheel_status_publisher-32]: process has finished cleanly [pid 10584] 1689274638.2370915 [INFO] [ir_intensity_vector_publisher-30]: process has finished cleanly [pid 10564] 1689274638.2432039 [INFO] [create-7]: process has finished cleanly [pid 10282] 1689274638.2455184 [INFO] [static_transform_publisher-40]: process has finished cleanly [pid 10684] 1689274638.2457147 [INFO] [static_transform_publisher-6]: process has finished cleanly [pid 10280] 1689274638.2458022 [INFO] [static_transform_publisher-41]: process has finished cleanly [pid 10688] 1689274638.2480791 [INFO] [interface_buttons_node-39]: process has finished cleanly [pid 10681] 1689274638.2499673 [INFO] [pose_republisher_node-37]: process has finished cleanly [pid 10663] 1689274638.2501376 [INFO] [ui_mgr-36]: process has finished cleanly [pid 10659] 1689274638.2502370 [INFO] [robot_state-34]: process has finished cleanly [pid 10628] 1689274638.2503209 [INFO] [kidnap_estimator_publisher-35]: process has finished cleanly [pid 10650] 1689274638.2522249 [INFO] [hazards_vector_publisher-29]: process has finished cleanly [pid 10542] 1689274638.2530448 [INFO] [robot_state_publisher-5]: process has finished cleanly [pid 10278] 1689274638.3006778 [INFO] [sensors_node-38]: process has finished cleanly [pid 10676] 1689274638.3058879 [INFO] [turtlebot4_node-27]: process has finished cleanly [pid 10515] 1689274638.3188808 [INFO] [motion_control-31]: process has finished cleanly [pid 10582] 1689274638.3795829 [ERROR] [joint_state_publisher-4]: process has died [pid 10276, exit code 1, cmd '/opt/ros/humble/lib/joint_state_publisher/joint_state_publisher --ros-args -r __node:=joint_state_publisher -r __ns:=/ --params-file /tmp/launch_params_7evyhb4h -r /tf:=tf -r /tf_static:=tf_static']. 1689274638.3829067 [ERROR] [ruby $(which ign) gazebo-1]: process has died [pid 10268, exit code -2, cmd 'ruby $(which ign) gazebo warehouse.sdf -v 4 --gui-config /home/rihanadm/turtlebot4_ws/install/turtlebot4_ignition_bringup/share/turtlebot4_ignition_bringup/gui/lite/gui.config --force-version 6']. 1689274643.0948062 [ERROR] [parameter_bridge-26]: process[parameter_bridge-26] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.0958385 [ERROR] [parameter_bridge-25]: process[parameter_bridge-25] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.0966098 [ERROR] [parameter_bridge-24]: process[parameter_bridge-24] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.0972619 [ERROR] [parameter_bridge-23]: process[parameter_bridge-23] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.0978830 [ERROR] [parameter_bridge-22]: process[parameter_bridge-22] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.0984960 [ERROR] [parameter_bridge-21]: process[parameter_bridge-21] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.0991356 [ERROR] [parameter_bridge-20]: process[parameter_bridge-20] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.0996881 [ERROR] [parameter_bridge-19]: process[parameter_bridge-19] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1002042 [ERROR] [parameter_bridge-18]: process[parameter_bridge-18] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1025400 [INFO] [parameter_bridge-26]: sending signal 'SIGTERM' to process[parameter_bridge-26] 1689274643.1108925 [INFO] [parameter_bridge-25]: sending signal 'SIGTERM' to process[parameter_bridge-25] 1689274643.1168296 [ERROR] [parameter_bridge-17]: process[parameter_bridge-17] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1175711 [ERROR] [parameter_bridge-16]: process[parameter_bridge-16] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1183054 [ERROR] [parameter_bridge-15]: process[parameter_bridge-15] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1194861 [ERROR] [parameter_bridge-14]: process[parameter_bridge-14] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1201577 [ERROR] [parameter_bridge-13]: process[parameter_bridge-13] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1207378 [ERROR] [parameter_bridge-12]: process[parameter_bridge-12] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1212747 [ERROR] [parameter_bridge-11]: process[parameter_bridge-11] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1217847 [ERROR] [parameter_bridge-10]: process[parameter_bridge-10] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1223438 [ERROR] [parameter_bridge-9]: process[parameter_bridge-9] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1230037 [ERROR] [parameter_bridge-2]: process[parameter_bridge-2] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM' 1689274643.1262813 [INFO] [parameter_bridge-24]: sending signal 'SIGTERM' to process[parameter_bridge-24] 1689274643.1344159 [INFO] [parameter_bridge-23]: sending signal 'SIGTERM' to process[parameter_bridge-23] 1689274643.1424642 [INFO] [parameter_bridge-22]: sending signal 'SIGTERM' to process[parameter_bridge-22] 1689274643.1500504 [INFO] [parameter_bridge-21]: sending signal 'SIGTERM' to process[parameter_bridge-21] 1689274643.1579986 [INFO] [parameter_bridge-20]: sending signal 'SIGTERM' to process[parameter_bridge-20] 1689274643.1657128 [INFO] [parameter_bridge-19]: sending signal 'SIGTERM' to process[parameter_bridge-19] 1689274643.1741140 [INFO] [parameter_bridge-18]: sending signal 'SIGTERM' to process[parameter_bridge-18] 1689274643.1817653 [INFO] [parameter_bridge-17]: sending signal 'SIGTERM' to process[parameter_bridge-17] 1689274643.1888976 [INFO] [parameter_bridge-16]: sending signal 'SIGTERM' to process[parameter_bridge-16] 1689274643.1961048 [INFO] [parameter_bridge-15]: sending signal 'SIGTERM' to process[parameter_bridge-15] 1689274643.2041731 [INFO] [parameter_bridge-14]: sending signal 'SIGTERM' to process[parameter_bridge-14] 1689274643.2127805 [INFO] [parameter_bridge-13]: sending signal 'SIGTERM' to process[parameter_bridge-13] 1689274643.2220023 [INFO] [parameter_bridge-12]: sending signal 'SIGTERM' to process[parameter_bridge-12] 1689274643.2247484 [INFO] [parameter_bridge-26]: process has finished cleanly [pid 10506] 1689274643.2301412 [INFO] [parameter_bridge-11]: sending signal 'SIGTERM' to process[parameter_bridge-11] 1689274643.2325301 [INFO] [parameter_bridge-25]: process has finished cleanly [pid 10493] 1689274643.2373505 [INFO] [parameter_bridge-10]: sending signal 'SIGTERM' to process[parameter_bridge-10] 1689274643.2447305 [INFO] [parameter_bridge-9]: sending signal 'SIGTERM' to process[parameter_bridge-9] 1689274643.2464690 [INFO] [parameter_bridge-24]: process has finished cleanly [pid 10472] 1689274643.2536292 [INFO] [parameter_bridge-2]: sending signal 'SIGTERM' to process[parameter_bridge-2] 1689274643.2540157 [INFO] [parameter_bridge-23]: process has finished cleanly [pid 10425] 1689274643.2553329 [INFO] [parameter_bridge-22]: process has finished cleanly [pid 10387] 1689274643.2585542 [INFO] [parameter_bridge-21]: process has finished cleanly [pid 10366] 1689274643.2656612 [INFO] [parameter_bridge-20]: process has finished cleanly [pid 10348] 1689274643.2732453 [INFO] [parameter_bridge-19]: process has finished cleanly [pid 10322] 1689274643.2817671 [INFO] [parameter_bridge-18]: process has finished cleanly [pid 10311] 1689274643.2887905 [INFO] [parameter_bridge-17]: process has finished cleanly [pid 10309] 1689274643.2957580 [INFO] [parameter_bridge-16]: process has finished cleanly [pid 10307] 1689274643.3044667 [INFO] [parameter_bridge-15]: process has finished cleanly [pid 10302] 1689274643.3127429 [INFO] [parameter_bridge-14]: process has finished cleanly [pid 10300] 1689274643.3202696 [INFO] [parameter_bridge-13]: process has finished cleanly [pid 10298] 1689274643.3293440 [INFO] [parameter_bridge-12]: process has finished cleanly [pid 10296] 1689274643.3365402 [INFO] [parameter_bridge-11]: process has finished cleanly [pid 10293] 1689274643.3449340 [INFO] [parameter_bridge-10]: process has finished cleanly [pid 10289] 1689274643.3520558 [INFO] [parameter_bridge-9]: process has finished cleanly [pid 10286] 1689274643.3630941 [INFO] [parameter_bridge-2]: process has finished cleanly [pid 10270]

Thanks Yazan,

Notice earlier up in the terminal output, the following error:

[robot_state_publisher-3] Error:   link 'velodyne_base_link' is not unique. [robot_state_publisher-3] at line 178 in ./urdf_parser/src/model.cpp
[robot_state_publisher-3] Failed to parse robot description using: urdf_xml_parser/URDFXMLParser [robot_state_publisher-3] terminate called after throwing an instance of 'std::runtime_error'
[robot_state_publisher-3]   what():  Unable to initialize urdf::model from robot description

This is likely a conflict because you have inserted two velodyne links and set the naming to the same as the default name instead of changing the second one to a unique name.

  <xacro:VLP-16>
    <origin xyz="${vlp16_x_offset} ${vlp16_y_offset} ${vlp16_z_offset}"/>
  </xacro:VLP-16>

  <xacro:VLP-16 parent="base_link" name="velodyne" topic="/velodyne_points" organize_cloud="false" hz="10" samples="440" gpu="false">
    <origin xyz="${vlp16_x_offset} ${vlp16_y_offset} ${vlp16_z_offset}" rpy="0 0 0" />
  </xacro:VLP-16>

Thank you @hilary-luo,

The first link was added by mistake and I removed it. However, Ignition still crashes during launch. Here's the output:
[INFO] [launch]: All log files can be found below /home/rihanadm/.ros/log/2023-07-13-22-57-08-917903-innb02903-41845 [INFO] [launch]: Default logging verbosity is set to INFO ign_args is deprecated, migrate to gz_args! [INFO] [ruby $(which ign) gazebo-1]: process started with pid [41872] [INFO] [parameter_bridge-2]: process started with pid [41875] [INFO] [robot_state_publisher-3]: process started with pid [41877] [INFO] [joint_state_publisher-4]: process started with pid [41879] [INFO] [robot_state_publisher-5]: process started with pid [41882] [INFO] [static_transform_publisher-6]: process started with pid [41884] [INFO] [create-7]: process started with pid [41886] [INFO] [create-8]: process started with pid [41901] [INFO] [parameter_bridge-9]: process started with pid [41923] [INFO] [parameter_bridge-10]: process started with pid [41928] [INFO] [parameter_bridge-11]: process started with pid [41930] [INFO] [parameter_bridge-12]: process started with pid [41941] [INFO] [parameter_bridge-13]: process started with pid [41950] [INFO] [parameter_bridge-14]: process started with pid [41952] [INFO] [parameter_bridge-15]: process started with pid [41979] [INFO] [parameter_bridge-16]: process started with pid [41982] [INFO] [parameter_bridge-17]: process started with pid [42009] [INFO] [parameter_bridge-18]: process started with pid [42022] [INFO] [parameter_bridge-19]: process started with pid [42047] [INFO] [parameter_bridge-20]: process started with pid [42051] [INFO] [parameter_bridge-21]: process started with pid [42073] [INFO] [parameter_bridge-22]: process started with pid [42089] [INFO] [parameter_bridge-23]: process started with pid [42117] [INFO] [parameter_bridge-24]: process started with pid [42123] [INFO] [parameter_bridge-25]: process started with pid [42129] [INFO] [parameter_bridge-26]: process started with pid [42145] [INFO] [turtlebot4_node-27]: process started with pid [42157] [INFO] [spawner-28]: process started with pid [42192] [INFO] [hazards_vector_publisher-29]: process started with pid [42202] [INFO] [ir_intensity_vector_publisher-30]: process started with pid [42213] [INFO] [motion_control-31]: process started with pid [42219] [INFO] [wheel_status_publisher-32]: process started with pid [42230] [INFO] [mock_publisher-33]: process started with pid [42274] [INFO] [robot_state-34]: process started with pid [42289] [INFO] [kidnap_estimator_publisher-35]: process started with pid [42304] [INFO] [ui_mgr-36]: process started with pid [42319] [INFO] [pose_republisher_node-37]: process started with pid [42322] [INFO] [sensors_node-38]: process started with pid [42339] [INFO] [interface_buttons_node-39]: process started with pid [42411] [INFO] [static_transform_publisher-40]: process started with pid [42414] [INFO] [static_transform_publisher-41]: process started with pid [42424] [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Warehouse to https://fuel.gazebosim.org/1.0/OpenRobotics/models/Warehouse [parameter_bridge-2] [INFO] [1689281831.303569381] [clock_bridge]: Creating GZ->ROS Bridge: [/clock (ignition.msgs.Clock) -> /clock (rosgraph_msgs/msg/Clock)] (Lazy 0) [robot_state_publisher-3] [WARN] [1689281831.231120640] [kdl_parser]: The root link base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [robot_state_publisher-3] [INFO] [1689281831.231341486] [robot_state_publisher]: got segment base_link [robot_state_publisher-3] [INFO] [1689281831.231428298] [robot_state_publisher]: got segment bump_front_center [robot_state_publisher-3] [INFO] [1689281831.231440281] [robot_state_publisher]: got segment bump_front_left [robot_state_publisher-3] [INFO] [1689281831.231448773] [robot_state_publisher]: got segment bump_front_right [robot_state_publisher-3] [INFO] [1689281831.231456966] [robot_state_publisher]: got segment bump_left [robot_state_publisher-3] [INFO] [1689281831.231465341] [robot_state_publisher]: got segment bump_right [robot_state_publisher-3] [INFO] [1689281831.231473673] [robot_state_publisher]: got segment bumper [robot_state_publisher-3] [INFO] [1689281831.231481903] [robot_state_publisher]: got segment button_1 [robot_state_publisher-3] [INFO] [1689281831.231490040] [robot_state_publisher]: got segment button_2 [robot_state_publisher-3] [INFO] [1689281831.231498027] [robot_state_publisher]: got segment button_power [robot_state_publisher-3] [INFO] [1689281831.231506252] [robot_state_publisher]: got segment cliff_front_left [robot_state_publisher-3] [INFO] [1689281831.231514329] [robot_state_publisher]: got segment cliff_front_right [robot_state_publisher-3] [INFO] [1689281831.231522611] [robot_state_publisher]: got segment cliff_side_left [robot_state_publisher-3] [INFO] [1689281831.231530627] [robot_state_publisher]: got segment cliff_side_right [robot_state_publisher-3] [INFO] [1689281831.231538864] [robot_state_publisher]: got segment front_caster_link [robot_state_publisher-3] [INFO] [1689281831.231547247] [robot_state_publisher]: got segment imu_link [robot_state_publisher-3] [INFO] [1689281831.231555587] [robot_state_publisher]: got segment ir_intensity_front_center_left [robot_state_publisher-3] [INFO] [1689281831.231564372] [robot_state_publisher]: got segment ir_intensity_front_center_right [robot_state_publisher-3] [INFO] [1689281831.231572657] [robot_state_publisher]: got segment ir_intensity_front_left [robot_state_publisher-3] [INFO] [1689281831.231580788] [robot_state_publisher]: got segment ir_intensity_front_right [robot_state_publisher-3] [INFO] [1689281831.231589102] [robot_state_publisher]: got segment ir_intensity_left [robot_state_publisher-3] [INFO] [1689281831.231597632] [robot_state_publisher]: got segment ir_intensity_right [robot_state_publisher-3] [INFO] [1689281831.231605465] [robot_state_publisher]: got segment ir_intensity_side_left [robot_state_publisher-3] [INFO] [1689281831.231613323] [robot_state_publisher]: got segment ir_omni [robot_state_publisher-3] [INFO] [1689281831.231621409] [robot_state_publisher]: got segment left_wheel [robot_state_publisher-3] [INFO] [1689281831.231629192] [robot_state_publisher]: got segment mouse [robot_state_publisher-3] [INFO] [1689281831.231637579] [robot_state_publisher]: got segment oakd_camera_bracket [robot_state_publisher-3] [INFO] [1689281831.231645419] [robot_state_publisher]: got segment oakd_imu_frame [robot_state_publisher-3] [INFO] [1689281831.231653482] [robot_state_publisher]: got segment oakd_left_camera_frame [robot_state_publisher-3] [INFO] [1689281831.231661000] [robot_state_publisher]: got segment oakd_left_camera_optical_frame [robot_state_publisher-3] [INFO] [1689281831.231668810] [robot_state_publisher]: got segment oakd_link [robot_state_publisher-3] [INFO] [1689281831.231676760] [robot_state_publisher]: got segment oakd_rgb_camera_frame [robot_state_publisher-3] [INFO] [1689281831.231689759] [robot_state_publisher]: got segment oakd_rgb_camera_optical_frame [robot_state_publisher-3] [INFO] [1689281831.231697570] [robot_state_publisher]: got segment oakd_right_camera_frame [robot_state_publisher-3] [INFO] [1689281831.231705115] [robot_state_publisher]: got segment oakd_right_camera_optical_frame [robot_state_publisher-3] [INFO] [1689281831.231712585] [robot_state_publisher]: got segment right_wheel [robot_state_publisher-3] [INFO] [1689281831.231719792] [robot_state_publisher]: got segment rplidar_link [robot_state_publisher-3] [INFO] [1689281831.231727132] [robot_state_publisher]: got segment velodyne [robot_state_publisher-3] [INFO] [1689281831.231734458] [robot_state_publisher]: got segment velodyne_base_link [robot_state_publisher-3] [INFO] [1689281831.231742013] [robot_state_publisher]: got segment wheel_drop_left [robot_state_publisher-3] [INFO] [1689281831.231748608] [robot_state_publisher]: got segment wheel_drop_right [robot_state_publisher-5] [WARN] [1689281831.216073394] [kdl_parser]: The root link std_dock_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF. [robot_state_publisher-5] [INFO] [1689281831.216141265] [dock_state_publisher]: got segment green_buoy_link [robot_state_publisher-5] [INFO] [1689281831.216185965] [dock_state_publisher]: got segment halo_link [robot_state_publisher-5] [INFO] [1689281831.216191835] [dock_state_publisher]: got segment red_buoy_link [robot_state_publisher-5] [INFO] [1689281831.216196404] [dock_state_publisher]: got segment std_dock_link [robot_state_publisher-5] [INFO] [1689281831.216200799] [dock_state_publisher]: got segment yellow_buoy_link [static_transform_publisher-6] [WARN] [1689281831.203493271] []: Old-style arguments are deprecated; see --help for new-style arguments [static_transform_publisher-6] [INFO] [1689281831.223568891] [tf_odom_std_dock_link_publisher]: Spinning until stopped - publishing transform [static_transform_publisher-6] translation: ('0.157000', '0.000000', '0.000000') [static_transform_publisher-6] rotation: ('0.000000', '0.000000', '1.000000', '0.000000') [static_transform_publisher-6] from 'odom' to 'std_dock_link' [create-7] [ros_ign_gazebo] is deprecated! Redirecting to use [ros_gz_sim] instead! [create-7] [create-7] [INFO] [1689281831.260094703] [ros_gz_sim]: Requesting list of world names. [create-8] [ros_ign_gazebo] is deprecated! Redirecting to use [ros_gz_sim] instead! [create-8] [create-8] [INFO] [1689281831.324135858] [ros_gz_sim]: Requesting list of world names. [parameter_bridge-9] [INFO] [1689281831.368882365] [cmd_vel_bridge]: Creating GZ->ROS Bridge: [/cmd_vel (ignition.msgs.Twist) -> /cmd_vel (geometry_msgs/msg/Twist)] (Lazy 0) [parameter_bridge-9] [INFO] [1689281831.374400183] [cmd_vel_bridge]: Creating ROS->GZ Bridge: [/model/turtlebot4/cmd_vel (geometry_msgs/msg/Twist) -> /model/turtlebot4/cmd_vel (ignition.msgs.Twist)] (Lazy 0) [parameter_bridge-10] [INFO] [1689281831.459721771] [pose_bridge]: Creating GZ->ROS Bridge: [/model/turtlebot4/pose (ignition.msgs.Pose_V) -> /model/turtlebot4/pose (tf2_msgs/msg/TFMessage)] (Lazy 0) [parameter_bridge-10] [INFO] [1689281831.467495364] [pose_bridge]: Creating GZ->ROS Bridge: [/model/standard_dock/pose (ignition.msgs.Pose_V) -> /model/standard_dock/pose (tf2_msgs/msg/TFMessage)] (Lazy 0) [parameter_bridge-11] [INFO] [1689281831.378357944] [odom_base_tf_bridge]: Creating GZ->ROS Bridge: [/model/turtlebot4/tf (ignition.msgs.Pose_V) -> /model/turtlebot4/tf (tf2_msgs/msg/TFMessage)] (Lazy 0) [parameter_bridge-12] [INFO] [1689281831.481262030] [bumper_contact_bridge]: Creating GZ->ROS Bridge: [/bumper_contact (ignition.msgs.Contacts) -> /bumper_contact (ros_gz_interfaces/msg/Contacts)] (Lazy 0) [parameter_bridge-13] [INFO] [1689281831.411912531] [cliff_front_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_front_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_front_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-14] [INFO] [1689281831.490775966] [cliff_front_right_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_front_right/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_front_right/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-15] [INFO] [1689281831.854491147] [cliff_side_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_side_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_side_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-16] [INFO] [1689281831.582768273] [cliff_side_right_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_side_right/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/base_link/sensor/cliff_side_right/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-17] [INFO] [1689281831.529681821] [ir_intensity_front_center_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_front_center_left/sensor/ir_intensity_front_center_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_front_center_left/sensor/ir_intensity_front_center_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-18] [INFO] [1689281831.757629094] [ir_intensity_front_center_right_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_front_center_right/sensor/ir_intensity_front_center_right/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_front_center_right/sensor/ir_intensity_front_center_right/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-20] [INFO] [1689281831.844412311] [ir_intensity_front_right_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_front_right/sensor/ir_intensity_front_right/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_front_right/sensor/ir_intensity_front_right/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-21] [INFO] [1689281831.840249833] [ir_intensity_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_left/sensor/ir_intensity_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_left/sensor/ir_intensity_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-22] [INFO] [1689281831.702045747] [ir_intensity_right_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_right/sensor/ir_intensity_right/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_right/sensor/ir_intensity_right/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-25] [INFO] [1689281831.830448286] [lidar_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/rplidar_link/sensor/rplidar/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/rplidar_link/sensor/rplidar/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [parameter_bridge-26] [INFO] [1689281831.807615692] [camera_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/image (ignition.msgs.Image) -> /world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/image (sensor_msgs/msg/Image)] (Lazy 0) [parameter_bridge-26] [INFO] [1689281831.811611784] [camera_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/depth_image (ignition.msgs.Image) -> /world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/depth_image (sensor_msgs/msg/Image)] (Lazy 0) [parameter_bridge-26] [INFO] [1689281831.827907317] [camera_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/points (ignition.msgs.PointCloudPacked) -> /world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/points (sensor_msgs/msg/PointCloud2)] (Lazy 0) [parameter_bridge-26] [INFO] [1689281831.828670767] [camera_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/camera_info (ignition.msgs.CameraInfo) -> /world/warehouse/model/turtlebot4/link/oakd_rgb_camera_frame/sensor/rgbd_camera/camera_info (sensor_msgs/msg/CameraInfo)] (Lazy 0) [turtlebot4_node-27] [INFO] [1689281831.757001844] [turtlebot4_node]: Init Turtlebot4 Node Main [turtlebot4_node-27] [INFO] [1689281831.953533420] [turtlebot4_node]: Buttons Init [hazards_vector_publisher-29] [INFO] [1689281831.826213355] [hazards_vector_publisher]: Advertised topic: hazard_detection [hazards_vector_publisher-29] [INFO] [1689281831.863783343] [hazards_vector_publisher]: Subscription to topic: _internal/bumper/event [hazards_vector_publisher-29] [INFO] [1689281831.864418742] [hazards_vector_publisher]: Subscription to topic: _internal/cliff_front_left/event [hazards_vector_publisher-29] [INFO] [1689281831.864660188] [hazards_vector_publisher]: Subscription to topic: _internal/cliff_front_right/event [hazards_vector_publisher-29] [INFO] [1689281831.871975233] [hazards_vector_publisher]: Subscription to topic: _internal/cliff_side_left/event [hazards_vector_publisher-29] [INFO] [1689281831.872283622] [hazards_vector_publisher]: Subscription to topic: _internal/cliff_side_right/event [hazards_vector_publisher-29] [INFO] [1689281831.872473154] [hazards_vector_publisher]: Subscription to topic: _internal/wheel_drop/left_wheel/event [hazards_vector_publisher-29] [INFO] [1689281831.872650373] [hazards_vector_publisher]: Subscription to topic: _internal/wheel_drop/right_wheel/event [hazards_vector_publisher-29] [INFO] [1689281831.874430817] [hazards_vector_publisher]: Subscription to topic: _internal/backup_limit [ir_intensity_vector_publisher-30] [INFO] [1689281831.763020708] [ir_intensity_vector_publisher]: Advertised topic: ir_intensity [ir_intensity_vector_publisher-30] [INFO] [1689281831.763458217] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_front_center_left [ir_intensity_vector_publisher-30] [INFO] [1689281831.763698947] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_front_center_right [ir_intensity_vector_publisher-30] [INFO] [1689281831.763919887] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_front_left [ir_intensity_vector_publisher-30] [INFO] [1689281831.764130040] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_front_right [ir_intensity_vector_publisher-30] [INFO] [1689281831.764314926] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_left [ir_intensity_vector_publisher-30] [INFO] [1689281831.764505001] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_right [ir_intensity_vector_publisher-30] [INFO] [1689281831.764709434] [ir_intensity_vector_publisher]: Subscription to topic: _internal/ir_intensity_side_left [motion_control-31] [INFO] [1689281831.948358988] [motion_control]: Enabling REFLEX_BUMP [motion_control-31] [INFO] [1689281831.948494541] [motion_control]: Enabling REFLEX_CLIFF [motion_control-31] [INFO] [1689281831.948585350] [motion_control]: Enabling REFLEX_STUCK [motion_control-31] [INFO] [1689281831.948636499] [motion_control]: Enabling REFLEX_WHEEL_DROP [static_transform_publisher-40] [WARN] [1689281831.939784297] []: Old-style arguments are deprecated; see --help for new-style arguments [static_transform_publisher-41] [WARN] [1689281831.982473228] []: Old-style arguments are deprecated; see --help for new-style arguments [mock_publisher-33] [INFO] [1689281832.022560477] [mock_publisher]: Advertised mocked topic: slip_status [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/pallet_box_mobile to https://fuel.gazebosim.org/1.0/MovAi/models/pallet_box_mobile [parameter_bridge-19] [INFO] [1689281832.131053622] [ir_intensity_front_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_front_left/sensor/ir_intensity_front_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_front_left/sensor/ir_intensity_front_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [turtlebot4_node-27] [INFO] [1689281832.135087768] [turtlebot4_node]: Turtlebot4 lite running. [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf_big to https://fuel.gazebosim.org/1.0/MovAi/models/shelf_big [wheel_status_publisher-32] [INFO] [1689281832.154772772] [wheel_status_publisher]: Advertised topic: wheel_vels [wheel_status_publisher-32] [INFO] [1689281832.155290516] [wheel_status_publisher]: Advertised topic: wheel_ticks [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf_big to https://fuel.gazebosim.org/1.0/MovAi/models/shelf_big [parameter_bridge-24] [INFO] [1689281832.223658795] [buttons_msg_bridge]: Creating GZ->ROS Bridge: [/create3_buttons (ignition.msgs.Int32) -> /create3_buttons (std_msgs/msg/Int32)] (Lazy 0) [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf_big to https://fuel.gazebosim.org/1.0/MovAi/models/shelf_big [kidnap_estimator_publisher-35] [INFO] [1689281832.275156290] [kidnap_estimator_publisher]: Advertised topic: kidnap_status [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf to https://fuel.gazebosim.org/1.0/MovAi/models/shelf [kidnap_estimator_publisher-35] [INFO] [1689281832.295783359] [kidnap_estimator_publisher]: Subscription to topic: hazard_detection [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf to https://fuel.gazebosim.org/1.0/MovAi/models/shelf [static_transform_publisher-41] [INFO] [1689281832.367657676] [camera_stf]: Spinning until stopped - publishing transform [static_transform_publisher-41] translation: ('0.000000', '0.000000', '0.000000') [static_transform_publisher-41] rotation: ('0.499952', '-0.500000', '0.500000', '0.500048') [static_transform_publisher-41] from 'oakd_rgb_camera_optical_frame' to 'turtlebot4/oakd_rgb_camera_frame/rgbd_camera' [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf to https://fuel.gazebosim.org/1.0/MovAi/models/shelf [robot_state-34] [INFO] [1689281832.407775743] [robot_state]: Advertised topic: battery_state [robot_state-34] [INFO] [1689281832.423044000] [robot_state]: Subscription to topic: dock_status [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf to https://fuel.gazebosim.org/1.0/MovAi/models/shelf [robot_state-34] [INFO] [1689281832.443918782] [robot_state]: Advertised topic: stop_status [static_transform_publisher-40] [INFO] [1689281832.451885264] [rplidar_stf]: Spinning until stopped - publishing transform [static_transform_publisher-40] translation: ('0.000000', '0.000000', '0.000000') [static_transform_publisher-40] rotation: ('0.000000', '0.000000', '0.000000', '1.000000') [static_transform_publisher-40] from 'rplidar_link' to 'turtlebot4/rplidar_link/rplidar' [robot_state-34] [INFO] [1689281832.452639754] [robot_state]: Subscription to topic: odom [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf to https://fuel.gazebosim.org/1.0/MovAi/models/shelf [ui_mgr-36] [INFO] [1689281832.512094071] [ui_mgr]: Subscription to topic: cmd_lightring [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf_big to https://fuel.gazebosim.org/1.0/MovAi/models/shelf_big [ui_mgr-36] [INFO] [1689281832.545435178] [ui_mgr]: Subscription to topic: cmd_audio [parameter_bridge-23] [INFO] [1689281832.554262828] [ir_intensity_side_left_bridge]: Creating GZ->ROS Bridge: [/world/warehouse/model/turtlebot4/link/ir_intensity_side_left/sensor/ir_intensity_side_left/scan (ignition.msgs.LaserScan) -> /world/warehouse/model/turtlebot4/link/ir_intensity_side_left/sensor/ir_intensity_side_left/scan (sensor_msgs/msg/LaserScan)] (Lazy 0) [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf_big to https://fuel.gazebosim.org/1.0/MovAi/models/shelf_big [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf to https://fuel.gazebosim.org/1.0/MovAi/models/shelf [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf to https://fuel.gazebosim.org/1.0/MovAi/models/shelf [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/MovAi/models/shelf to https://fuel.gazebosim.org/1.0/MovAi/models/shelf [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:/qml/StyleDialog.qml:112:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:/qml/StyleDialog.qml:105:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:/qml/StyleDialog.qml:98:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:102:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:/qml/PluginMenu.qml:27:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/Gazebo/GazeboDrawer.qml:241:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/Gazebo/GazeboDrawer.qml:147:3: QML Dialog: Binding loop detected for property "implicitHeight" [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/Gazebo/GazeboDrawer.qml:147:3: QML Dialog: Binding loop detected for property "implicitHeight" [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Chair to https://fuel.gazebosim.org/1.0/OpenRobotics/models/Chair [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Chair to https://fuel.gazebosim.org/1.0/OpenRobotics/models/Chair [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/foldable_chair to https://fuel.gazebosim.org/1.0/OpenRobotics/models/foldable_chair [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/foldable_chair to https://fuel.gazebosim.org/1.0/OpenRobotics/models/foldable_chair [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Table to https://fuel.gazebosim.org/1.0/OpenRobotics/models/Table [ruby $(which ign) gazebo-1] [Wrn] [FuelClient.cc:1978] The fuel.ignitionrobotics.org URL is deprecrated. Pleasse change https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Artifact Proximity Detector to https://fuel.gazebosim.org/1.0/OpenRobotics/models/Artifact Proximity Detector [ruby $(which ign) gazebo-1] [Dbg] [ign.cc:161] Subscribing to [/gazebo/starting_world]. [ruby $(which ign) gazebo-1] [Dbg] [ign.cc:163] Waiting for a world to be set from the GUI... [ruby $(which ign) gazebo-1] [Msg] Received world [warehouse.sdf] from the GUI. [ruby $(which ign) gazebo-1] [Dbg] [ign.cc:167] Unsubscribing from [/gazebo/starting_world]. [ruby $(which ign) gazebo-1] [Msg] Ignition Gazebo Server v6.14.0 [ruby $(which ign) gazebo-1] [Msg] Loading SDF world file[/home/rihanadm/turtlebot4_ws/install/turtlebot4_ignition_bringup/share/turtlebot4_ignition_bringup/worlds/warehouse.sdf]. [ruby $(which ign) gazebo-1] [Msg] Serving entity system service on [/entity/system/add] [ruby $(which ign) gazebo-1] [Dbg] [Physics.cc:803] Loaded [ignition::physics::dartsim::Plugin] from library [/usr/lib/x86_64-linux-gnu/ign-physics-5/engine-plugins/libignition-physics-dartsim-plugin.so] [ruby $(which ign) gazebo-1] [Dbg] [SystemManager.cc:70] Loaded system [ignition::gazebo::systems::Physics] for entity [1] [ruby $(which ign) gazebo-1] [Msg] Create service on [/world/warehouse/create] [ruby $(which ign) gazebo-1] [Msg] Remove service on [/world/warehouse/remove] [ruby $(which ign) gazebo-1] [Msg] Pose service on [/world/warehouse/set_pose] [ruby $(which ign) gazebo-1] [Msg] Pose service on [/world/warehouse/set_pose_vector] [ruby $(which ign) gazebo-1] [Msg] Light configuration service on [/world/warehouse/light_config] [ruby $(which ign) gazebo-1] [Msg] Physics service on [/world/warehouse/set_physics] [ruby $(which ign) gazebo-1] [Msg] SphericalCoordinates service on [/world/warehouse/set_spherical_coordinates] [ruby $(which ign) gazebo-1] [Msg] Enable collision service on [/world/warehouse/enable_collision] [ruby $(which ign) gazebo-1] [Msg] Disable collision service on [/world/warehouse/disable_collision] [ruby $(which ign) gazebo-1] [Msg] Material service on [/world/warehouse/visual_config] [ruby $(which ign) gazebo-1] [Msg] Material service on [/world/warehouse/wheel_slip] [ruby $(which ign) gazebo-1] [Dbg] [SystemManager.cc:70] Loaded system [ignition::gazebo::systems::UserCommands] for entity [1] [ruby $(which ign) gazebo-1] [Dbg] [SystemManager.cc:70] Loaded system [ignition::gazebo::systems::SceneBroadcaster] for entity [1] [ruby $(which ign) gazebo-1] [Dbg] [SystemManager.cc:70] Loaded system [ignition::gazebo::systems::PosePublisher] for entity [12] [ruby $(which ign) gazebo-1] [Msg] PerformerDetector publishing messages on [/subt_performer_detector] [ruby $(which ign) gazebo-1] [Dbg] [SystemManager.cc:70] Loaded system [ignition::gazebo::systems::PerformerDetector] for entity [141] [ruby $(which ign) gazebo-1] [Dbg] [Thermal.cc:112] Thermal plugin, heat signature: using a minimum temperature of 288.15 kelvin, and a max temperature of 305 kelvin. [ruby $(which ign) gazebo-1] [Dbg] [SystemManager.cc:70] Loaded system [ignition::gazebo::systems::Thermal] for entity [139] [ruby $(which ign) gazebo-1] [Msg] Loaded level [3] [ruby $(which ign) gazebo-1] [Msg] Serving world controls on [/world/warehouse/control], [/world/warehouse/control/state] and [/world/warehouse/playback/control] [joint_state_publisher-4] [INFO] [1689281833.798966506] [joint_state_publisher]: Waiting for robot_description to be published on the robot_description topic... [create-7] [INFO] [1689281833.856659177] [ros_gz_sim]: Waiting messages on topic [robot_description]. [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Scene3D.cc:2941] The GzScene3D plugin is deprecated on v6 and will be removed on v7. Use MinimalScene together with other plugins as needed. [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/GzScene3D/GzScene3D.qml:108:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/GzScene3D/GzScene3D.qml:63:5: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/WorldControl/WorldControl.qml:30:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [Msg][Msg] Ignition Gazebo GUI v6.14.0 [ruby $(which ign) gazebo-1] [Dbg] [Gui.cc:253] Waiting for subscribers to [/gazebo/starting_world]... [ruby $(which ign) gazebo-1] [Dbg] [Application.cc:92] Initializing application. [ruby $(which ign) gazebo-1] [GUI] [Dbg] [Application.cc:555] Create main window [ruby $(which ign) gazebo-1] [GUI] [Dbg] [PathManager.cc:66] Requesting resource paths through [/gazebo/resource_paths/get] [ruby $(which ign) gazebo-1] [GUI] [Dbg] [Gui.cc:333] GUI requesting list of world names. The server may be busy downloading resources. Please be patient. [ruby $(which ign) gazebo-1] [GUI] [Dbg] [GuiRunner.cc:145] Requesting initial state from [/world/warehouse/state]... [ruby $(which ign) gazebo-1] [GUI] [Msg] Loading config [/home/rihanadm/turtlebot4_ws/install/turtlebot4_ignition_bringup/share/turtlebot4_ignition_bringup/gui/lite/gui.config] [ruby $(which ign) gazebo-1] [GUI] [Dbg] [Application.cc:426] Loading plugin [GzScene3D] [ruby $(which ign) gazebo-1] [GUI] [Msg] Video recorder stats topic advertised on [/gui/record_video/stats] [ruby $(which ign) gazebo-1] [GUI] [Msg] Transform mode service on [/gui/transform_mode] [ruby $(which ign) gazebo-1] [GUI] [Msg] Record video service on [/gui/record_video] [ruby $(which ign) gazebo-1] [GUI] [Msg] Move to service on [/gui/move_to] [ruby $(which ign) gazebo-1] [GUI] [Msg] Follow service on [/gui/follow] [ruby $(which ign) gazebo-1] [GUI] [Msg] Follow offset service on [/gui/follow/offset] [ruby $(which ign) gazebo-1] [GUI] [Msg] View angle service on [/gui/view_angle] [ruby $(which ign) gazebo-1] [GUI] [Msg] Move to pose service on [/gui/move_to/pose] [ruby $(which ign) gazebo-1] [GUI] [Msg] Camera pose topic advertised on [/gui/camera/pose] [ruby $(which ign) gazebo-1] [GUI] [Msg] View as transparent service on [/gui/view/transparent] [ruby $(which ign) gazebo-1] [GUI] [Msg] View center of mass service on [/gui/view/com] [ruby $(which ign) gazebo-1] [GUI] [Msg] View inertia service on [/gui/view/inertia] [ruby $(which ign) gazebo-1] [GUI] [Msg] View joints service on [/gui/view/joints] [ruby $(which ign) gazebo-1] [GUI] [Msg] View wireframes service on [/gui/view/wireframes] [ruby $(which ign) gazebo-1] [GUI] [Msg] View collisions service on [/gui/view/collisions] [ruby $(which ign) gazebo-1] [GUI] [Msg] Camera view controller topic advertised on [/gui/camera/view_control] [ruby $(which ign) gazebo-1] [GUI] [Msg] Added plugin [3D View] to main window [ruby $(which ign) gazebo-1] [GUI] [Msg] Loaded plugin [GzScene3D] from path [/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/gui/libGzScene3D.so] [ruby $(which ign) gazebo-1] [GUI] [Dbg] [Application.cc:426] Loading plugin [WorldControl] [ruby $(which ign) gazebo-1] [GUI] [Msg] Using world control service [/world/warehouse/control] [ruby $(which ign) gazebo-1] [GUI] [Msg] Listening to stats on [/world/warehouse/stats] [ruby $(which ign) gazebo-1] [GUI] [Dbg] [WorldControl.cc:248] Using a service to share WorldControl msgs with the server [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/TransformControl/TransformControl.qml:104:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/TransformControl/TransformControl.qml:99:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/TransformControl/TransformControl.qml:94:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/TransformControl/TransformControl.qml:89:3: QML Connections: Implicitly defined onFoo properties in Connections are deprecated. Use this syntax instead: function onFoo(<arguments>) { ... } [create-7] [INFO] [1689281834.053196282] [ros_gz_sim]: Requested creation of entity. [create-7] [INFO] [1689281834.053257661] [ros_gz_sim]: OK creation of entity. [create-8] [INFO] [1689281834.054525578] [ros_gz_sim]: Waiting messages on topic [standard_dock_description]. [create-8] [INFO] [1689281834.071647361] [ros_gz_sim]: Requested creation of entity. [create-8] [INFO] [1689281834.071700454] [ros_gz_sim]: OK creation of entity. [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/Create3Hmi/Create3Hmi.qml:49:7: Unable to assign [undefined] to QString [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] QObject::connect: No such signal ignition::gui::Create3Hmi::AddMsg(QString) [INFO] [create-7]: process has finished cleanly [pid 41886] [INFO] [create-8]: process has finished cleanly [pid 41901] [ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::/WorldStats/WorldStats.qml:53:3: QML RowLayout: Binding loop detected for property "x" [ruby $(which ign) gazebo-1] [Wrn] [SdfEntityCreator.cc:900] Sensor type LIDAR not supported yet. Try usinga GPU LIDAR instead. [ruby $(which ign) gazebo-1] [INFO] [1689281834.398156524] [gz_ros2_control]: [ign_ros2_control] Fixed joint [bumper_joint] (Entity=214)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398348813] [gz_ros2_control]: [ign_ros2_control] Fixed joint [front_caster_joint] (Entity=215)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398365191] [gz_ros2_control]: [ign_ros2_control] Fixed joint [imu_joint] (Entity=216)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398374790] [gz_ros2_control]: [ign_ros2_control] Fixed joint [ir_intensity_front_center_left_joint] (Entity=217)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398383816] [gz_ros2_control]: [ign_ros2_control] Fixed joint [ir_intensity_front_center_right_joint] (Entity=218)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398392311] [gz_ros2_control]: [ign_ros2_control] Fixed joint [ir_intensity_front_left_joint] (Entity=219)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398400645] [gz_ros2_control]: [ign_ros2_control] Fixed joint [ir_intensity_front_right_joint] (Entity=220)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398408877] [gz_ros2_control]: [ign_ros2_control] Fixed joint [ir_intensity_left_joint] (Entity=221)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398417372] [gz_ros2_control]: [ign_ros2_control] Fixed joint [ir_intensity_right_joint] (Entity=222)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398425615] [gz_ros2_control]: [ign_ros2_control] Fixed joint [ir_intensity_side_left_joint] (Entity=223)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398433851] [gz_ros2_control]: [ign_ros2_control] Fixed joint [ir_omni_joint] (Entity=224)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398439862] [gz_ros2_control]: [ign_ros2_control] Fixed joint [mouse_joint] (Entity=225)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398445532] [gz_ros2_control]: [ign_ros2_control] Fixed joint [oakd_camera_bracket_joint] (Entity=226)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398451716] [gz_ros2_control]: [ign_ros2_control] Fixed joint [oakd_joint] (Entity=227)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398460036] [gz_ros2_control]: [ign_ros2_control] Fixed joint [oakd_imu_joint] (Entity=228)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398468167] [gz_ros2_control]: [ign_ros2_control] Fixed joint [oakd_left_camera_joint] (Entity=229)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398476683] [gz_ros2_control]: [ign_ros2_control] Fixed joint [oakd_left_camera_optical_joint] (Entity=230)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398486182] [gz_ros2_control]: [ign_ros2_control] Fixed joint [oakd_rgb_camera_joint] (Entity=231)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398495028] [gz_ros2_control]: [ign_ros2_control] Fixed joint [oakd_rgb_camera_optical_joint] (Entity=232)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398503252] [gz_ros2_control]: [ign_ros2_control] Fixed joint [oakd_right_camera_joint] (Entity=233)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398511244] [gz_ros2_control]: [ign_ros2_control] Fixed joint [oakd_right_camera_optical_joint] (Entity=234)] is skipped [ruby $(which ign) gazebo-1] [INFO] [1689281834.398519520] [gz_ros2_control]: [ign_ros2_control] Fixed joint [rplidar_joint] (Entity=235)] is skipped [ruby $(which ign) gazebo-1] libEGL warning: egl: failed to create dri2 screen [ruby $(which ign) gazebo-1] libEGL warning: egl: failed to create dri2 screen [ruby $(which ign) gazebo-1] [GUI] [Err] [Ogre2Camera.cc:390] Ogre2Camera::SetVisibilityMask: Mask bits c0000000 are set but will be ignored by ogre2 backend. [ruby $(which ign) gazebo-1] [ERROR] [1689281834.920610474] [gz_ros2_control]: robot_state_publisher service not available, waiting again... [ruby $(which ign) gazebo-1] [INFO] [1689281835.282593392] [gz_ros2_control]: connected to service!! robot_state_publisher asking for robot_description [ruby $(which ign) gazebo-1] [INFO] [1689281835.283821879] [gz_ros2_control]: Received URDF from param server [ruby $(which ign) gazebo-1] [WARN] [1689281835.290321432] [gz_ros2_control]: The position_proportional_gain parameter was not defined, defaulting to: 0.1 [ruby $(which ign) gazebo-1] [INFO] [1689281835.290404096] [gz_ros2_control]: Loading joint: left_wheel_joint [ruby $(which ign) gazebo-1] [INFO] [1689281835.290415204] [gz_ros2_control]: State: [ruby $(which ign) gazebo-1] [INFO] [1689281835.290424324] [gz_ros2_control]: velocity [ruby $(which ign) gazebo-1] [INFO] [1689281835.290432553] [gz_ros2_control]: position [ruby $(which ign) gazebo-1] [INFO] [1689281835.290439364] [gz_ros2_control]: Command: [ruby $(which ign) gazebo-1] [INFO] [1689281835.290445555] [gz_ros2_control]: velocity [ruby $(which ign) gazebo-1] [INFO] [1689281835.290572557] [gz_ros2_control]: Loading sensor: imu [ruby $(which ign) gazebo-1] [INFO] [1689281835.290580448] [gz_ros2_control]: State: [ruby $(which ign) gazebo-1] [INFO] [1689281835.290601197] [resource_manager]: Initialize hardware 'left_wheel_controller' [ruby $(which ign) gazebo-1] [WARN] [1689281835.290610286] [gz_ros2_control]: On init... [ruby $(which ign) gazebo-1] [INFO] [1689281835.290650714] [resource_manager]: Successful initialization of hardware 'left_wheel_controller' [ruby $(which ign) gazebo-1] [INFO] [1689281835.290680313] [resource_manager]: 'configure' hardware 'left_wheel_controller' [ruby $(which ign) gazebo-1] [INFO] [1689281835.290713708] [gz_ros2_control]: System Successfully configured! [ruby $(which ign) gazebo-1] [INFO] [1689281835.290722170] [resource_manager]: Successful 'configure' of hardware 'left_wheel_controller' [ruby $(which ign) gazebo-1] [INFO] [1689281835.290727114] [resource_manager]: 'activate' hardware 'left_wheel_controller' [ruby $(which ign) gazebo-1] [INFO] [1689281835.290730939] [resource_manager]: Successful 'activate' of hardware 'left_wheel_controller' [ruby $(which ign) gazebo-1] [WARN] [1689281835.290762726] [gz_ros2_control]: The position_proportional_gain parameter was not defined, defaulting to: 0.1 [ruby $(which ign) gazebo-1] [INFO] [1689281835.290777648] [gz_ros2_control]: Loading joint: right_wheel_joint [ruby $(which ign) gazebo-1] [INFO] [1689281835.290784543] [gz_ros2_control]: State: [ruby $(which ign) gazebo-1] [INFO] [1689281835.290790498] [gz_ros2_control]: velocity [ruby $(which ign) gazebo-1] [INFO] [1689281835.290796603] [gz_ros2_control]: position [ruby $(which ign) gazebo-1] [INFO] [1689281835.290802376] [gz_ros2_control]: Command: [ruby $(which ign) gazebo-1] [INFO] [1689281835.290808012] [gz_ros2_control]: velocity [ruby $(which ign) gazebo-1] [INFO] [1689281835.290818014] [gz_ros2_control]: Loading sensor: imu [ruby $(which ign) gazebo-1] [INFO] [1689281835.290824236] [gz_ros2_control]: State: [ruby $(which ign) gazebo-1] [INFO] [1689281835.290830042] [resource_manager]: Initialize hardware 'right_wheel_controller' [ruby $(which ign) gazebo-1] [WARN] [1689281835.290833378] [gz_ros2_control]: On init... [ruby $(which ign) gazebo-1] [INFO] [1689281835.290843280] [resource_manager]: Successful initialization of hardware 'right_wheel_controller' [ruby $(which ign) gazebo-1] [INFO] [1689281835.290851023] [resource_manager]: 'configure' hardware 'right_wheel_controller' [ruby $(which ign) gazebo-1] [INFO] [1689281835.290854180] [gz_ros2_control]: System Successfully configured! [ruby $(which ign) gazebo-1] [INFO] [1689281835.290859788] [resource_manager]: Successful 'configure' of hardware 'right_wheel_controller' [ruby $(which ign) gazebo-1] [INFO] [1689281835.290863660] [resource_manager]: 'activate' hardware 'right_wheel_controller' [ruby $(which ign) gazebo-1] [INFO] [1689281835.290866976] [resource_manager]: Successful 'activate' of hardware 'right_wheel_controller' [ruby $(which ign) gazebo-1] [INFO] [1689281835.290870542] [gz_ros2_control]: Loading controller_manager [ruby $(which ign) gazebo-1] [INFO] [1689281835.421061172] [controller_manager]: Loading controller 'joint_state_broadcaster' [ruby $(which ign) gazebo-1] [GUI] [Msg] Added plugin [World control] to main Serving GUI information on [/world/warehouse/gui/info] [ruby $(which ign) gazebo-1] [Msg] World [warehouse] initialized with [default_physics] physics profile. [ruby $(which ign) gazebo-1] [Msg] Serving world SDF generation service on [/world/warehouse/generate_world_sdf] [ruby $(which ign) gazebo-1] [Msg] Serving world names on [/gazebo/worlds] [ruby $(which ign) gazebo-1] [Msg] Resource path add service on [/gazebo/resource_paths/add]. [ruby $(which ign) gazebo-1] [Msg] Resource path get service on [/gazebo/resource_paths/get]. [ruby $(which ign) gazebo-1] [Msg] Resource path resolve service on [/gazebo/resource_paths/resolve]. [ruby $(which ign) gazebo-1] [Msg] Resource paths published on [/gazebo/resource_paths]. [ruby $(which ign) gazebo-1] [Msg] Server control service on [/server_control]. [ruby $(which ign) gazebo-1] [Msg] Found no publishers on /stats, adding root stats topic [ruby $(which ign) gazebo-1] [Msg] Found no publishers on /clock, adding root clock topic [ruby $(which ign) gazebo-1] [Dbg] [SimulationRunner.cc:496] Creating PostUpdate worker threads: 4 [ruby $(which ign) gazebo-1] [Dbg] [SimulationRunner.cc:507] Creating postupdate worker thread (0) [ruby $(which ign) gazebo-1] [Dbg] [SimulationRunner.cc:507] Creating postupdate worker thread (1) [ruby $(which ign) gazebo-1] [Dbg] [SimulationRunner.cc:507] Creating postupdate worker thread (2) [ruby $(which ign) gazebo-1] [Dbg] [SystemManager.cc:70] Loaded system [ign_ros2_control::IgnitionROS2ControlPlugin] for entity [150] [ruby $(which ign) gazebo-1] [Dbg] [SystemManager.cc:70] Loaded system [ignition::gazebo::systems::PosePublisher] for entity [150] [ruby $(which ign) gazebo-1] [Dbg] [SystemManager.cc:70] Loaded system [ignition::gazebo::systems::Contact] for entity [150] [ruby $(which ign) gazebo-1] [Dbg] [Sensors.cc:479] Configuring Sensors system [ruby $(which ign) gazebo-1] [Dbg] [Sensors.cc:398] SensorsPrivate::Run [ruby $(which ign) gazebo-1] [Dbg] [SystemManager.cc:70] Loaded system [ignition::gazebo::systems::Sensors] for entity [150] [ruby $(which ign) gazebo-1] [Dbg] [Sensors.cc:378] SensorsPrivate::RenderThread started [ruby $(which ign) gazebo-1] [Dbg] [Sensors.cc:228] Waiting for init [ruby $(which ign) gazebo-1] Library [/home/rihanadm/turtlebot4_ws/install/velodyne_gazebo_plugins/lib/libgazebo_ros_velodyne_laser.so] does not export any plugins. The symbol [IgnitionPluginHook] is missing, or it is not externally visible. [ruby $(which ign) gazebo-1] [INFO] [1689281835.701435511] [controller_manager]: Setting use_sim_time=True for joint_state_broadcaster to match controller manager (see ros2_control#325 for details) [spawner-28] [INFO] [1689281835.703077797] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster [ruby $(which ign) gazebo-1] [INFO] [1689281835.710497452] [controller_manager]: Configuring controller 'joint_state_broadcaster' [ruby $(which ign) gazebo-1] [INFO] [1689281835.710689143] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published [ruby $(which ign) gazebo-1] ign gazebo server: ./dart/dynamics/SphereShape.cpp:68: void dart::dynamics::SphereShape::setRadius(double): Assertion radius > 0.0' failed.
[ruby $(which ign) gazebo-1] Stack trace (most recent call last):
[ruby $(which ign) gazebo-1] #31 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ff38742fc34, in
[ruby $(which ign) gazebo-1] #30 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ff38737ba1e, in
[ruby $(which ign) gazebo-1] #29 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ff3872a69ac, in rb_protect
[ruby $(which ign) gazebo-1] #28 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ff38743ec61, in rb_yield
[ruby $(which ign) gazebo-1] #27 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ff38743a30c, in rb_vm_exec
[ruby $(which ign) gazebo-1] #26 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ff387434c96, in
[ruby $(which ign) gazebo-1] #25 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ff387431fc5, in
[ruby $(which ign) gazebo-1] #24 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ff38742fc34, in
[ruby $(which ign) gazebo-1] #23 Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7ff386cf644b, in
[ruby $(which ign) gazebo-1] #22 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ff3873fd088, in rb_nogvl
[ruby $(which ign) gazebo-1] #21 Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7ff386cf5d6b, in
[ruby $(which ign) gazebo-1] #20 Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7ff386ce7492, in
[ruby $(which ign) gazebo-1] #19 Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7ff386ceae2d, in
[ruby $(which ign) gazebo-1] #18 Object "/usr/lib/x86_64-linux-gnu/libignition-gazebo6-ign.so.6.14.0", at 0x7ff383177a53, in runServer
[ruby $(which ign) gazebo-1] #17 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7ff382133655, in
[ruby $(which ign) gazebo-1] #16 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7ff38213da5a, in ignition::gazebo::v6::SimulationRunner::Run(unsigned long)
[ruby $(which ign) gazebo-1] #15 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7ff3821476cd, in ignition::gazebo::v6::SimulationRunner::Step(ignition::gazebo::v6::UpdateInfo const&)
[ruby $(which ign) gazebo-1] #14 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7ff38213d0ea, in ignition::gazebo::v6::SimulationRunner::UpdateSystems()
[ruby $(which ign) gazebo-1] #13 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7ff37854d1ba, in ignition::gazebo::v6::systems::Physics::Update(ignition::gazebo::v6::UpdateInfo const&, ignition::gazebo::v6::EntityComponentManager&)
[ruby $(which ign) gazebo-1] #12 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7ff37854d115, in ignition::gazebo::v6::systems::PhysicsPrivate::CreatePhysicsEntities(ignition::gazebo::v6::EntityComponentManager const&)
[ruby $(which ign) gazebo-1] #11 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7ff378547131, in ignition::gazebo::v6::systems::PhysicsPrivate::CreateCollisionEntities(ignition::gazebo::v6::EntityComponentManager const&)
[ruby $(which ign) gazebo-1] #10 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7ff3785bc864, in
[ruby $(which ign) gazebo-1] #9 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7ff37855d49a, in
[ruby $(which ign) gazebo-1] #8 Object "/usr/lib/x86_64-linux-gnu/ign-physics-5/engine-plugins/libignition-physics-dartsim-plugin.so", at 0x7ff35fd9772e, in ignition::physics::dartsim::SDFFeatures::ConstructSdfCollision(ignition::physics::Identity const&, sdf::v12::Collision const&)
[ruby $(which ign) gazebo-1] #7 Object "/usr/lib/x86_64-linux-gnu/ign-physics-5/engine-plugins/libignition-physics-dartsim-plugin.so", at 0x7ff35fd96ed4, in
[ruby $(which ign) gazebo-1] #6 Object "/lib/x86_64-linux-gnu/libdart.so.6.12", at 0x7ff35f8e916f, in dart::dynamics::SphereShape::SphereShape(double)
[ruby $(which ign) gazebo-1] #5 Object "/lib/x86_64-linux-gnu/libdart.so.6.12", at 0x7ff35f8e80e2, in dart::dynamics::SphereShape::setRadius(double)
[ruby $(which ign) gazebo-1] #4 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7ff386e39e95, in __assert_fail
[ruby $(which ign) gazebo-1] #3 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7ff386e2871a, in
[ruby $(which ign) gazebo-1] #2 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7ff386e287f2, in abort
[ruby $(which ign) gazebo-1] #1 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7ff386e42475, in raise
[ruby $(which ign) gazebo-1] #0 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7ff386e96a7c, in pthread_kill
[ruby $(which ign) gazebo-1] Aborted (Signal sent by tkill() 42158 1767023770)
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:52: TypeError: Cannot read property 'dialogOnExitText' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:54: TypeError: Cannot read property 'exitDialogShowCloseGui' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:53: TypeError: Cannot read property 'exitDialogShowShutdown' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:251: TypeError: Cannot read property 'showDrawer' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:/qml/SideDrawer.qml:93: TypeError: Cannot read property 'showDefaultDrawerOpts' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:/qml/IgnSplit.qml:56: TypeError: Cannot read property 'pluginCount' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:41: TypeError: Cannot read property 'toolBarColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:42: TypeError: Cannot read property 'toolBarTextColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:43: TypeError: Cannot read property 'toolBarColorDark' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:44: TypeError: Cannot read property 'toolBarTextColorDark' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:45: TypeError: Cannot read property 'pluginToolBarColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:46: TypeError: Cannot read property 'pluginToolBarTextColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:47: TypeError: Cannot read property 'pluginToolBarColorDark' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:48: TypeError: Cannot read property 'pluginToolBarTextColorDark' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:50: TypeError: Cannot read property 'defaultExitAction' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:51: TypeError: Cannot read property 'showDialogOnExit' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:55: TypeError: Cannot read property 'exitDialogShutdownText' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:56: TypeError: Cannot read property 'exitDialogCloseGuiText' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:66: TypeError: Cannot read property 'toolBarColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:76: TypeError: Cannot read property 'toolBarTextColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:219: TypeError: Cannot read property 'showPluginMenu' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:202: TypeError: Cannot read property 'showDrawer' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] qrc:qml/Main.qml:188: TypeError: Cannot read property 'showDrawer' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:128: TypeError: Cannot read property 'pluginToolBarColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:139: TypeError: Cannot read property 'pluginToolBarTextColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:128: TypeError: Cannot read property 'pluginToolBarColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:139: TypeError: Cannot read property 'pluginToolBarTextColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:128: TypeError: Cannot read property 'pluginToolBarColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:139: TypeError: Cannot read property 'pluginToolBarTextColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:128: TypeError: Cannot read property 'pluginToolBarColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:139: TypeError: Cannot read property 'pluginToolBarTextColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:128: TypeError: Cannot read property 'pluginToolBarColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:139: TypeError: Cannot read property 'pluginToolBarTextColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:128: TypeError: Cannot read property 'pluginToolBarColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:139: TypeError: Cannot read property 'pluginToolBarTextColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:128: TypeError: Cannot read property 'pluginToolBarColorLight' of null
[ruby $(which ign) gazebo-1] [GUI] [Wrn] [Application.cc:797] [QT] file::qml/IgnCard.qml:139: TypeError: Cannot read property 'pluginToolBarTextColorLight' of null
[ruby $(which ign) gazebo-1] window
[ruby $(which ign) gazebo-1] [GUI] [Msg] Loaded plugin [WorldControl] from path [/usr/lib/x86_64-linux-gnu/ign-gui-6/plugins/libWorldControl.so]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [Application.cc:426] Loading plugin [WorldStats]
[ruby $(which ign) gazebo-1] [GUI] [Msg] Listening to stats on [/world/warehouse/stats]
[ruby $(which ign) gazebo-1] [GUI] [Msg] Added plugin [World stats] to main window
[ruby $(which ign) gazebo-1] [GUI] [Msg] Loaded plugin [WorldStats] from path [/usr/lib/x86_64-linux-gnu/ign-gui-6/plugins/libWorldStats.so]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [Application.cc:426] Loading plugin [TransformControl]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [TransformControl.cc:219] Legacy mode is disabled; this plugin must be used with MinimalScene.
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [PathManager.cc:55] Received resource paths.
[ruby $(which ign) gazebo-1] [GUI] [Msg] Added plugin [Transform control] to main window
[ruby $(which ign) gazebo-1] [GUI] [Msg] Loaded plugin [TransformControl] from path [/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/gui/libTransformControl.so]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [Application.cc:426] Loading plugin [Shapes]
[ruby $(which ign) gazebo-1] [GUI] [Msg] Added plugin [Shapes] to main window
[ruby $(which ign) gazebo-1] [GUI] [Msg] Loaded plugin [Shapes] from path [/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/gui/libShapes.so]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [Application.cc:426] Loading plugin [Create3Hmi]
[ruby $(which ign) gazebo-1] [GUI] [Msg] Added plugin [Create3 HMI] to main window
[ruby $(which ign) gazebo-1] [GUI] [Msg] Loaded plugin [Create3Hmi] from path [/opt/ros/humble/share/irobot_create_ignition_plugins/lib/libCreate3Hmi.so]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [Application.cc:426] Loading plugin [Teleop]
[ruby $(which ign) gazebo-1] [GUI] [Msg] A new topic has been entered: '/cmd_vel '
[ruby $(which ign) gazebo-1] [GUI] [Msg] Added plugin [Teleop] to main window
[ruby $(which ign) gazebo-1] [GUI] [Msg] Loaded plugin [Teleop] from path [/usr/lib/x86_64-linux-gnu/ign-gui-6/plugins/libTeleop.so]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [Application.cc:569] Applying config
[ruby $(which ign) gazebo-1] [GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [RenderUtil.cc:2542] Create scene [scene]
[ruby $(which ign) gazebo-1] [GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [TransformControl.cc:528] TransformControl plugin is using camera [scene::Camera(65527)]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [SignalHandler.cc:141] Received signal[2].
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [Gui.cc:472] Shutting down ign-gazebo-gui
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [Application.cc:140] Terminating application.
[ruby $(which ign) gazebo-1] [GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[ruby $(which ign) gazebo-1] [GUI] [Dbg] [Scene3D.cc:2165] Destroy scene [scene]
[INFO] [ruby $(which ign) gazebo-1]: process has finished cleanly [pid 41872]`

I noticed that it cannot find the VLP-16 plugin. So I exported its location to $GAZEBO_PLUGIN_PATH. But the same output still persists.

Are you certain that plugin works with the new Gazebo (previously referred to as Ignition) and not just Gazebo classic? I am not familiar with that repo so I can't help too much with why it can't find that plugin. I don't see anything else specifically wrong from the terminal output.

Instead, I would suggest inserting a generic lidar and configuring it to the correct resolution. The URDF that we use to add the VLP-16 lidar is available here: https://github.com/clearpathrobotics/clearpath_common/blob/humble/clearpath_sensors_description/urdf/velodyne_lidar.urdf.xacro

You will need velodyne_description installed, include a copy of this new file in your urdf and then insert a velodyne_lidar element.

Thank you so much Hilary.

I tried doign what you said, but it kept giving the Unable to find file with URI [model://velodyne_simulator/meshes/VLP16_base_1.dae] or any of the other meshes.

I realized that the meshes have to be added to IGN_GAZEBO_RESOURCE_PATH, and not added properly as a dependency to Turtlebot4 packages.

Then way it worked was as follows:

  1. followed the steps you gave me above

  2. in turtlebot4_ignition_bringup/launch/ignition.launch.py I added the following:

pkg_velodyne_description = get_package_share_directory( 'velodyne_description')
and str(Path(pkg_velodyne_description).parent.resolve()) to ign_resource_path

  1. Added <depend>velodyne_description</depend> to turtlebot4_ignition_bringup/package.xml
  2. Added find_package(velodyne_description REQUIRED) to turtlebot4_description/CMakeLists.txt

I guess the issue I opened with the repo had to be integrated better with the turtlebot4 too. But the one you provided perfectly works.

Hy @YazanRihan.

Sorry to bother you, but did the Velodyne worked for you?
I followed all the steps in this post (which end up beeing very useful, thanks both for the info) and I could launch a world with both, the turtlebot4 and the velodyne, but the velodyne is not working at all. I can't see any topic from it, even tough I tried to create a ros_gazebo_bridge. Do you know If i have to run it or if I'm missing something?

Thanks in advance.