I’m having some trouble getting a custom model working in the ROS2 SITL (Humble/Harmonic).
I took the r1_rover and duplicated it, taking care to give it a new name (sentroproto). I followed the instructions for incorporating a new model (gave it an airframe number, updated the CMakeLists.txt file).
Sure enough, if I make px4_sitl gz_sentroproto
the SITL and Gazebo come up and we’re in good shape. I see all variety of IMUs, magnetometers, etc under Gazebo’s System Plugin Info pane. QGC connects…
Here’s the output of that working:
| ___ \ \ \ / / / |
| |_/ / \ V / / /| |
| __/ / \ / /_| |
| | / /^\ \ \___ |
\_| \/ \/ |_/
px4 starting.
INFO [px4] startup script: /bin/sh etc/init.d-posix/rcS 0
INFO [init] found model autostart file as SYS_AUTOSTART=4023
INFO [param] selected parameter default file parameters.bson
INFO [param] importing from 'parameters.bson'
INFO [parameters] BSON document size 312 bytes, decoded 312 bytes (INT32:13, FLOAT:3)
INFO [param] selected parameter backup file parameters_backup.bson
INFO [dataman] data manager file './dataman' size is 1208528 bytes
INFO [init] Gazebo simulator
INFO [init] Starting gazebo with world: /root/PX4-Autopilot/Tools/simulation/gz/worlds/rover.sdf
INFO [init] Starting gz gui
INFO [init] Waiting for Gazebo world...
INFO [init] Gazebo world is ready
INFO [init] Spawning model
INFO [gz_bridge] world: rover, model: sentroproto_0
INFO [lockstep_scheduler] setting initial absolute time to 4220000 us
INFO [commander] LED: open /dev/led0 failed (22)
WARN [health_and_arming_checks] Preflight Fail: ekf2 missing data
WARN [health_and_arming_checks] Preflight Fail: system power unavailable
INFO [uxrce_dds_client] init UDP agent IP:127.0.0.1, port:8888
INFO [tone_alarm] home set
INFO [mavlink] mode: Normal, data rate: 4000000 B/s on udp port 18570 remote port 14550
INFO [mavlink] mode: Onboard, data rate: 4000000 B/s on udp port 14580 remote port 14540
INFO [mavlink] mode: Onboard, data rate: 4000 B/s on udp port 14280 remote port 14030
INFO [mavlink] mode: Gimbal, data rate: 400000 B/s on udp port 13030 remote port 13280
INFO [logger] logger started (mode=all)
INFO [logger] Start file log (type: full)
INFO [logger] [logger] ./log/2025-04-23/21_42_58.ulg
INFO [logger] Opened full log file: ./log/2025-04-23/21_42_58.ulg
INFO [mavlink] MAVLink only on localhost (set param MAV_{i}_BROADCAST = 1 to enable network)
INFO [mavlink] MAVLink only on localhost (set param MAV_{i}_BROADCAST = 1 to enable network)
INFO [px4] Startup script returned successfully
However, I’d like a little more control over how Gazebo is launched, so I started down the path of launching the SITL in stand alone mode.
I’m exec’ing the SITL like so:
#!/bin/bash
cd /root/PX4-Autopilot
export PX4_GZ_STANDALONE=1
export PX4_SYS_AUTOSTART=4023
export PX4_GZ_MODEL_NAME=sentroproto
export PX4_GZ_WORLD=rover
./build/px4_sitl_default/bin/px4
…and launching Gazebo with a node like this (where model_sdf_path points to the same working sdf as before):
spawner = Node(package='ros_gz_sim', executable='create',
arguments=['-file', model_sdf_path,
'-name', 'sentroproto',
'-z', '0.1'],
output='screen')
My model appears, but none of the sensor plugins appear to load. The IMU, etc are absent from the System Plugins pane. The SITL looks like it attaches to the model, but then can’t find any sensors.
Here’s the output of the SITL:
| ___ \ \ \ / / / |
| |_/ / \ V / / /| |
| __/ / \ / /_| |
| | / /^\ \ \___ |
\_| \/ \/ |_/
px4 starting.
INFO [px4] startup script: /bin/sh etc/init.d-posix/rcS 0
env SYS_AUTOSTART: 4023
INFO [param] selected parameter default file parameters.bson
INFO [param] importing from 'parameters.bson'
INFO [parameters] BSON document size 312 bytes, decoded 312 bytes (INT32:13, FLOAT:3)
INFO [param] selected parameter backup file parameters_backup.bson
INFO [dataman] data manager file './dataman' size is 1208528 bytes
INFO [init] Gazebo simulator
INFO [init] Standalone PX4 launch, waiting for Gazebo
INFO [init] Gazebo world is ready
INFO [init] PX4_GZ_MODEL_NAME set, PX4 will attach to existing model
INFO [gz_bridge] world: rover, model: sentroproto
INFO [lockstep_scheduler] setting initial absolute time to 11130000 us
INFO [commander] LED: open /dev/led0 failed (22)
WARN [health_and_arming_checks] Too many arming check events (1, 14 > 14). Not reporting all
WARN [health_and_arming_checks] Preflight Fail: Accel Sensor 0 missing
WARN [health_and_arming_checks] Preflight Fail: barometer 0 missing
WARN [health_and_arming_checks] Preflight Fail: ekf2 missing data
WARN [health_and_arming_checks] Preflight Fail: Gyro Sensor 0 missing
WARN [health_and_arming_checks] Preflight Fail: Found 0 compass (required: 1)
WARN [health_and_arming_checks] Preflight Fail: system power unavailable
INFO [uxrce_dds_client] init UDP agent IP:127.0.0.1, port:8888
INFO [mavlink] mode: Normal, data rate: 4000000 B/s on udp port 18570 remote port 14550
INFO [mavlink] mode: Onboard, data rate: 4000000 B/s on udp port 14580 remote port 14540
INFO [mavlink] mode: Onboard, data rate: 4000 B/s on udp port 14280 remote port 14030
INFO [mavlink] mode: Gimbal, data rate: 400000 B/s on udp port 13030 remote port 13280
INFO [logger] logger started (mode=all)
INFO [logger] Start file log (type: full)
INFO [logger] [logger] ./log/2025-04-23/21_29_45.ulg
INFO [logger] Opened full log file: ./log/2025-04-23/21_29_45.ulg
INFO [mavlink] MAVLink only on localhost (set param MAV_{i}_BROADCAST = 1 to enable network)
INFO [mavlink] MAVLink only on localhost (set param MAV_{i}_BROADCAST = 1 to enable network)
INFO [px4] Startup script returned successfully
pxh> WARN [health_and_arming_checks] Too many arming check events (1, 14 > 14). Not reporting all
WARN [health_and_arming_checks] Preflight Fail: Accel Sensor 0 missing
WARN [health_and_arming_checks] Preflight Fail: barometer 0 missing
WARN [health_and_arming_checks] Preflight Fail: ekf2 missing data
WARN [health_and_arming_checks] Preflight Fail: Gyro Sensor 0 missing
WARN [health_and_arming_checks] Preflight Fail: Found 0 compass (required: 1)
Here’s what Gazebo logs:
[INFO] [launch]: All log files can be found below /root/.ros/log/2025-04-23-15-00-17-393953-docker-desktop-2840
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ruby $(which gz) sim-1]: process started with pid [2841]
[INFO] [robot_state_publisher-2]: process started with pid [2843]
[INFO] [create-3]: process started with pid [2846]
[create-3] [INFO] [1745445617.748871421] [ros_gz_sim]: Requesting list of world names.
[robot_state_publisher-2] [WARN] [1745445617.776333154] [sdformat_urdf]: SDFormat link [base_link] has a <sensor>, but URDF does not support this
[robot_state_publisher-2] [WARN] [1745445617.780880423] [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-2] [INFO] [1745445617.780954535] [robot_state_publisher]: got segment base_link
[robot_state_publisher-2] [INFO] [1745445617.781030700] [robot_state_publisher]: got segment lb_wheel_link
[robot_state_publisher-2] [INFO] [1745445617.781038575] [robot_state_publisher]: got segment lf_wheel_link
[robot_state_publisher-2] [INFO] [1745445617.781043891] [robot_state_publisher]: got segment rb_wheel_link
[robot_state_publisher-2] [INFO] [1745445617.781065137] [robot_state_publisher]: got segment rf_wheel_link
[ruby $(which gz) sim-1] QStandardPaths: XDG_RUNTIME_DIR not set, defaulting to '/tmp/runtime-root'
[ruby $(which gz) sim-1] [Dbg] [gz.cc:166] Subscribing to [/gazebo/starting_world].
[ruby $(which gz) sim-1] [Dbg] [gz.cc:168] Waiting for a world to be set from the GUI...
[ruby $(which gz) sim-1] [Msg] Received world [/root/PX4-Autopilot/Tools/simulation/gz/worlds/rover.sdf] from the GUI.
[ruby $(which gz) sim-1] [Dbg] [gz.cc:172] Unsubscribing from [/gazebo/starting_world].
[ruby $(which gz) sim-1] [Msg] Gazebo Sim Server v8.9.0
[ruby $(which gz) sim-1] [Msg] Loading SDF world file[/root/PX4-Autopilot/Tools/simulation/gz/worlds/rover.sdf].
[ruby $(which gz) sim-1] [Msg] Serving entity system service on [/entity/system/add]
[ruby $(which gz) sim-1] [Msg] Loaded level [default]
[ruby $(which gz) sim-1] [Msg] No systems loaded from SDF, loading defaults
[ruby $(which gz) sim-1] [Dbg] [ServerConfig.cc:1034] Loaded (3) plugins from file [/root/.gz/sim/8/server.config]
[ruby $(which gz) sim-1] [Dbg] [Physics.cc:883] Loaded [gz::physics::dartsim::Plugin] from library [/usr/lib/x86_64-linux-gnu/gz-physics-7/engine-plugins/libgz-physics-dartsim-plugin.so]
[ruby $(which gz) sim-1] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::Physics] for entity [1]
[ruby $(which gz) sim-1] [Msg] Create service on [/world/rover/create]
[ruby $(which gz) sim-1] [Msg] Remove service on [/world/rover/remove]
[ruby $(which gz) sim-1] [Msg] Pose service on [/world/rover/set_pose]
[ruby $(which gz) sim-1] [Msg] Pose service on [/world/rover/set_pose_vector]
[ruby $(which gz) sim-1] [Msg] Light configuration service on [/world/rover/light_config]
[ruby $(which gz) sim-1] [Msg] Physics service on [/world/rover/set_physics]
[ruby $(which gz) sim-1] [Msg] SphericalCoordinates service on [/world/rover/set_spherical_coordinates]
[ruby $(which gz) sim-1] [Msg] Enable collision service on [/world/rover/enable_collision]
[ruby $(which gz) sim-1] [Msg] Disable collision service on [/world/rover/disable_collision]
[ruby $(which gz) sim-1] [Msg] Material service on [/world/rover/visual_config]
[ruby $(which gz) sim-1] [Msg] Material service on [/world/rover/wheel_slip]
[ruby $(which gz) sim-1] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::UserCommands] for entity [1]
[ruby $(which gz) sim-1] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::SceneBroadcaster] for entity [1]
[ruby $(which gz) sim-1] [Msg] Serving world controls on [/world/rover/control], [/world/rover/control/state] and [/world/rover/playback/control]
[ruby $(which gz) sim-1] [Msg] Serving GUI information on [/world/rover/gui/info]
[ruby $(which gz) sim-1] [Msg] World [rover] initialized with [default_physics] physics profile.
[ruby $(which gz) sim-1] [Msg] Serving world SDF generation service on [/world/rover/generate_world_sdf]
[ruby $(which gz) sim-1] [Msg] Serving world names on [/gazebo/worlds]
[ruby $(which gz) sim-1] [Msg] Resource path add service on [/gazebo/resource_paths/add].
[create-3] [INFO] [1745445618.350298572] [ros_gz_sim]: Requested creation of entity.
[create-3] [INFO] [1745445618.350377819] [ros_gz_sim]: OK creation of entity.
[INFO] [create-3]: process has finished cleanly [pid 2846]
[ruby $(which gz) sim-1] [Msg] Resource path get service on [/gazebo/resource_paths/get[Msg] Gazebo Sim GUI v8.9.0
[ruby $(which gz) sim-1] [Dbg] [Gui.cc:275] Waiting for subscribers to [/gazebo/starting_world]...
[ruby $(which gz) sim-1] [Dbg] [Application.cc:96] Initializing application.
[ruby $(which gz) sim-1] [Dbg] [Application.cc:170] Qt using OpenGL graphics interface
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:657] Create main window
[ruby $(which gz) sim-1] [GUI] [Dbg] [PathManager.cc:68] Requesting resource paths through [/gazebo/resource_paths/get]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Gui.cc:355] GUI requesting list of world names. The server may be busy downloading resources. Please be patient.
[ruby $(which gz) sim-1] [GUI] [Dbg] [PathManager.cc:57] Received resource paths.
[ruby $(which gz) sim-1] [GUI] [Dbg] [Gui.cc:413] Requesting GUI from [/world/rover/gui/info]...
[ruby $(which gz) sim-1] [GUI] [Dbg] [GuiRunner.cc:149] Requesting initial state from [/world/rover/state]...
[ruby $(which gz) sim-1] [GUI] [Msg] Loading config [/root/.gz/sim/8/gui.config]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [MinimalScene]
[ruby $(which gz) sim-1] [GUI] [Dbg] [MinimalScene.cc:802] Creating gz-rendering interface for OpenGL
[ruby $(which gz) sim-1] [GUI] [Dbg] [MinimalScene.cc:802] Creating gz-rendering interface for OpenGL
[ruby $(which gz) sim-1] [GUI] [Dbg] [MinimalScene.cc:986] Creating render thread interface for OpenGL
[ruby $(which gz) sim-1] [GUI] [Dbg] [MinimalScene.cc:802] Creating gz-rendering interface for OpenGL
[ruby $(which gz) sim-1] [GUI] [Dbg] [MinimalScene.cc:986] Creating render thread interface for OpenGL
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [3D View] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [MinimalScene] from path [/usr/lib/x86_64-linux-gnu/gz-gui-8/plugins/libMinimalScene.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [EntityContextMenuPlugin]
[ruby $(which gz) sim-1] [GUI] [Msg] Currently tracking topic on [/gui/currently_tracked]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Entity Context Menu] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [EntityContextMenuPlugin] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libEntityContextMenuPlugin.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [GzSceneManager]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Scene Manager] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [GzSceneManager] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libGzSceneManager.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [InteractiveViewControl]
[ruby $(which gz) sim-1] [GUI] [Msg] Camera view controller topic advertised on [/gui/camera/view_control]
[ruby $(which gz) sim-1] [GUI] [Msg] Camera reference visual topic advertised on [/gui/camera/view_control/reference_visual]
[ruby $(which gz) sim-1] [GUI] [Msg] Camera view control sensitivity advertised on [/gui/camera/view_control/sensitivity]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Interactive view control] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [InteractiveViewControl] from path [/usr/lib/x86_64-linux-gnu/gz-gui-8/plugins/libInteractiveViewControl.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [CameraTracking]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Camera tracking] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [CameraTracking] from path [/usr/lib/x86_64-linux-gnu/gz-gui-8/plugins/libCameraTracking.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [MarkerManager]
[ruby $(which gz) sim-1] [GUI] [Msg] Listening to stats on [/world/rover/stats]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Marker Manager] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [MarkerManager] from path [/usr/lib/x86_64-linux-gnu/gz-gui-8/plugins/libMarkerManager.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [SelectEntities]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Select entities] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [SelectEntities] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libSelectEntities.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [Spawn]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Spawn] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [Spawn] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libSpawn.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [VisualizationCapabilities]
[ruby $(which gz) sim-1] [GUI] [Msg] View as transparent service on [/gui/view/transparent]
[ruby $(which gz) sim-1] [GUI] [Msg] View as wireframes service on [/gui/view/wireframes]
[ruby $(which gz) sim-1] [GUI] [Msg] View center of mass service on [/gui/view/com]
[ruby $(which gz) sim-1] [GUI] [Msg] View inertia service on [/gui/view/inertia]
[ruby $(which gz) sim-1] [GUI] [Msg] View collisions service on [/gui/view/collisions]
[ruby $(which gz) sim-1] [GUI] [Msg] View joints service on [/gui/view/joints]
[ruby $(which gz) sim-1] [GUI] [Msg] View frames service on [/gui/view/frames]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Visualization capabilities] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [VisualizationCapabilities] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libVisualizationCapabilities.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [WorldControl]
[ruby $(which gz) sim-1] [GUI] [Msg] Using world control service [/world/rover/control]
[ruby $(which gz) sim-1] [GUI] [Msg] Listening to stats on [/world/rover/stats]
[ruby $(which gz) sim-1] [GUI] [Dbg] [WorldControl.cc:237] Using an event to share WorldControl msgs with the server
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [World control] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [WorldControl] from path [/usr/lib/x86_64-linux-gnu/gz-gui-8/plugins/libWorldControl.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [WorldStats]
[ruby $(which gz) sim-1] [GUI] [Msg] Listening to stats on [/world/rover/stats]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [World stats] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [WorldStats] from path [/usr/lib/x86_64-linux-gnu/gz-gui-8/plugins/libWorldStats.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [Shapes]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Shapes] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [Shapes] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libShapes.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [Lights]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Lights] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [Lights] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libLights.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [TransformControl]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Transform control] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [TransformControl] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libTransformControl.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [Screenshot]
[ruby $(which gz) sim-1] [GUI] [Msg] Screenshot service on [/gui/screenshot]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Screenshot] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [Screenshot] from path [/usr/lib/x86_64-linux-gnu/gz-gui-8/plugins/libScreenshot.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [CopyPaste]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Copy/Paste] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [CopyPaste] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libCopyPaste.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [ComponentInspector]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Component inspector] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [ComponentInspector] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libComponentInspector.so]
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.cc:528] Loading plugin [EntityTree]
[ruby $(which gz) sim-1] [GUI] [Msg] Currently tracking topic on [/gui/currently_tracked]
[ruby $(which gz) sim-1] [GUI] [Msg] Added plugin [Entity tree] to main window
[ruby $(which gz) sim-1] [GUI] [Msg] Loaded plugin [EntityTree] from path [/usr/lib/x86_64-linux-gnu/gz-sim-8/plugins/gui/libEntityTree.so]
[ruby $(which gz) sim-1] [GUI] [Wrn] [Application.cc:908] [QT] file::/WorldStats/WorldStats.qml:53:3: QML RowLayout: Binding loop detected for property "x"
[ruby $(which gz) sim-1] libEGL warning: MESA-LOADER: failed to open vgem: /usr/lib/dri/vgem_dri.so: cannot open shared object file: No such file or directory (search paths /usr/lib/x86_64-linux-gnu/dri:\$${ORIGIN}/dri:/usr/lib/dri, suffix _dri)
[ruby $(which gz) sim-1]
[ruby $(which gz) sim-1] libEGL warning: NEEDS EXTENSION: falling back to kms_swrast
[ruby $(which gz) sim-1] [GUI] [Wrn] [Ogre2RenderTarget.cc:668] Anti-aliasing level of ' is not supported; valid FSAA levels are: [ 0 4 ]. Setting to 1
[ruby $(which gz) sim-1] [GUI] [Dbg] [Application.1;32m].
[ruby $(which gz) sim-1] [Msg] Resource path resolve service on [/gazebo/resource_paths/resolve].
[ruby $(which gz) sim-1] [Msg] Resource paths published on [/gazebo/resource_paths].
[ruby $(which gz) sim-1] [Msg] Server control service on [/server_control].
[ruby $(which gz) sim-1] [Msg] Found no publishers on /stats, adding root stats topic
[ruby $(which gz) sim-1] [Msg] Found no publishers on /clock, adding root clock topic
[ruby $(which gz) sim-1] [Dbg] [SimulationRunner.cc:533] Creating PostUpdate worker threads: 2
[ruby $(which gz) sim-1] [Dbg] [SimulationRunner.cc:544] Creating postupdate worker thread (0)
[ruby $(which gz) sim-1] [Dbg] [JointController.cc:161] [JointController] Velocity mode
[ruby $(which gz) sim-1] [Msg] JointController subscribing to Actuator messages on [/model/sentroproto/command/motor_speed]
[ruby $(which gz) sim-1] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::JointController] for entity [10]
[ruby $(which gz) sim-1] [Dbg] [JointController.cc:161] [JointController] Velocity mode
[ruby $(which gz) sim-1] [Msg] JointController subscribing to Actuator messages on [/model/sentroproto/command/motor_speed]
[ruby $(which gz) sim-1] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::JointController] for entity [10]
[ruby $(which gz) sim-1] [Dbg] [JointController.cc:161] [JointController] Velocity mode
[ruby $(which gz) sim-1] [Msg] JointController subscribing to Actuator messages on [/model/sentroproto/command/motor_speed]
[ruby $(which gz) sim-1] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::JointController] for entity [10]
[ruby $(which gz) sim-1] [Dbg] [JointController.cc:161] [JointController] Velocity mode
[ruby $(which gz) sim-1] [Msg] JointController subscribing to Actuator messages on [/model/sentroproto/command/motor_speed]
[ruby $(which gz) sim-1] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::JointController] for entity [10]
[ruby $(which gz) sim-1] [Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::JointStatePublisher] for entity [10]
[ruby $(which gz) sim-1] [Dbg] [UserCommands.cc:1318] Created entity [10] named [sentroproto]
[ruby $(which gz) sim-1] [Dbg] [SimulationFeatures.cc:90] Simulation timestep set to: 0.002
[ruby $(which gz) sim-1] [Msg] Serving scene information on [/world/rover/scene/info]
[ruby $(which gz) sim-1] [Msg] Serving graph information on [/world/rover/scene/graph]
[ruby $(which gz) sim-1] [Msg] Serving full state on [/world/rover/state]
[ruby $(which gz) sim-1] [Msg] Serving full state (async) on [/world/rover/state_async]
[ruby $(which gz) sim-1] [Msg] Publishing scene information on [/world/rover/scene/info]
[ruby $(which gz) sim-1] [Msg] Publishing entity deletions on [/world/rover/scene/deletion]
[ruby $(which gz) sim-1] [Msg] Publishing state changes on [/world/rover/state]
[ruby $(which gz) sim-1] [Msg] Publishing pose messages on [/world/rover/pose/info]
I found this line in Gazebo’s logs concerning: No systems loaded from SDF, loading defaults
Is there something I need to add to GZ_SIM_SYSTEM_PLUGIN_PATH for these sensors to load?
Should ./build/px4_sitl_default/build_gz contain something worth pointing at? It’s empty.
Thanks