Skip to content

[Bug] GZ symbol lookup error with custom plugin #25866

@Fildo7525

Description

@Fildo7525

Describe the bug

I wanted to add the vrx plugins into the PX4 to adjust my simulation environment. However, as the title says, I cannot run the simulation with custom plugins. I always get an error:

gz sim --verbose=4 -r -s ~PX4-Autopilot/Tools/simulation/gz/worlds/nbpark.sdf: symbol lookup error: ~/PX4-Autopilot/build/px4_sitl_default/src/modules/simulation/gz_plugins/libSurface.so: undefined symbol: _ZN6custom9WavefieldC1Ev

Even though the symbol exists

$ readelf -Ws ~/PX4-Autopilot/build/px4_sitl_default/src/modules/simulation/gz_plugins/libSurface.so | grep _ZN6custom9WavefieldC1Ev
   127: 0000000000000000     0 NOTYPE  GLOBAL DEFAULT  UND _ZN6custom9WavefieldC1Ev
   459: 0000000000000000     0 NOTYPE  GLOBAL DEFAULT  UND _ZN6custom9WavefieldC1Ev

To Reproduce

  1. Copy all the plugins files to src/modules/simulation/gz_plugins/vrx/ and adjust so that everything compiels and change the namespace to custom
    (It is in this patch)

0001-gz_plugins-add-vrx-custom-plugins.patch

  1. Register all the plugins
    0001-gz_bridge-register-plugins.patch

  2. In a model add this code

<?xml version="1.0"?>
<sdf version="1.6">
	<model name="my_robot">
		<link name="base_link">
			<!-- load the model and setup inertial tag -->
			<collision name="main_body_collision_lower_back">
				<pose relative_to="base_link">0 0.35 -0.15 1.5707 0 1.5707</pose>
				<geometry>
					<box>
						<size>0.85 0.2 0.4</size>
					</box>
				</geometry>
			</collision>
		</link>


		<!-- the model configuration -->
		<plugin
			filename="libSurface.so"
			name="custom::Surface">
			<!-- https://github.com/osrf/vrx/blob/jazzy/vrx_gz/src/Surface.hh -->
			<link_name>base_link</link_name>
			<hull_length>1.54</hull_length>
			<hull_radius>0.3</hull_radius>
			<fluid_level>0</fluid_level>
			<points>
				<point>0 -0.1 0</point>
				<point>0 0 0</point>
				<point>0 0.1 0</point>
				<point>0 0.2 0</point>
				<point>0 0.3 0</point>
				<point>0 0.4 0</point>
				<point>0 0.5 0</point>
			</points>
			<wavefield>
				<topic>/vrx/wavefield/parameters</topic>
			</wavefield>
		</plugin>
	</model>
</sdf>
  1. Add the model as a new configuration new ariframe and run
make px4_sitl my_robot

Expected behavior

The plugin does load, and everything works.

Screenshot / Media

output

$ GZ_VERBOSE=4 make px4_sitl gz_my_robot
[0/1] cd ~/PX4-Autopilot/build/px4_sitl_default/src/modules/simula...agt GZ_IP=127.0.0.1 ~/PX4-Autopilot/build/px4_sitl_default/bin/px4

______  __   __    ___ 
| ___ \ \ \ / /   /   |
| |_/ /  \ V /   / /| |
|  __/   /   \  / /_| |
| |     / /^\ \ \___  |
\_|     \/   \/     |_/

px4 starting.

INFO  [px4] startup script: /bin/sh etc/init.d-posix/rcS 0
INFO  [init] found model autostart file as SYS_AUTOSTART=4022
INFO  [param] selected parameter default file parameters.bson
INFO  [param] importing from 'parameters.bson'
INFO  [parameters] BSON document size 327 bytes, decoded 327 bytes (INT32:14, 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:~/PX4-Autopilot/Tools/simulation/gz/worlds/nbpark.sdf
INFO  [init] Starting gz gui
[Msg] Gazebo Sim Server v8.9.0
[Msg] Loading SDF world file[~/PX4-Autopilot/Tools/simulation/gz/worlds/nbpark.sdf].
[Msg] Serving entity system service on [/entity/system/add]
[Dbg] [Physics.cc:883] Loaded [gz::physics::dartsim::Plugin] from library [/opt/ros/jazzy/opt/gz_physics_vendor/lib/gz-physics-7/engine-plugins/libgz-physics-dartsim-plugin.so]
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::Physics] for entity [1]
[Msg] Create service on [/world/nbpark/create]
[Msg] Remove service on [/world/nbpark/remove]
[Msg] Pose service on [/world/nbpark/set_pose]
[Msg] Pose service on [/world/nbpark/set_pose_vector]
[Msg] Light configuration service on [/world/nbpark/light_config]
[Msg] Physics service on [/world/nbpark/set_physics]
[Msg] SphericalCoordinates service on [/world/nbpark/set_spherical_coordinates]
[Msg] Enable collision service on [/world/nbpark/enable_collision]
[Msg] Disable collision service on [/world/nbpark/disable_collision]
[Msg] Material service on [/world/nbpark/visual_config]
[Msg] Material service on [/world/nbpark/wheel_slip]
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::UserCommands] for entity [1]
[Dbg] [Sensors.cc:697] Configuring Sensors system
[Dbg] [Sensors.cc:557] SensorsPrivate::Run
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::Sensors] for entity [1]
[Dbg] [Sensors.cc:532] SensorsPrivate::RenderThread started
[Dbg] [Sensors.cc:337] Waiting for init
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::Imu] for entity [1]
[Dbg] [Magnetometer.cc:261] Magnetometer: using param [use_units_gauss: 1].
[Dbg] [Magnetometer.cc:269] Magnetometer: using param [use_earth_frame_ned: 1].
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::Magnetometer] for entity [1]
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::ForceTorque] for entity [1]
[Msg] Serving particle emitter information on [/world/nbpark/particle_emitters]
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::ParticleEmitter] for entity [1]
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::SceneBroadcaster] for entity [1]
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::Contact] for entity [1]
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::NavSat] for entity [1]
[Dbg] [USVWind.cc:160] wamv loaded
[Msg] Wind direction unit vector = -0.5 -0.866025 0
[Msg] Wind mean velocity = 0
[Msg] var wind gain constants = 0
[Msg] var wind time constants = 2
[Msg] update rate  = 10
[Msg] topic wind speed  = /vrx/debug/wind/speed
[Msg] topic wind direction = /vrx/debug/wind/direction
[Msg] Random seed value = 10
[Msg] Var wind filter gain = 0
[Dbg] [SystemManager.cc:80] Loaded system [custom::USVWind] for entity [1]
[Dbg] [SystemManager.cc:80] Loaded system [custom::PublisherPlugin] for entity [1]
[Msg] Loaded level [default]
[Msg] Serving world controls on [/world/nbpark/control], [/world/nbpark/control/state] and [/world/nbpark/playback/control]
[Msg] Serving GUI information on [/world/nbpark/gui/info]
[Msg] World [nbpark] initialized with [4ms] physics profile.
[Msg] Serving world SDF generation service on [/world/nbpark/generate_world_sdf]
[Msg] Serving world names on [/gazebo/worlds]
[Msg] Resource path add service on [/gazebo/resource_paths/add].
[Msg] Resource path get service on [/gazebo/resource_paths/get].
[Msg] Resource path resolve service on [/gazebo/resource_paths/resolve].
[Msg] Resource paths published on [/gazebo/resource_paths].
[Msg] Server control service on [/server_control].
INFO  [init] Waiting for Gazebo world...
[Msg] Found no publishers on /stats, adding root stats topic
[Msg] Found no publishers on /clock, adding root clock topic
[Dbg] [SimulationRunner.cc:533] Creating PostUpdate worker threads: 8
[Dbg] [SimulationRunner.cc:544] Creating postupdate worker thread (0)
[Dbg] [SimulationRunner.cc:544] Creating postupdate worker thread (1)
[Dbg] [SimulationRunner.cc:544] Creating postupdate worker thread (2)
[Dbg] [SimulationRunner.cc:544] Creating postupdate worker thread (3)
[Dbg] [SimulationRunner.cc:544] Creating postupdate worker thread (4)
[Dbg] [SimulationRunner.cc:544] Creating postupdate worker thread (5)
[Dbg] [SimulationRunner.cc:544] Creating postupdate worker thread (6)
[Dbg] [SimulationFeatures.cc:90] Simulation timestep set to: 0.004
[Msg] Serving scene information on [/world/nbpark/scene/info]
[Msg] Serving graph information on [/world/nbpark/scene/graph]
[Msg] Serving full state on [/world/nbpark/state]
[Msg] Serving full state (async) on [/world/nbpark/state_async]
[Msg] Publishing scene information on [/world/nbpark/scene/info]
[Msg] Publishing entity deletions on [/world/nbpark/scene/deletion]
[Msg] Publishing state changes on [/world/nbpark/state]
[Msg] Publishing pose messages on [/world/nbpark/pose/info]
[Msg] Publishing dynamic pose messages on [/world/nbpark/dynamic_pose/info]
[Dbg] [EntityComponentManager.cc:1656] Updated state thread iterators: 5 threads processing around 1 entities each.
INFO  [init] Gazebo world is ready
INFO  [init] Spawning model
[Msg] Thruster listening to commands on [/model/my_robot_0/joint/left_engine_propeller_joint/cmd_thrust]
[Msg] Thruster listening to enable_deadband on [/model/my_robot_0/joint/left_engine_propeller_joint/enable_deadband]
[Dbg] [Thruster.cc:496] Using velocity control for propeller joint.
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::Thruster] for entity [6]
[Msg] Thruster listening to commands on [/model/my_robot_0/joint/right_engine_propeller_joint/cmd_thrust]
[Msg] Thruster listening to enable_deadband on [/model/my_robot_0/joint/right_engine_propeller_joint/enable_deadband]
[Dbg] [Thruster.cc:496] Using velocity control for propeller joint.
[Dbg] [SystemManager.cc:80] Loaded system [gz::sim::systems::Thruster] for entity [6]
gz sim --verbose=4 -r -s ~/PX4-Autopilot/Tools/simulation/gz/worlds/nbpark.sdf: symbol lookup error: ~/PX4-Autopilot/build/px4_sitl_default/src/modules/simulation/gz_plugins/libSurface.so: undefined symbol: _ZN6custom9WavefieldC1Ev
INFO  [gz_bridge] world: nbpark, model: my_robot_0
INFO  [commander] LED: open /dev/led0 failed (22)
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-11-03/23_34_43.ulg	
INFO  [logger] Opened full log file: ./log/2025-11-03/23_34_43.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> 

Flight Log

No response

Software Version

No response

Flight controller

No response

Vehicle type

None

How are the different components wired up (including port information)

No response

Additional context

No response

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions