Giter Site home page Giter Site logo

ardupilot / ardupilot_gazebo Goto Github PK

View Code? Open in Web Editor NEW
86.0 12.0 83.0 40.09 MB

Plugins and models for vehicle simulation in Gazebo Sim with ArduPilot SITL controllers

License: GNU Lesser General Public License v3.0

CMake 3.49% C++ 96.30% Shell 0.20%
ardupilot gazebo simulation sitl

ardupilot_gazebo's Introduction

ArduPilot Gazebo Plugin

ubuntu-build ccplint cppcheck

This is the official ArduPilot plugin for Gazebo. It replaces the previous ardupilot_gazebo plugin and provides support for the recent releases of the Gazebo simulator (Gazebo Garden) and (Gazebo Harmonic).

It also adds the following features:

  • More flexible data exchange between SITL and Gazebo using JSON.
  • Additional sensors supported.
  • True simulation lockstepping. It is now possible to use GDB to stop the Gazebo time for debugging.
  • Improved 3D rendering using the ogre2 rendering engine.

The project comprises a Gazebo plugin to connect to ArduPilot SITL (Software In The Loop) and some example models and worlds.

Prerequisites

Gazebo Garden or Harmonic is supported on Ubuntu 22.04 (Jammy). Harmonic is recommended. If you are running Ubuntu as a virtual machine you will need at least Ubuntu 20.04 in order to have the OpenGL support required for the ogre2 render engine. Gazebo and ArduPilot SITL will also run on macOS (Big Sur, Monterey and Venturua; Intel and M1 devices).

Follow the instructions for a binary install of Gazebo Garden or Gazebo Harmonic and verify that Gazebo is running correctly.

Set up an ArduPilot development environment. In the following it is assumed that you are able to run ArduPilot SITL using the MAVProxy GCS.

Installation

Install additional dependencies:

Ubuntu

Garden (apt)

Manual - Gazebo Garden Dependencies:

sudo apt update
sudo apt install libgz-sim7-dev rapidjson-dev
sudo apt install libopencv-dev libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev gstreamer1.0-plugins-bad gstreamer1.0-libav gstreamer1.0-gl

Harmonic (apt)

Manual - Gazebo Harmonic Dependencies:

sudo apt update
sudo apt install libgz-sim8-dev rapidjson-dev
sudo apt install libopencv-dev libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev gstreamer1.0-plugins-bad gstreamer1.0-libav gstreamer1.0-gl

Rosdep

Use rosdep with osrf's rosdep rules to manage all dependencies. This is driven off of the environment variable GZ_VERSION.

export GZ_VERSION=harmonic # or garden
sudo bash -c 'wget https://raw.githubusercontent.com/osrf/osrf-rosdep/master/gz/00-gazebo.list -O /etc/ros/rosdep/sources.list.d/00-gazebo.list'
rosdep update
rosdep resolve gz-harmonic # or gz-garden
# Navigate to your ROS workspace before the next command.
rosdep install --from-paths src --ignore-src -y

macOS

brew update
brew install rapidjson
brew install opencv gstreamer

Ensure the GZ_VERSION environment variable is set to either garden or harmonic.

Clone the repo and build:

git clone https://github.com/ArduPilot/ardupilot_gazebo
cd ardupilot_gazebo
mkdir build && cd build
cmake .. -DCMAKE_BUILD_TYPE=RelWithDebInfo
make -j4

Configure

Set the Gazebo environment variables in your .bashrc or .zshrc or in the terminal used to run Gazebo.

Terminal

Assuming that you have cloned the repository to $HOME/ardupilot_gazebo:

export GZ_SIM_SYSTEM_PLUGIN_PATH=$HOME/ardupilot_gazebo/build:$GZ_SIM_SYSTEM_PLUGIN_PATH
export GZ_SIM_RESOURCE_PATH=$HOME/ardupilot_gazebo/models:$HOME/ardupilot_gazebo/worlds:$GZ_SIM_RESOURCE_PATH

.bashrc or .zshrc

Assuming that you have cloned the repository to $HOME/ardupilot_gazebo:

echo 'export GZ_SIM_SYSTEM_PLUGIN_PATH=$HOME/ardupilot_gazebo/build:${GZ_SIM_SYSTEM_PLUGIN_PATH}' >> ~/.bashrc
echo 'export GZ_SIM_RESOURCE_PATH=$HOME/ardupilot_gazebo/models:$HOME/ardupilot_gazebo/worlds:${GZ_SIM_RESOURCE_PATH}' >> ~/.bashrc

Reload your terminal with source ~/.bashrc (or source ~/.zshrc on macOS).

Usage

1. Iris quad-copter

Run Gazebo

gz sim -v4 -r iris_runway.sdf

The -v4 parameter is not mandatory, it shows additional information and is useful for troubleshooting.

Run ArduPilot SITL

To run an ArduPilot simulation with Gazebo, the frame should have gazebo- in it and have JSON as model. Other commandline parameters are the same as usual on SITL.

sim_vehicle.py -v ArduCopter -f gazebo-iris --model JSON --map --console

Arm and takeoff

STABILIZE> mode guided
GUIDED> arm throttle
GUIDED> takeoff 5

2. Zephyr delta wing

The Zephyr delta wing is positioned on the runway for vertical take-off.

Run Gazebo

gz sim -v4 -r zephyr_runway.sdf

Run ArduPilot SITL

sim_vehicle.py -v ArduPlane -f gazebo-zephyr --model JSON --map --console

Arm, takeoff and circle

MANUAL> mode fbwa
FBWA> arm throttle
FBWA> rc 3 1800
FBWA> mode circle

Increase the simulation speed

The zephyr_runway.sdf world has a <physics> element configured to run faster than real time:

<physics name="1ms" type="ignore">
  <max_step_size>0.001</max_step_size>
  <real_time_factor>-1.0</real_time_factor>
</physics>

To see the effect of the speed-up set the param SIM_SPEEDUP to a value greater than one:

MANUAL> param set SIM_SPEEDUP 10

3. Streaming camera video

Images from camera sensors may be streamed with GStreamer using the GstCameraPlugin sensor plugin. The example gimbal models include the plugin element:

<plugin name="GstCameraPlugin"
    filename="GstCameraPlugin">
  <udp_host>127.0.0.1</udp_host>
  <udp_port>5600</udp_port>
  <use_basic_pipeline>true</use_basic_pipeline>
  <use_cuda>false</use_cuda>
</plugin>

The <image_topic> and <enable_topic> parameters are deduced from the topic name for the camera sensor, but may be overriden if required.

The gimbal.sdf world includes a 3 degrees of freedom gimbal with a zoomable camera. To start streaming:

gz topic -t /world/gimbal/model/mount/model/gimbal/link/pitch_link/sensor/camera/image/enable_streaming -m gz.msgs.Boolean -p "data: 1"

Display the streamed video:

gst-launch-1.0 -v udpsrc port=5600 caps='application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264' ! rtph264depay ! avdec_h264 ! videoconvert ! autovideosink sync=false

View the streamed camera frames in QGC:

Open QGC > Application Settings > Video Settings > Select UDP h.264 Video Stream & use port 5600

qgc_video_settings

4. Using 3d Gimbal

The Iris model is equipped with a 3d gimbal and camera that can be controlled directly in MAVProxy using the RC overrides.

Run Gazebo

gz sim -v4 -r iris_runway.sdf

Run ArduPilot SITL with a specified parameter file

cd ardupilot

sim_vehicle.py -D -v ArduCopter -f JSON --add-param-file=$HOME/ardupilot_gazebo/config/gazebo-iris-gimbal.parm --console --map

Control action for gimbal over RC channel:

Action Channel RC Low RC High
Roll RC6 Roll Left Roll Right
Pitch RC7 Pitch Down Pitch Up
Yaw RC8 Yaw Left Yaw Right

Example usage:

rc 6 1100 - Gimbal rolls left

rc 7 1900 - Gimbal pitch upwards

rc 8 1500 - Gimbal yaw neutral

Models

In addition to the Iris and Zephyr models included here, a selection of models configured use the ArduPilot Gazebo plugin is available in ArduPilot/SITL_Models. Click on the images to see further details.

Troubleshooting

For issues concerning installing and running Gazebo on your platform please consult the Gazebo documentation for troubleshooting frequent issues.

ardupilot_gazebo's People

Contributors

41mo avatar acxz avatar kant avatar khancyr avatar ryanf55 avatar snktshrma avatar srmainwaring avatar swiftgust avatar tridge avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

ardupilot_gazebo's Issues

Fail to display the streamed video in QGC with <use_cuda> set to true

Bug report

Issue details
QGC can not render the video stream according to the guide. The camera topic can be seen from the image display in gazebo-garden, but QGC can not display the same video stream with default port 5600. ArduPilot SITL console can be launched successfully and used to control the iris in gazebo.

Running gst-launch-1.0:

gst-launch-1.0 -v udpsrc port=5600 caps='application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264' ! rtph264depay ! avdec_h264 ! videoconvert ! autovideosink sync=false
Setting pipeline to PAUSED ...
Pipeline is live and does not need PREROLL ...
/GstPipeline:pipeline0/GstUDPSrc:udpsrc0.GstPad:src: caps = application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264
Setting pipeline to PLAYING ...
New clock: GstSystemClock
/GstPipeline:pipeline0/GstRtpH264Depay:rtph264depay0.GstPad:sink: caps = application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264

Running gz topic and find the msg is not publishing at 127.0.0.1. Is that normal?

gz topic -i -t /world/iris_runway/model/iris_with_gimbal/model/gimbal/link/pitch_link/sensor/camera/image
Publishers [Address, Message Type]:
  tcp://172.16.6.163:38773, gz.msgs.Image

QGC can not find the camera:

./GCS\ Software/QGroundControl.AppImage 
Settings location "/home/xliu/.config/QGroundControl.org/QGroundControl.ini" Is writable?: true
Filter rules "*Log.debug=false\nGStreamerAPILog.debug=true\nqt.qml.connections=false"
System reported locale: QLocale(English, Latin, United States) ; Name "en_US" ; Preffered (used in maps):  "en-US"
MAVLinkLogManagerLog: MAVLink logs directory: "/home/xliu/Documents/QGroundControl/Logs"
Map Cache in: "/home/xliu/.cache/QGCMapCache300" / "qgcMapCache.db"
setCurrentPlanViewSeqNum
setCurrentPlanViewSeqNum
"v4.3.0"
Adding target QHostAddress("127.0.0.1") 36638
setCurrentPlanViewSeqNum
setCurrentPlanViewSeqNum
setCurrentPlanViewSeqNum
setCurrentPlanViewSeqNum
VideoReceiverLog: Stop called on empty URI
VideoReceiverLog: Stop called on empty URI
FactPanelControllerLog: Missing parameter: "1:MNT_RC_IN_PAN"
FactPanelControllerLog: Missing parameter: "1:MNT_STAB_PAN"
FactPanelControllerLog: Missing parameter: "1:MNT_ANGMIN_PAN"
FactPanelControllerLog: Missing parameter: "1:MNT_ANGMAX_PAN"
FactPanelControllerLog: Missing parameter: "1:MNT_RC_IN_ROLL"
FactPanelControllerLog: Missing parameter: "1:MNT_STAB_ROLL"
FactPanelControllerLog: Missing parameter: "1:MNT_ANGMIN_ROL"
FactPanelControllerLog: Missing parameter: "1:MNT_ANGMAX_ROL"
FactPanelControllerLog: Missing parameter: "1:MNT_RC_IN_TILT"
FactPanelControllerLog: Missing parameter: "1:MNT_STAB_TILT"
FactPanelControllerLog: Missing parameter: "1:MNT_ANGMIN_TIL"
FactPanelControllerLog: Missing parameter: "1:MNT_ANGMAX_TIL"
FactPanelControllerLog: Missing parameter: "1:MNT_RETRACT_X"
FactPanelControllerLog: Missing parameter: "1:MNT_RETRACT_Y"
FactPanelControllerLog: Missing parameter: "1:MNT_RETRACT_Z"
FactPanelControllerLog: Missing parameter: "1:MNT_NEUTRAL_X"
FactPanelControllerLog: Missing parameter: "1:MNT_NEUTRAL_Y"
FactPanelControllerLog: Missing parameter: "1:MNT_NEUTRAL_Z"
FactPanelControllerLog: Missing parameter: "1:BRD_PWM_COUNT"
qrc:/qml/APMCameraComponent.qml:193: TypeError: Cannot read property 'value' of null
VideoReceiverLog: Stop called on empty URI
Quit event true
Done
VideoReceiverLog: Stop called on empty URI
After app delete

The gimbal camera is actually working in gazebo-garden:
bug

Version
Master branch

Platform
[ ] All
[ ] AntennaTracker
[ x ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Zephyr: update model to conform to ROS REP 105

Feature request

Is your feature request related to a problem? Please describe.

  • The zephyr model does not conform to ROS REP 105.
  • This is a problem as users may take the zephyr as a template for adding new models, and propagate the unconventional orientation (for example see: ArduPilot/SITL_Models#116).

Describe the solution you'd like

Describe alternatives you've considered

Platform
[ ] All
[ ] AntennaTracker
[ ] Copter
[ x] Plane
[ ] Rover
[ ] Submarine

Video update rate and cuda are not working.

Bug report

Issue details

I am changing the camera settings for the simulation but enabling cuda and changing update rate are not working. When enabeling cuda, <use_cuda>true</use_cuda>, there is no more video output. When changing the <update_rate>20</update_rate>, there is no change in FPS. The image resolution changes without issues.

I am using an NVIDIA L4 gpu, with NVIDIA L4 VRAM. There is barely any usage.

This is the configuration file.

  <sensor name="camera" type="camera">
    <pose>0 0 0 -1.57 -1.57 0</pose>
    <camera>
      <horizontal_fov>2.0</horizontal_fov>
      <image>
        <width>32</width>
        <height>24</height>
      </image>
      <clip>
        <near>0.05</near>
        <far>15000</far>
      </clip>
    </camera>
    <always_on>1</always_on>
    <update_rate>20</update_rate>
    <visualize>1</visualize>

    <plugin filename="CameraZoomPlugin"
        name="CameraZoomPlugin">
      <max_zoom>125.0</max_zoom>
      <slew_rate>0.42514285714</slew_rate>
    </plugin>
    
    <plugin name="GstCameraPlugin"
        filename="GstCameraPlugin">
      <udp_host>127.0.0.1</udp_host>
      <udp_port>5600</udp_port>
      <use_basic_pipeline>true</use_basic_pipeline>
      <use_cuda>true</use_cuda>
    </plugin>

  </sensor>

Gsteamer command

gst-launch-1.0 -v udpsrc port=5600 caps='application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264' ! rtph264depay ! avdec_h264 ! videoconvert ! fpsdisplaysink video-sink=autovideosink sync=false
Setting pipeline to PAUSED ...
Pipeline is live and does not need PREROLL ...
Got context from element 'autovideosink0': gst.gl.GLDisplay=context, gst.gl.GLDisplay=(GstGLDisplay)"\(GstGLDisplayX11\)\ gldisplayx11-0";
/GstPipeline:pipeline0/GstFPSDisplaySink:fpsdisplaysink0/GstAutoVideoSink:autovideosink0/GstGLImageSinkBin:autovideosink0-actual-sink-glimage/GstGLImageSink:sink: sync = false
/GstPipeline:pipeline0/GstFPSDisplaySink:fpsdisplaysink0/GstAutoVideoSink:autovideosink0/GstGLImageSinkBin:autovideosink0-actual-sink-glimage: sync = false
Pipeline is PREROLLED ...
Setting pipeline to PLAYING ...
/GstPipeline:pipeline0/GstUDPSrc:udpsrc0.GstPad:src: caps = application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264
New clock: GstSystemClock
/GstPipeline:pipeline0/GstRtpH264Depay:rtph264depay0.GstPad:sink: caps = application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264

Logs

[Msg] GstCameraPlugin: image topic [world/iris_runway/model/iris_with_gimbal/model/gimbal/link/pitch_link/sensor/camera/image]
[Msg] GstCameraPlugin: enable topic [world/iris_runway/model/iris_with_gimbal/model/gimbal/link/pitch_link/sensor/camera/image/enable_streaming]
[Dbg] [CameraSensor.cc:480] Enabling camera sensor: 'iris_with_gimbal::gimbal::pitch_link::camera' data generation.
[Msg] GstCameraPlugin:: streaming: started
[Dbg] [GstCameraPlugin.cc:407] GstCameraPlugin: creating generic pipeline
[Dbg] [GstCameraPlugin.cc:477] Using Cuda
[Msg] GstCameraPlugin: GStreamer element set state returned: 2
[Msg] GstCameraPlugin: starting GStreamer main loop

Version
Master branch

Platform
[ ] All
[ ] AntennaTracker
[X] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Add support for using Ardupilot FDM for the vehicle dynamics instead of Gazebo

Feature request

Is your feature request related to a problem? Please describe.

Creating a gazebo model, with lift/drag coefficients requires precise knowledge of the vehicle. This is only needed if you want gazebo to run physics on the vehicle. What if I want to use gazebo for doing robotics-type stuff like path planning, computer vision, and SLAM, but don't have experience with aerodynamics?

Describe the solution you'd like

Perhaps a simpler approach for people using gazebo is to have ArduPilot SITL run the FDM, send the FDM state to gazebo, and then have Gazebo skip running physics on the vehicle.

This has the cost of removing collision support, but the advantage is now you can drive a lot more of the vehicle behavior from the Ardupilot SIM* parameters.

In it's simplest form, reproduce this demo on gazebo harmonic:

Describe alternatives you've considered

Learning more aerodynamics and how the lift/drag plugin works.

Platform
[ ] All
[ ] AntennaTracker
[x] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Additional context

To create a new plane, here are the steps it looks like you need based on the current zephyr.sdf file. This is a lot of work. A user on the discord server asked how to do it for a cessna-style plane. I've tried to summarize the process here

zephyr.sdf

  1. Create links for all the parts of the vehicle
    • wing
    • propellor
    • flap_left
    • flap_right
    • imu_link
  2. Each link you need to know
    • pose
    • mass
    • Inertia
    • a visual geometry which can be either a mesh in .dae format or a simple collision box
    • a collision geometry, same as above, and you can re-use a the .dae file
  3. The wing link also has collision boxes defined with the rudders (seems this is to have mechanical limits of the elevon throws)
  4. Create joints (all are revolute)
    • flap_left_joint
    • flap_right_joint
    • imu_joint
    • propeller_joint
  5. For each of the joints, you need to know
  • damping coefficient
  • For the flaps, you also have axis limits, which seem redundant with having collision defined above

zephyr_with_ardupilot.sdf

Here is where you add the plugins of:

  • gz-sim-joint-state-publisher-system
  • gz-sim-lift-drag-system
  • gz-sim-apply-joint-force-system
  • ArduPilotPlugin

The lift drag plugin seems quite complex to understand all the aerodynamic values. Hence, the motivation to just use the ArduPilot FDM.

CameraZoomPlugin is not updating topic camera_info

Bug report

Issue details

The CameraZoomPlugin does not update the camera intrinsics published in the /world/{world}/model/{model}/link/{link}/sensor/{sensor}/camera_info (gz.msgs.CameraInfo) topic.

Version

  • main

Steps to replicate:

  • Run an example containing a model equipped with the gimbal_small_3d which includes a camera sensor and CameraZoomPlugin.
  • Inspect the topics for the one containing camera_info and subscribe to the topic and filter for the projection matrix. For example:
gz topic -e -t /world/playpen/model/mount/model/gimbal/link/pitch_link/sensor/camera/camera_info | grep -A12 projection
--
projection {
  p: 205.46962738037109
  p: 0
  p: 320
  p: 0
  p: 0
  p: 205.46965599060059
  p: 240
  p: 0
  p: 0
  p: 0
  p: 1
  p: 0

In another terminal change the zoom setting of the camera:

gz topic -t /model/gimbal/sensor/camera/zoom/cmd_zoom -m gz.msgs.Double -p "data: 4"

Monitor the camera_info topic and notice there is no change to the intrinsic matrix.

Platform
[ x ] All
[ ] AntennaTracker
[ ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Add zoom slew rate to CameraZoomPlugin

Feature request

Is your feature request related to a problem? Please describe.

Not all cameras can do instant zoom. I'd like to achieve the nice optical zoom rate limit that nice cameras have.

Describe the solution you'd like

Add one new parameter "slew_rate", which is the change in focal length per second possible from the camera.

The gazebo camera zoom plugin should be able to configure something like this:
https://www.youtube.com/watch?v=jShVCd7m1ak&ab_channel=SuperZoom
https://www.nikonusa.com/en/nikon-products/product/compact-digital-cameras/coolpix-p1000.html

Example:

Nikon has a P1000 has a 125x optical zoom (3000mm / 24mm = 125x). From the video, it takes about 7 seconds to do the zoom action.

Converting to SI, because REP-15, you have a 3 meter to 0.024 meter change.

Slew Rate [m/s] = ( 3 - 0.024) / 7 = 0.42514285714 m/s
Thus, you would add to models/gimbal_small_3d/model.sdf:

        <plugin filename="CameraZoomPlugin"
            name="CameraZoomPlugin">
          <max_zoom>125.0</max_zoom>
          <slew_rate>0.42514285714</slew_rate>
        </plugin>

Describe alternatives you've considered

N/A

Platform
[ x] All
[ ] AntennaTracker
[ ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Assumptions

Ignore the weird lens effects at high zoom levels. If someone wants to make a 50-9999999 lens simulator, then let them.
Assume most users want instant zoom, so the default for the zoom rate will be infinity.

Additional context

I can do the implementation. Just requires a bit more math. It will be nice internally in the plugin to start doing math against focal lengths instead of the currently exposed zoom factor.

https://www.scantips.com/lights/fieldofviewmath.html
https://en.wikipedia.org/wiki/Focal_length

Add range sensor example

Feature request

PR #5 provides support for range / proximity sensor integration in the core ArduPilotPlugin, but refers to an example in an external repo.

It would be good to have a simple rover example using the range sensors included here to help users get started.

Describe alternatives you've considered

Continue to reference external repos for examples. Not ideal as not self contained.

Platform
[ ] All
[ ] AntennaTracker
[ x ] Copter
[ x ] Plane
[ x ] Rover
[ ] Submarine

Additional context

The example referred to is here: https://github.com/srmainwaring/ros_gz_rover

CMake error

CMake Error at CMakeLists.txt:19 (find_package):
By not providing "Findgz-cmake3.cmake" in CMAKE_MODULE_PATH this project
has asked CMake to find a package configuration file provided by
"gz-cmake3", but CMake did not find one.

Could not find a package configuration file provided by "gz-cmake3" with
any of the following names:

gz-cmake3Config.cmake
gz-cmake3-config.cmake

Add the installation prefix of "gz-cmake3" to CMAKE_PREFIX_PATH or set
"gz-cmake3_DIR" to a directory containing one of the above files. If
"gz-cmake3" provides a separate development package or SDK, be sure it has
been installed.

-- Configuring incomplete, errors occurred!

undefined symbol

Bug report

Issue details

I couldn't solve this link error. The plugin at commit 5b4d5a7 compiled just fine

$ gz sim -r iris_runway.sdf
Error while loading the library [/home/ep/ardupilot_gazebo/build/libArduPilotPlugin.so]: /home/ep/ardupilot_gazebo/build/libArduPilotPlugin.so: undefined symbol: _ZNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEED1Ev, version Qt_5
[Err] [SystemLoader.cc:140] Failed to load system plugin: (Reason: No plugins detected in library)
- Requested plugin name: [ArduPilotPlugin]
- Requested library name: [libArduPilotPlugin]
- Resolved library path: [/home/ep/ardupilot_gazebo/build/libArduPilotPlugin.so]

Version
ardupilot_gazebo commit 5b4d5a7
Gazebo Garden
Ubuntu 22.04
gcc 12.1.0

Any help would be greatly appreciated.

[GUI] [Dbg] [Application.cc:242] Terminating application.

Bug report

I just installed gazebo from the tutorial from ardupilot but i cant lunch gazebo with "gz sim -v4 -r iris_runway.sdf" or "gz sim -v4 -r zephyr_runway.sdf"

Version
Ubuntu 22.04.3
Gazebo Sim, version 8.0.0
ArduCopter 4.4.4
ArduPLane 4.1

Platform
[ x ] All
[ ] AntennaTracker
[ ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Airframe type
İris and Zephyr

Logs
"[Msg] Gazebo Sim GUI v8.0.0
[Dbg] [gz.cc:166] Subscribing to [/gazebo/starting_world].
[Dbg] [gz.cc:168] Waiting for a world to be set from the GUI...
[Dbg] [Gui.cc:263] Waiting for subscribers to [/gazebo/starting_world]...
[Msg] Received world [iris_runway.sdf] from the GUI.
[Dbg] [gz.cc:172] Unsubscribing from [/gazebo/starting_world].
[Msg] Gazebo Sim Server v8.0.0
[Msg] Loading SDF world file[/home/metaphaz/gz_ws/src/ardupilot_gazebo/worlds/iris_runway.sdf].
[Dbg] [Application.cc:101] Initializing application.
[Dbg] [Application.cc:175] Qt using OpenGL graphics interface
[GUI] [Dbg] [Application.cc:662] Create main window
[Msg] Serving entity system service on [/entity/system/add]
[Dbg] [Physics.cc:860] Loaded [gz::physics::dartsim::Plugin] from library [/usr/lib/x86_64-linux-gnu/gz-physics-7/engine-plugins/libgz-physics-dartsim-plugin.so]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::Physics] for entity [1]
[Dbg] [Sensors.cc:511] Configuring Sensors system
[Dbg] [Sensors.cc:430] SensorsPrivate::Run
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::Sensors] for entity [1]
[Dbg] [Sensors.cc:406] SensorsPrivate::RenderThread started
[Dbg] [Sensors.cc:246] Waiting for init
[Msg] Create service on [/world/iris_runway/create]
[Msg] Remove service on [/world/iris_runway/remove]
[Msg] Pose service on [/world/iris_runway/set_pose]
[Msg] Pose service on [/world/iris_runway/set_pose_vector]
[Msg] Light configuration service on [/world/iris_runway/light_config]
[Msg] Physics service on [/world/iris_runway/set_physics]
[Msg] SphericalCoordinates service on [/world/iris_runway/set_spherical_coordinates]
[Msg] Enable collision service on [/world/iris_runway/enable_collision]
[Msg] Disable collision service on [/world/iris_runway/disable_collision]
[Msg] Material service on [/world/iris_runway/visual_config]
[Msg] Material service on [/world/iris_runway/wheel_slip]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::UserCommands] for entity [1]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::SceneBroadcaster] for entity [1]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::Imu] for entity [1]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::NavSat] for entity [1]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::JointStatePublisher] for entity [15]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::LiftDrag] for entity [15]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::LiftDrag] for entity [15]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::LiftDrag] for entity [15]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::LiftDrag] for entity [15]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::LiftDrag] for entity [15]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::LiftDrag] for entity [15]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::LiftDrag] for entity [15]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::LiftDrag] for entity [15]
[Msg] ApplyJointForce subscribing to Double messages on [/model/iris_with_ardupilot/joint/iris_with_standoffs::rotor_0_joint/cmd_force]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::ApplyJointForce] for entity [15]
[Msg] ApplyJointForce subscribing to Double messages on [/model/iris_with_ardupilot/joint/iris_with_standoffs::rotor_1_joint/cmd_force]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::ApplyJointForce] for entity [15]
[Msg] ApplyJointForce subscribing to Double messages on [/model/iris_with_ardupilot/joint/iris_with_standoffs::rotor_2_joint/cmd_force]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::ApplyJointForce] for entity [15]
[Msg] ApplyJointForce subscribing to Double messages on [/model/iris_with_ardupilot/joint/iris_with_standoffs::rotor_3_joint/cmd_force]
[Dbg] [SystemManager.cc:74] Loaded system [gz::sim::systems::ApplyJointForce] for entity [15]
[libprotobuf ERROR google/protobuf/descriptor_database.cc:175] Symbol name "gz.sim.private_msgs.PerformerAffinity" conflicts with the existing symbol "gz.sim.private_msgs.PerformerAffinity".
[libprotobuf FATAL google/protobuf/descriptor.cc:1382] CHECK failed: GeneratedDatabase()->Add(encoded_file_descriptor, size):
terminate called after throwing an instance of 'google::protobuf::FatalException'
what(): CHECK failed: GeneratedDatabase()->Add(encoded_file_descriptor, size):
Stack trace (most recent call last):
#31 Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7fad7c914c00, in gz::sim::v8::SdfEntityCreator::CreateEntities(sdf::v14::Model const*)
#30 Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7fad7c8ecf55, in
#29 Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7fad7c94d268, in gz::sim::v8::SimulationRunner::LoadPlugins(unsigned long, std::vector<sdf::v14::Plugin, std::allocatorsdf::v14::Plugin > const&)
#28 Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7fad7c959d33, in gz::sim::v8::SystemManager::LoadPlugin(unsigned long, sdf::v14::Plugin const&)
#27 Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7fad7c9594e9, in gz::sim::v8::SystemLoader::LoadPlugin(sdf::v14::Plugin const&)
#26 Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7fad7c9584a8, in
#25 Object "/lib/x86_64-linux-gnu/libgz-plugin2-loader.so.2", at 0x7fad7cf5e56f, in gz::plugin::Loader::LoadLib(std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&, bool)
#24 Object "/lib/x86_64-linux-gnu/libgz-plugin2-loader.so.2", at 0x7fad7cf5d4dd, in gz::plugin::Loader::Implementation::LoadLib(std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&, bool)
#23 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fad81a906c7, in dlopen
#22 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fad81a9012d, in
#21 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fad81b74972, in _dl_catch_error
#20 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fad81b748a7, in _dl_catch_exception
#19 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fad81a9063b, in
#18 Object "/lib64/ld-linux-x86-64.so.2", at 0x7fad822a634d, in
#17 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fad81b748a7, in _dl_catch_exception
#16 Object "/lib64/ld-linux-x86-64.so.2", at 0x7fad822a5ff5, in
#15 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fad81b74904, in _dl_catch_exception
#14 Object "/lib64/ld-linux-x86-64.so.2", at 0x7fad8229e567, in
#13 Object "/lib64/ld-linux-x86-64.so.2", at 0x7fad8229e47d, in
#12 Object "/lib/x86_64-linux-gnu/libgz-sim7.so.7", at 0x7fad490b3d08, in
#11 Object "/lib/x86_64-linux-gnu/libprotobuf.so.23", at 0x7fad7bd81951, in google::protobuf::internal::AddDescriptors(google::protobuf::internal::DescriptorTable const*)
#10 Object "/lib/x86_64-linux-gnu/libprotobuf.so.23", at 0x7fad7bd81966, in google::protobuf::internal::AddDescriptors(google::protobuf::internal::DescriptorTable const*)
#9 Object "/lib/x86_64-linux-gnu/libprotobuf.so.23", at 0x7fad7bc92c35, in
#8 Object "/lib/x86_64-linux-gnu/libgcc_s.so.1", at 0x7fad81c4e2dc, in _Unwind_Resume
#7 Object "/lib/x86_64-linux-gnu/libgcc_s.so.1", at 0x7fad81c4d883, in
#6 Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7fad7d8ad958, in __gxx_personality_v0
#5 Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7fad7d8ad1e8, in
#4 Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7fad7d8ae20b, in
#3 Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7fad7d8a2b9d, in
#2 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fad81a287f2, in abort
#1 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fad81a42475, in raise
#0 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fad81a969fc, in pthread_kill
Aborted (Signal sent by tkill() 43776 1000)
[GUI] [Dbg] [PathManager.cc:68] Requesting resource paths through [/gazebo/resource_paths/get]
[GUI] [Dbg] [Gui.cc:343] GUI requesting list of world names. The server may be busy downloading resources. Please be patient.
[GUI] [Dbg] [SignalHandler.cc:142] Received signal[2].
[GUI] [Dbg] [SignalHandler.cc:142] Received signal[2].
[GUI] [Dbg] [Application.cc:242] Terminating application."

Add Gimbal

Feature request

The original version of the project for Gazebo11 included a plugin for a small 2d gimbal. This request is to have the gimbal model updated to run in Gazebo Sim and for the plugin to be ported to work with the gz-sim7 libraries.

Desired outcome

  • A small gimbal model is available to attach to the Iris quadcopter.
  • The gimbal joints may be controlled using a suitable plugin.
  • There is a topic to which commands may be published to set the gimbal joint position.

Alternatives

The gimbal model is available for download from Gimbal Small 2D but has not been ported to Gazebo Sim / PBS shading:

  • It uses the deprecated material <script> element for specifying visual colours.
  • It uses the plugin libGimbalSmall2dPlugin which does not work in Gazebo Sim.

Platform

[ ] All
[ ] AntennaTracker
[ x ] Copter
[ x ] Plane
[ x ] Rover
[ x ] Submarine

Additional context

iris_with_standoffs import error when using Gazebo Harmonic and ROS Jazzy

Bug report

Issue details

I'm running ROS Jazzy and Gazebo Harmonic and tried installing ardupilot_gazebo following the installation instructions on the ros2 branch. Installation works as expected but when I run gz sim -v4 -r iris_runway.sdf I get the following expections:

[Err] [Server.cc:204] Error Code 14: Msg: Parser configurations requested resolved uris, but uri [package://ardupilot_gazebo/models/iris_with_standoffs/meshes/iris.dae] could not be resolved.
[Err] [Server.cc:204] Error Code 14: Msg: Parser configurations requested resolved uris, but uri [package://ardupilot_gazebo/models/iris_with_standoffs/meshes/iris_prop_ccw.dae] could not be resolved.
[Err] [Server.cc:204] Error Code 14: Msg: Parser configurations requested resolved uris, but uri [package://ardupilot_gazebo/models/iris_with_standoffs/meshes/iris_prop_ccw.dae] could not be resolved.
[Err] [Server.cc:204] Error Code 14: Msg: Parser configurations requested resolved uris, but uri [package://ardupilot_gazebo/models/iris_with_standoffs/meshes/iris_prop_cw.dae] could not be resolved.
[Err] [Server.cc:204] Error Code 14: Msg: Parser configurations requested resolved uris, but uri [package://ardupilot_gazebo/models/iris_with_standoffs/meshes/iris_prop_cw.dae] could not be resolved.
[Err] [Server.cc:204] Error Code 9: Msg: Failed to load a world.

This seems to be related to the changes in #56 as the problem doesn't occur when changing from:

+ <uri>package://ardupilot_gazebo/models/iris_with_standoffs/meshes/iris.dae</uri>
- <uri>model://iris_with_standoffs/meshes/iris.dae</uri>

+ <uri>model://iris_with_standoffs/meshes/iris_prop_ccw.dae</uri> 
- <uri>package://ardupilot_gazebo/models/iris_with_standoffs/meshes/iris_prop_ccw.dae</uri>

+ <uri>model://iris_with_standoffs/meshes/iris_prop_cw.dae</uri>
- <uri>package://ardupilot_gazebo/models/gimbal_small_2d/meshes/base_main.dae</uri>

I don't have extensive experience with Gazebo and therefore I'm unsure if this is causes by incorrect usage or not but I suggest that either the README should be adapted to show the correct usage of the change should be reverted.

Version

Current version of ros branch (77b303e)

Platform
[ ] All
[ ] AntennaTracker
[ x ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Airframe type
iris_with_standoffs (used also in other iris models)

Support for gz-fortress (LTS)

Feature request

Is your feature request related to a problem? Please describe.
So far i am bound to ROS1/Noetic and i want to use gazebo image bridge from https://github.com/gazebosim/ros_gz/tree/noetic. The ROS noetic codebase over there only supports the LTS release so far. This leeds to the problem, that AFAIK no ROS1 codebase + simulated images can be used with ardupilot_gazebo.

Describe the solution you'd like
Add support for gz-fortress (LTS).

Describe alternatives you've considered
If using ROS2 would be a option, then https://github.com/gazebosim/ros_gz is possible. For ROS1 there is AFAIK no other option avaiable which works with this repo.

Platform
[ ] All
[ ] AntennaTracker
[ ] Copter
[x] Plane
[ ] Rover
[ ] Submarine

Additional context

Add feature / plugin for parachute testing

Feature request

It would be nice to be able to test parachute release with gazebo.

We could make something similar
px4 gazebo plugins already have this feature, but for gazebo-classic

I have made my own implementation, but its poorly written
ParachutePlugin.cc

Platform
[ ] All
[ ] AntennaTracker
[ ✓ ] Copter
[ ✓ ] Plane
[ ] Rover
[ ] Submarine

Sync ros2 branch with main

Feature request

Bring the ros2 branch up to date with the following changes in main.

Platform
[x] All
[ ] AntennaTracker
[ ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Update attitude controller params for iris

Feature request

Update the default attitude controller params for the Iris when running on Gazebo.

Is your feature request related to a problem? Please describe.

The current value of ATC_RAT_RLL_D causes roll oscillations, reducing it to 1E-5 eliminates the problem.

Describe the solution you'd like

Either provide parameters in this project or update the parameters in the upstream project (ArduPilot/ardupilot).

Describe alternatives you've considered

A full retune / autotune of the iris Gazebo model may be useful. The proposed change is the minimum needed to eliminate the oscillation.

Platform

  • All
  • AntennaTracker
  • Copter
  • Plane
  • Rover
  • Submarine

Additional context

This has not been a major problem to date, but became apparent while attempting to investigate possible issues with the motor velocity controllers while tuning the OmniCopter in SITL_Models/Gazebo.

Gazebo simulation doesn't start with `gimbal.sdf` world

Bug report

Issue details

Gazebo simulation fails to run with gimbal.sdf world. It throws the next error:

[Msg] Loading SDF world file[/Users/sergiir/git/gz_ws/src/ardupilot_gazebo/worlds/gimbal.sdf].
[Err] [Server.cc:203] Error Code 14: Msg: Parser configurations requested resolved uris, but uri [file://media/materials/scripts/gazebo.material] could not be resolved.
[Err] [Server.cc:203] Error Code 9: Msg: Failed to load a world.
[Dbg] [gz.cc:434] Shutting down gz-sim-server

Other worlds don't have any issues.

Version
Gazebo Harmonic
MacOS Sonoma 14.5

Platform
[] Copter

[Errno 111] Connection refused sleeping

I successfully opened Gazebo using the command "gz sim -v4 -r iris_runway.sdf".
However, when I tried to open SITL by entering the command :
"sim_vehicle.py -v ArduCopter -f gazebo-iris --model JSON --map --console", I encountered the following error:

Connect tcp:127.0.0.1:5760 source_system=255
[Errno 111] Connection refused sleeping
[Errno 111] Connection refused sleeping
[Errno 111] Connection refused sleeping
[Errno 111] Connection refused sleeping
Failed to connect to tcp:127.0.0.1:5760 : [Errno 111] Connection refused
SIM_VEHICLE: MAVProxy exited
SIM_VEHICLE: Killing tasks

Error: [ruby $(which gz) sim-1] ODE INTERNAL ERROR 1: assertion "aabbBound >= dMinIntExact && aabbBound < dMaxIntExact" failed in collide() [collision_space.cpp:460]

Bug report

When I run a gazebo simulation with the ardupilot plugin loaded, it crashes immediately when ardupilot connects via mavros. This started to happen after gazebo got upgraded to version 7.2. More info at: gazebosim/gz-sim#1871 and gazebosim/gz-sim#15

I am not sure if this is a bug related to the plugin or gazebo.

gazebo output:

ros2 launch bluerov2_ignition simulation.launch.py 
[INFO] [launch]: All log files can be found below /home/gus/.ros/log/2023-01-31-13-37-20-944372-alien-362949
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ruby $(which gz) sim-1]: process started with pid [362952]
[INFO] [create-2]: process started with pid [362954]
[INFO] [create-3]: process started with pid [362957]
[INFO] [create-4]: process started with pid [362959]
[INFO] [parameter_bridge-5]: process started with pid [362962]
[parameter_bridge-5] [INFO] [1675168641.110988456] [gz_bluerov_pose_bridge]: Creating GZ->ROS Bridge: [/model/bluerov2/pose (gz.msgs.Pose) -> /model/bluerov2/pose (geometry_msgs/msg/Pose)] (Lazy 0)
[parameter_bridge-5] [INFO] [1675168641.113575214] [gz_bluerov_pose_bridge]: Creating ROS->GZ Bridge: [/model/bluerov2/pose (geometry_msgs/msg/Pose) -> /model/bluerov2/pose (gz.msgs.Pose)] (Lazy 0)
[create-2] [INFO] [1675168641.586280364] [ros_gz_sim]: Requested creation of entity.
[create-2] [INFO] [1675168641.586449620] [ros_gz_sim]: OK creation of entity.
[create-3] [INFO] [1675168641.686370576] [ros_gz_sim]: Requested creation of entity.
[create-3] [INFO] [1675168641.686529413] [ros_gz_sim]: OK creation of entity.
[INFO] [create-2]: process has finished cleanly [pid 362954]
[create-4] [INFO] [1675168641.786736353] [ros_gz_sim]: Requested creation of entity.
[create-4] [INFO] [1675168641.787018690] [ros_gz_sim]: OK creation of entity.
[INFO] [create-3]: process has finished cleanly [pid 362957]
[INFO] [create-4]: process has finished cleanly [pid 362959]
[ruby $(which gz) sim-1] [Err] [SDFFeatures.cc:819] The geometry element of collision [ground] couldn't be created
[ruby $(which gz) sim-1] 
[ruby $(which gz) sim-1] ODE INTERNAL ERROR 1: assertion "aabbBound >= dMinIntExact && aabbBound < dMaxIntExact" failed in collide() [collision_space.cpp:460]
[ruby $(which gz) sim-1] Stack trace (most recent call last):
[ruby $(which gz) sim-1] #31   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f4935642c96, in 
[ruby $(which gz) sim-1] #30   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f493563ffc5, in 
[ruby $(which gz) sim-1] #29   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f493563dc34, in 
[ruby $(which gz) sim-1] #28   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f4935589a1e, in 
[ruby $(which gz) sim-1] #27   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f49354b49ac, in rb_protect
[ruby $(which gz) sim-1] #26   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f493564cc61, in rb_yield
[ruby $(which gz) sim-1] #25   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f493564830c, in rb_vm_exec
[ruby $(which gz) sim-1] #24   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f4935642c96, in 
[ruby $(which gz) sim-1] #23   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f493563ffc5, in 
[ruby $(which gz) sim-1] #22   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f493563dc34, in 
[ruby $(which gz) sim-1] #21   Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7f49314fb44b, in 
[ruby $(which gz) sim-1] #20   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f493560b088, in rb_nogvl
[ruby $(which gz) sim-1] #19   Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7f49314fad6b, in 
[ruby $(which gz) sim-1] #18   Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7f49314ec492, in 
[ruby $(which gz) sim-1] #17   Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7f49314efe2d, in 
[ruby $(which gz) sim-1] #16   Object "/usr/lib/x86_64-linux-gnu/libgz-sim7-gz.so.7.2.0", at 0x7f4930a09e35, in runServer
[ruby $(which gz) sim-1] #15   Object "/lib/x86_64-linux-gnu/libgz-sim7.so.7", at 0x7f49306e3f55, in 
[ruby $(which gz) sim-1] #14   Object "/lib/x86_64-linux-gnu/libgz-sim7.so.7", at 0x7f49306f13aa, in gz::sim::v7::SimulationRunner::Run(unsigned long)
[ruby $(which gz) sim-1] #13   Object "/lib/x86_64-linux-gnu/libgz-sim7.so.7", at 0x7f49306f0a80, in gz::sim::v7::SimulationRunner::Step(gz::sim::v7::UpdateInfo const&)
[ruby $(which gz) sim-1] #12   Object "/lib/x86_64-linux-gnu/libgz-sim7.so.7", at 0x7f49306eefb2, in gz::sim::v7::SimulationRunner::UpdateSystems()
[ruby $(which gz) sim-1] #11   Object "/usr/lib/x86_64-linux-gnu/gz-sim-7/plugins/libgz-sim-physics-system.so", at 0x7f49207262e6, in gz::sim::v7::systems::Physics::Update(gz::sim::v7::UpdateInfo const&, gz::sim::v7::EntityComponentManager&)
[ruby $(which gz) sim-1] #10   Object "/usr/lib/x86_64-linux-gnu/gz-sim-7/plugins/libgz-sim-physics-system.so", at 0x7f4920726961, in gz::sim::v7::systems::PhysicsPrivate::Step(std::chrono::duration<long, std::ratio<1l, 1000000000l> > const&)
[ruby $(which gz) sim-1] #9    Object "/usr/lib/x86_64-linux-gnu/gz-physics-6/engine-plugins/libgz-physics-dartsim-plugin.so", at 0x7f48fee6e28c, in gz::physics::dartsim::SimulationFeatures::WorldForwardStep(gz::physics::Identity const&, gz::physics::SpecifyData<gz::physics::RequireData<gz::physics::WorldPoses>, gz::physics::ExpectData<gz::physics::ChangedWorldPoses, gz::physics::Contacts, gz::physics::JointPositions> >&, gz::physics::CompositeData&, gz::physics::ExpectData<gz::physics::ApplyExternalForceTorques, gz::physics::ApplyGeneralizedForces, gz::physics::VelocityControlCommands, gz::physics::ServoControlCommands, std::chrono::duration<long, std::ratio<1l, 1000000000l> > > const&)
[ruby $(which gz) sim-1] #8    Object "/lib/x86_64-linux-gnu/libdart.so.6.12", at 0x7f48feab6e73, in dart::simulation::World::step(bool)
[ruby $(which gz) sim-1] #7    Object "/lib/x86_64-linux-gnu/libdart.so.6.12", at 0x7f48fea9c705, in dart::constraint::ConstraintSolver::solve()
[ruby $(which gz) sim-1] #6    Object "/lib/x86_64-linux-gnu/libdart.so.6.12", at 0x7f48fea9afe1, in dart::constraint::ConstraintSolver::updateConstraints()
[ruby $(which gz) sim-1] #5    Object "/lib/x86_64-linux-gnu/libdart-collision-ode.so.6.12", at 0x7f48fec9e1cb, in dart::collision::OdeCollisionDetector::collide(dart::collision::CollisionGroup*, dart::collision::CollisionOption const&, dart::collision::CollisionResult*)
[ruby $(which gz) sim-1] #4    Object "/lib/x86_64-linux-gnu/libode.so.8", at 0x7f48fe599266, in dxHashSpace::collide(void*, void (*)(void*, dxGeom*, dxGeom*))
[ruby $(which gz) sim-1] #3    Object "/lib/x86_64-linux-gnu/libode.so.8", at 0x7f48fe5a17b7, in dDebug
[ruby $(which gz) sim-1] #2    Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f493520e7f2, in abort
[ruby $(which gz) sim-1] #1    Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f4935228475, in raise
[ruby $(which gz) sim-1] #0    Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f493527ca7c, in pthread_kill
[ruby $(which gz) sim-1] Aborted (Signal sent by tkill() 363028 1000)
[ruby $(which gz) sim-1] libEGL warning: DRI2: failed to create dri screen
[ruby $(which gz) sim-1] libEGL warning: DRI2: failed to create dri screen
[INFO] [ruby $(which gz) sim-1]: process has finished cleanly [pid 362952]

Version

  • Ubuntu 22.04
  • Mavros 2.4.0
  • ardupilot_gazebo main branch
  • ros_gz humble branch
  • gazebo 7.3.0

Platform
[ ] All
[ ] AntennaTracker
[ ] Copter
[ ] Plane
[ ] Rover
[ X ] Submarine

Hardware type
ArduSub SITL commit https://github.com/ArduPilot/ardupilot/tree/9f1c4df5e7

Unable to install this plugin on M1 Mac using GZ Harmonic

Bug report

Issue details
Attempting to install this plugin on an M1 Macbook Pro, running OSX 14.4.1. However, I persistently run into this error message

CMake Error at /opt/homebrew/lib/cmake/protobuf/protobuf-targets.cmake:71 (set_target_properties):
  The link interface of target "protobuf::libprotobuf" contains:

    absl::absl_check

  but the target was not found.  Possible reasons include:

    * There is a typo in the target name.
    * A find_package call is missing for an IMPORTED target.
    * An ALIAS target is missing.

Call Stack (most recent call first):
  /opt/homebrew/lib/cmake/protobuf/protobuf-config.cmake:16 (include)
  /opt/homebrew/share/cmake/gz-cmake3/cmake3/FindGzProtobuf.cmake:29 (find_package)
  /opt/homebrew/lib/cmake/gz-transport13/gz-transport13-config.cmake:92 (find_package)
  /opt/homebrew/lib/cmake/gz-sim8/gz-sim8-config.cmake:94 (find_package)
  /opt/homebrew/share/cmake/gz-cmake3/cmake3/GzFindPackage.cmake:243 (find_package)
  CMakeLists.txt:31 (gz_find_package)

Please describe the problem
I've installed GZ harmonic using brew install gz-harmonic. I'm able to run simple test examples using just gazebo. I've exported the GZ_VERSION env variable. However running cmake .. -DCMAKE_BUILD_TYPE=RelWithDebInfo as instructed in the install notes causes the above error. I can see that brew is pulling down protobuf v27 and abseil successfully, but something in this installation isn't picking up abseil properly. Wondering if you guys have certain versions of these dependency libraries that you pin that work for y'all. I'm in the process of going down the rabbit hole to try and get an earlier version of protobuf without abseil to work but figured I'd ask around here. I'm hoping at least one of y'all has this working on an M1 Mac.

Thanks in advance!

Version
What version was the issue encountered with
GZ Harmonic, attempting to build this package from latest master
Platform
[ x] All
[ ] AntennaTracker
[ ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Logs
Please provide a link to any relevant logs that show the issue

Cleanup example models

Feature request

Tidy the example models provided with the plugin library.

  • Remove examples that are not supported (i.e. Gazebo Sim does not support the StaticMapPlugin so remove iris_arducopter_cmac.world).
  • Shorten world names.
  • Change the world sdf file extensions to .sdf.
  • Update the edifice warehouse example to use the gazebosim fuel server.
  • Split the zephyr model into a base + with-ardupilot as we have done for iris.
  • Add thumbnails using the ModelPhotoShoot system plugin.

Platform
[ ] All
[ ] AntennaTracker
[ x ] Copter
[ x ] Plane
[ ] Rover
[ ] Submarine

Additional context

Simplified based models will help when configuring examples for peripheral plugins such as the one requested in #33.

gazebo server crash on macOS when gazebo gui launch

Bug report

Issue details
gazebo server will crash at once on macOS when gazebo gui launch

Version
ignition-garden branch

Logs

server launch first

ign gazebo -s -v 4 -r iris_arducopter_runway.world
[Msg] Ignition Gazebo Server v7.0.0~pre1
this->dataPtr->config.Source() 2
[Msg] Loading default world.
[Msg] Loading SDF world file[/Users/xlla/git/ardupilot_gazebo-1/worlds/iris_arducopter_runway.world].
[Msg] Loaded level [3]
[Msg] No systems loaded from SDF, loading defaults
[Dbg] [ServerConfig.cc:1004] Loaded (3) plugins from file [/Users/xlla/.ignition/gazebo/7/server.config]
[Dbg] [Physics.cc:824] Loaded [ignition::physics::dartsim::Plugin] from library [/usr/local/Cellar/ignition-physics6/5.999.999~0~20220414/lib/ign-physics-6/engine-plugins/libignition-physics-dartsim-plugin.dylib]
[Dbg] [SystemManager.cc:89] Loaded system [ignition::gazebo::systems::Physics] for entity [1]
[Msg] Create service on [/world/iris_arducopter_runway/create]
[Msg] Remove service on [/world/iris_arducopter_runway/remove]
[Msg] Pose service on [/world/iris_arducopter_runway/set_pose]
[Msg] Pose service on [/world/iris_arducopter_runway/set_pose_vector]
[Msg] Light configuration service on [/world/iris_arducopter_runway/light_config]
[Msg] Physics service on [/world/iris_arducopter_runway/set_physics]
[Msg] SphericalCoordinates service on [/world/iris_arducopter_runway/set_spherical_coordinates]
[Msg] Enable collision service on [/world/iris_arducopter_runway/enable_collision]
[Msg] Disable collision service on [/world/iris_arducopter_runway/disable_collision]
[Msg] Material service on [/world/iris_arducopter_runway/visual_config]
[Msg] Material service on [/world/iris_arducopter_runway/wheel_slip]
[Dbg] [SystemManager.cc:89] Loaded system [ignition::gazebo::systems::UserCommands] for entity [1]
[Dbg] [SystemManager.cc:89] Loaded system [ignition::gazebo::systems::SceneBroadcaster] for entity [1]
[Msg] Serving world controls on [/world/iris_arducopter_runway/control], [/world/iris_arducopter_runway/control/state] and [/world/iris_arducopter_runway/playback/control]
[Msg] Serving GUI information on [/world/iris_arducopter_runway/gui/info]
[Msg] World [iris_arducopter_runway] initialized with [default_physics] physics profile.
[Msg] Serving world SDF generation service on [/world/iris_arducopter_runway/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 paths published on [/gazebo/resource_paths].
[Msg] Server control service on [/server_control].
[Dbg] [SystemManager.cc:89] Loaded system [ignition::gazebo::systems::JointStatePublisher] for entity [9]
[Dbg] [SystemManager.cc:89] Loaded system [ignition::gazebo::systems::LiftDrag] for entity [9]
[Dbg] [SystemManager.cc:61] This system Plugin [ignition::gazebo::systems::LiftDrag] is already loaded in this entity [9]
[Dbg] [SystemManager.cc:61] This system Plugin [ignition::gazebo::systems::LiftDrag] is already loaded in this entity [9]
[Dbg] [SystemManager.cc:61] This system Plugin [ignition::gazebo::systems::LiftDrag] is already loaded in this entity [9]
[Dbg] [SystemManager.cc:61] This system Plugin [ignition::gazebo::systems::LiftDrag] is already loaded in this entity [9]
[Dbg] [SystemManager.cc:61] This system Plugin [ignition::gazebo::systems::LiftDrag] is already loaded in this entity [9]
[Dbg] [SystemManager.cc:61] This system Plugin [ignition::gazebo::systems::LiftDrag] is already loaded in this entity [9]
[Dbg] [SystemManager.cc:61] This system Plugin [ignition::gazebo::systems::LiftDrag] is already loaded in this entity [9]
[Msg] ApplyJointForce subscribing to Double messages on [/model/iris/joint/rotor_0_joint/cmd_force]
[Dbg] [SystemManager.cc:89] Loaded system [ignition::gazebo::systems::ApplyJointForce] for entity [9]
[Dbg] [SystemManager.cc:61] This system Plugin [ignition::gazebo::systems::ApplyJointForce] is already loaded in this entity [9]
[Dbg] [SystemManager.cc:61] This system Plugin [ignition::gazebo::systems::ApplyJointForce] is already loaded in this entity [9]
[Dbg] [SystemManager.cc:61] This system Plugin [ignition::gazebo::systems::ApplyJointForce] is already loaded in this entity [9]
[Dbg] [SystemManager.cc:89] Loaded system [ArduPilotPlugin] for entity [9]
[Dbg] [Physics.cc:824] Loaded [ignition::physics::dartsim::Plugin] from library [/usr/local/Cellar/ignition-physics6/5.999.999~0~20220414/lib/ign-physics-6/engine-plugins/libignition-physics-dartsim-plugin.dylib]
[Dbg] [SystemManager.cc:89] Loaded system [ignition::gazebo::systems::Physics] for entity [1]
[Msg] Create service on [/world/iris_arducopter_runway/create]
[Msg] Remove service on [/world/iris_arducopter_runway/remove]
[Msg] Pose service on [/world/iris_arducopter_runway/set_pose]
[Msg] Pose service on [/world/iris_arducopter_runway/set_pose_vector]
[Msg] Light configuration service on [/world/iris_arducopter_runway/light_config]
[Msg] Physics service on [/world/iris_arducopter_runway/set_physics]
[Msg] SphericalCoordinates service on [/world/iris_arducopter_runway/set_spherical_coordinates]
[Msg] Enable collision service on [/world/iris_arducopter_runway/enable_collision]
[Msg] Disable collision service on [/world/iris_arducopter_runway/disable_collision]
[Msg] Material service on [/world/iris_arducopter_runway/visual_config]
[Msg] Material service on [/world/iris_arducopter_runway/wheel_slip]
[Dbg] [SystemManager.cc:89] Loaded system [ignition::gazebo::systems::UserCommands] for entity [1]
[Dbg] [SystemManager.cc:89] Loaded system [ignition::gazebo::systems::SceneBroadcaster] for entity [1]
[Dbg] [SystemManager.cc:89] Loaded system [ignition::gazebo::systems::Imu] for entity [1]
[Msg] Download models in parallel has finished. Now you can start the simulation
[Msg] Found no publishers on /stats, adding root stats topic
[Msg] Found no publishers on /clock, adding root clock topic
[Dbg] [SimulationRunner.cc:494] Creating PostUpdate worker threads: 6
[Dbg] [SimulationRunner.cc:505] Creating postupdate worker thread (0)
[Dbg] [SimulationRunner.cc:505] Creating postupdate worker thread (1)
[Dbg] [SimulationRunner.cc:505] Creating postupdate worker thread (2)
[Dbg] [SimulationRunner.cc:505] Creating postupdate worker thread (3)
[Dbg] [SimulationRunner.cc:505] Creating postupdate worker thread (4)
[Dbg] [ArduPilotPlugin.cc:777] Computed IMU topic to be: world/iris_arducopter_runway/model/iris/link/imu_link/sensor/imu_sensor/imu
[Msg] Using [ode] collision detector
[Msg] Using [DantzigBoxedLcpSolver] solver.
[Dbg] [ImuSensor.cc:148] IMU data for [iris::imu_link::imu_sensor] advertised on [world/iris_arducopter_runway/model/iris/link/imu_link/sensor/imu_sensor/imu]
[Msg] Serving scene information on [Serving scene information on [[Msg] /scene/infoscene/info/world/iris_arducopter_runway
scene/infoscene/info]
[Msg] Serving graph information on [Serving graph information on [[Msg] /Serving graph information on [scene/graph/world/iris_arducopter_runway]/
]]
[Msg] Serving full state on [/world/iris_arducopter_runway//[Msg] ]Serving full state on [
//state]
[Msg] Serving full state (async) on [Serving full state (async) on [[Msg] /Serving full state (async) on [state_async/world/iris_arducopter_runway]/
]
[Msg] Publishing scene information on [/world/iris_arducopter_runway/scene/info]]
[Msg] Publishing scene information on [Publishing scene information on [/world/iris_arducopter_runway/scene/info]
[Msg] Publishing entity deletions on [/world/iris_arducopter_runway/scene/deletion]][Msg] Publishing entity deletions on [Publishing entity deletions on [/world/iris_arducopter_runway/scene/deletion]
[Msg] Publishing state changes on [Publishing state changes on [[Msg] ]Publishing state changes on [
]]
[Msg] Publishing pose messages on [Publishing pose messages on [/world/iris_arducopter_runway/world/iris_arducopter_runway////pose/infopose/infopose/infopose/info]]]]

[Msg] Publishing dynamic pose messages on [Publishing dynamic pose messages on [/world/iris_arducopter_runway//dynamic_pose/infodynamic_pose/info]]

[Dbg] [SimulationRunner.cc:259] Rewinding simulation back to time zero.

gui launch, then it got blank gui,

[Msg] Ignition Gazebo GUI    v7.0.0~pre1
[Dbg] [Application.cc:94] Initializing application.
[Dbg] [Application.cc:102] Qt using Metal graphics interface
[GUI] [Dbg] [Application.cc:570] Create main window
[GUI] [Dbg] [PathManager.cc:66] Requesting resource paths through [/gazebo/resource_paths/get]
[GUI] [Wrn] [Application.cc:819] [QT] file::/Gazebo/GazeboDrawer.qml:147:3: QML Dialog: Binding loop detected for property "implicitHeight"
[GUI] [Wrn] [Application.cc:819] [QT] file::/Gazebo/GazeboDrawer.qml:147:3: QML Dialog: Binding loop detected for property "implicitHeight"
[GUI] [Dbg] [Gui.cc:156] GUI requesting list of world names. The server may be busy downloading resources. Please be patient.
[GUI] [Dbg] [PathManager.cc:55] Received resource paths.
[GUI] [Dbg] [Gui.cc:215] Requesting GUI from [/world/iris_arducopter_runway/gui/info]...
[GUI] [Dbg] [GuiRunner.cc:145] Requesting initial state from [/world/iris_arducopter_runway/state]...
[GUI] [Msg] Loading config [/Users/xlla/.ignition/gazebo/7/gui.config]
[GUI] [Dbg] [Application.cc:433] Loading plugin [MinimalScene]
[GUI] [Dbg] [MinimalScene.cc:634] Creating ign-rendering interface for OpenGL
[GUI] [Dbg] [MinimalScene.cc:634] Creating ign-rendering interface for OpenGL
[GUI] [Dbg] [MinimalScene.cc:788] Creating render thread interface for OpenGL
[GUI] [Dbg] [MinimalScene.cc:1245] change plugin element graphics_api metal
[GUI] [Dbg] [MinimalScene.cc:641] Creating ign-renderering interface for Metal
[GUI] [Dbg] [MinimalScene.cc:794] Creating render thread interface for Metal
[GUI] [Msg] Added plugin [3D View] to main window
[GUI] [Msg] Loaded plugin [MinimalScene] from path [/usr/local/Cellar/ignition-gui7/6.999.999~0~20220414/lib/ign-gui-7/plugins/libMinimalScene.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [EntityContextMenuPlugin]
[GUI] [Msg] Added plugin [Entity Context Menu] to main window
[GUI] [Msg] Loaded plugin [EntityContextMenuPlugin] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libEntityContextMenuPlugin.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [GzSceneManager]
[GUI] [Msg] Added plugin [Scene Manager] to main window
[GUI] [Msg] Loaded plugin [GzSceneManager] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libGzSceneManager.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [InteractiveViewControl]
[GUI] [Msg] Camera view controller topic advertised on [/gui/camera/view_control]
[GUI] [Msg] Added plugin [Interactive view control] to main window
[GUI] [Msg] Loaded plugin [InteractiveViewControl] from path [/usr/local/Cellar/ignition-gui7/6.999.999~0~20220414/lib/ign-gui-7/plugins/libInteractiveViewControl.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [CameraTracking]
[GUI] [Msg] Added plugin [Camera tracking] to main window
[GUI] [Msg] Loaded plugin [CameraTracking] from path [/usr/local/Cellar/ignition-gui7/6.999.999~0~20220414/lib/ign-gui-7/plugins/libCameraTracking.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [MarkerManager]
[GUI] [Msg] Listening to stats on [/world/iris_arducopter_runway/stats]
[GUI] [Msg] Added plugin [Marker Manager] to main window
[GUI] [Msg] Loaded plugin [MarkerManager] from path [/usr/local/Cellar/ignition-gui7/6.999.999~0~20220414/lib/ign-gui-7/plugins/libMarkerManager.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [SelectEntities]
[GUI] [Msg] Added plugin [Select entities] to main window
[GUI] [Msg] Loaded plugin [SelectEntities] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libSelectEntities.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [Spawn]
[GUI] [Msg] Added plugin [Spawn] to main window
[GUI] [Msg] Loaded plugin [Spawn] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libSpawn.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [VisualizationCapabilities]
[GUI] [Msg] View as transparent service on [/gui/view/transparent]
[GUI] [Msg] View as wireframes service on [/gui/view/wireframes]
[GUI] [Msg] View center of mass service on [/gui/view/com]
[GUI] [Msg] View inertia service on [/gui/view/inertia]
[GUI] [Msg] View collisions service on [/gui/view/collisions]
[GUI] [Msg] View joints service on [/gui/view/joints]
[GUI] [Msg] View frames service on [/gui/view/frames]
[GUI] [Msg] Added plugin [Visualization capabilities] to main window
[GUI] [Msg] Loaded plugin [VisualizationCapabilities] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libVisualizationCapabilities.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [WorldControl]
[GUI] [Msg] Using world control service [/world/iris_arducopter_runway/control]
[GUI] [Msg] Listening to stats on [/world/iris_arducopter_runway/stats]
[GUI] [Msg] Added plugin [World control] to main window
[GUI] [Msg] Loaded plugin [WorldControl] from path [/usr/local/Cellar/ignition-gui7/6.999.999~0~20220414/lib/ign-gui-7/plugins/libWorldControl.dylib]
[GUI] [Dbg] [WorldControl.cc:245] Using an event to share WorldControl msgs with the server
[GUI] [Dbg] [Application.cc:433] Loading plugin [WorldStats]
[GUI] [Msg] Listening to stats on [/world/iris_arducopter_runway/stats]
[GUI] [Msg] Added plugin [World stats] to main window
[GUI] [Msg] Loaded plugin [WorldStats] from path [/usr/local/Cellar/ignition-gui7/6.999.999~0~20220414/lib/ign-gui-7/plugins/libWorldStats.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [Shapes]
[GUI] [Msg] Added plugin [Shapes] to main window
[GUI] [Msg] Loaded plugin [Shapes] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libShapes.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [Lights]
[GUI] [Msg] Added plugin [Lights] to main window
[GUI] [Msg] Loaded plugin [Lights] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libLights.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [TransformControl]
[GUI] [Dbg] [TransformControl.cc:219] Legacy mode is disabled; this plugin must be used with MinimalScene.
[GUI] [Msg] Added plugin [Transform control] to main window
[GUI] [Msg] Loaded plugin [TransformControl] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libTransformControl.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [Screenshot]
[GUI] [Msg] Screenshot service on [/gui/screenshot]
[GUI] [Msg] Added plugin [Screenshot] to main window
[GUI] [Msg] Loaded plugin [Screenshot] from path [/usr/local/Cellar/ignition-gui7/6.999.999~0~20220414/lib/ign-gui-7/plugins/libScreenshot.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [CopyPaste]
[GUI] [Msg] Added plugin [Copy/Paste] to main window
[GUI] [Msg] Loaded plugin [CopyPaste] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libCopyPaste.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [ComponentInspector]
[GUI] [Msg] Added plugin [Component inspector] to main window
[GUI] [Msg] Loaded plugin [ComponentInspector] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libComponentInspector.dylib]
[GUI] [Dbg] [Application.cc:433] Loading plugin [EntityTree]
[GUI] [Msg] Added plugin [Entity tree] to main window
[GUI] [Msg] Loaded plugin [EntityTree] from path [/usr/local/Cellar/ignition-gazebo7/6.999.999~0~20220412/lib/ign-gazebo-7/plugins/gui/libEntityTree.dylib]
[GUI] [Dbg] [Application.cc:303] Loading window config
[GUI] [Msg] Using server control service [/server_control]
[GUI] [Dbg] [Application.cc:584] Applying config
[GUI] [Wrn] [Application.cc:819] [QT] file::/Gazebo/GazeboDrawer.qml:147:3: QML Dialog: Binding loop detected for property "implicitHeight"
[GUI] [Wrn] [Application.cc:819] [QT] file::/WorldStats/WorldStats.qml:53:3: QML RowLayout: Binding loop detected for property "x"
[GUI] [Dbg] [MinimalScene.cc:641] Creating ign-renderering interface for Metal
[GUI] [Dbg] [MinimalScene.cc:794] Creating render thread interface for Metal
[GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[GUI] [Dbg] [MinimalScene.cc:583] Create scene [scene]
[GUI] [Dbg] [MinimalScene.cc:826] Creating texture node render interface for Metal
[GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[GUI] [Dbg] [TransformControl.cc:528] TransformControl plugin is using camera [scene::Camera(65527)]
[GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[GUI] [Dbg] [Spawn.cc:289] Spawn plugin is using camera [scene::Camera(65527)]
[GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[GUI] [Dbg] [SelectEntities.cc:452] SelectEntities plugin is using camera [scene::Camera(65527)]
[GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[GUI] [Dbg] [MarkerManager.cc:173] Advertise /marker/list service.
[GUI] [Dbg] [MarkerManager.cc:183] Advertise /marker/list.
[GUI] [Dbg] [MarkerManager.cc:193] Advertise /marker_array.
[GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[GUI] [Dbg] [CameraTracking.cc:181] CameraTrackingPrivate plugin is moving camera [scene::Camera(65527)]
[GUI] [Msg] Move to service on [/gui/move_to]
[GUI] [Msg] Follow service on [/gui/follow]
[GUI] [Msg] Move to pose service on [/gui/move_to/pose]
[GUI] [Msg] Camera pose topic advertised on [/gui/camera/pose]
[GUI] [Msg] Follow offset service on [/gui/follow/offset]
[GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[GUI] [Dbg] [InteractiveViewControl.cc:130] InteractiveViewControl plugin is moving camera [scene::Camera(65527)]
[GUI] [Msg] Loading plugin [ignition-rendering-ogre2]
[GUI] [Msg] Loading plugin [ignition-rendering-ogre2]

server will crash

Stack trace (most recent call last) in thread 123145340256256:
[Dbg] [EntityComponentManager.cc:1617] Updated state thread iterators: 8 threads processing around 5 entities each.
[Wrn] [Component.hh:144] Trying to serialize component with data type [N3sdf3v135WorldE], which doesn't have `operator<<`. Component will not be serialized.
#4    Object "libsystem_pthread.dylib", at 0x7fff55b2850c, in _pthread_start + 376
#3    Object "libsystem_pthread.dylib", at 0x7fff55b28660, in _pthread_body + 339
[Wrn] [Component.hh:144] Trying to serialize component with data type [#2    Object "libignition-gazebo7.7.dylib", at NSt3__16vectorIdNS_9allocatorIdEEEE0x10add2292, in void* std::__1::__thread_proxy >, ignition::gazebo::v7::SimulationRunner::ProcessSystemQueue()::$_0> >(void*) + 402
], which doesn't have #1    Object "libignition-gazebo-scene-broadcaster-system.dylib", at `operator<<`. Component will not be serialized.0x11b46beb2, in ignition::gazebo::v7::systems::SceneBroadcaster::PostUpdate(ignition::gazebo::v7::UpdateInfo const&, ignition::gazebo::v7::EntityComponentManager const&) + 1618

#0    Object "libignition-gazebo7.7.dylib", at 0x10ad19281, in ignition::gazebo::v7::EntityComponentManager::State(ignition::msgs::SerializedStateMap&, std::__1::unordered_set, std::__1::equal_to, std::__1::allocator > const&, std::__1::unordered_set, std::__1::equal_to, std::__1::allocator > const&, bool) const + 273
Segmentation fault: 11

Add support for nested models

The original Gazebo version of the plugin allowed models to be nested, however this is not currently supported in the Ignition version.

Motivation

It is useful to be able to create variants of a basic model that are equipped with different sensors or other peripherals. The base robot, each peripheral, and other components can each be defined as separate models which may then be composed into new robot variants.

For example: a base rover defines the chassis, wheel train and minimal sensor array (viz. IMU sensor). A peripheral model defines a laser scanner. A variant of the rover is then defined by composing the base rover and the laser scanner.

Issues

For composition to work, a plugin must be able to locate links, joints and sensors in composite models, and also define and resolve topics which have been scoped with the nested model names. The following list of issues have been identified:

  1. A nested IMU sensor cannot be resolved: The code in ArduPilotPlugin::PreUpdate that uses the entity component manager (ECM) to search for a named IMU component is not resolving IMU sensors in nested models.

  2. Nested joints cannot be resolved: The function ignition::gazebo::Model::JointByName only searches for joints that have the top level model as a parent. There is no recursion down into nested models.

  3. Topics: the rules for defining topics have changed between classic Gazebo and Ignition. In particular the prefix ~/ which used to be resolved to a namespace prefix comprising the world and top level model name is no longer permitted. The ArduPilot plugin needs to subscribe to a number of topics published by sensors and these need to reference topics published by sensors in the top level model as well as those in nested models. Furthermore the plugin should only need to specify topics up to a world and model namespace which is automatically resolved, otherwise every additional instance of a model spawned will need to be edited to ensure the correct sensor topics are subscribed to - this is not practical if say you are attempting to create a swarm of robots.

installation error

IF YOU DON'T REMOVE THESE FOUR LINES, THEN YOUR REPORT WILL BE CLOSED AUTOMATICALLY
Questions and user problems should be directed at the forum (http://discuss.ardupilot.org)
Please be very sure you have found a bug when opening this issue
If there was a previous discussion in the forum, link to it

Bug report

i am trying to install the plugins for the ardupilot on mac m1 gazebo i am facing the error for the incomplete configuration i need an insigth on it
" ardupilot_gazebo % cmake .. -DCMAKE_BUILD_TYPE=RelWithDebInfo
CMake Error at CMakeLists.txt:37 (find_package):
By not providing "Findgz-cmake3.cmake" in CMAKE_MODULE_PATH this project
has asked CMake to find a package configuration file provided by
"gz-cmake3", but CMake did not find one.

Could not find a package configuration file provided by "gz-cmake3" with
any of the following names:

gz-cmake3Config.cmake
gz-cmake3-config.cmake

Add the installation prefix of "gz-cmake3" to CMAKE_PREFIX_PATH or set
"gz-cmake3_DIR" to a directory containing one of the above files. If
"gz-cmake3" provides a separate development package or SDK, be sure it has
been installed."

Please describe the problem

Version
What version was the issue encountered with gazebo11
Platform
[ x ] All
[ ] AntennaTracker
[ ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

\

Runtime Crash with protobuf on gimbal.sdf launch (Ubuntu 22, GZ Harmonic and humble)

Bug report

Issue details

Trying to build+launch gazebo harmonic with the gimbal.sdf world has a crash on Ubuntu 22.

Version
commit 1caa507 (origin/ros2, ros2)

Platform
[ ] All
[ ] AntennaTracker
[x ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Logs

$ gz sim -r gimbal.sdf
[libprotobuf ERROR google/protobuf/descriptor_database.cc:175] Symbol name "gz.sim.private_msgs.PerformerAffinity" conflicts with the existing symbol "gz.sim.private_msgs.PerformerAffinity".
[libprotobuf FATAL google/protobuf/descriptor.cc:1382] CHECK failed: GeneratedDatabase()->Add(encoded_file_descriptor, size): 
terminate called after throwing an instance of 'google::protobuf::FatalException'
  what():  CHECK failed: GeneratedDatabase()->Add(encoded_file_descriptor, size): 
Stack trace (most recent call last):
#31   Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7f6d4ad14c60, in gz::sim::v8::SdfEntityCreator::CreateEntities(sdf::v14::Model const*)
#30   Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7f6d4acecf55, in 
#29   Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7f6d4ad4d268, in gz::sim::v8::SimulationRunner::LoadPlugins(unsigned long, std::vector<sdf::v14::Plugin, std::allocator<sdf::v14::Plugin> > const&)
#28   Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7f6d4ad59d33, in gz::sim::v8::SystemManager::LoadPlugin(unsigned long, sdf::v14::Plugin const&)
#27   Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7f6d4ad594e9, in gz::sim::v8::SystemLoader::LoadPlugin(sdf::v14::Plugin const&)
#26   Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7f6d4ad584a8, in 
#25   Object "/lib/x86_64-linux-gnu/libgz-plugin2-loader.so.2", at 0x7f6d4b2da56f, in gz::plugin::Loader::LoadLib(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, bool)
#24   Object "/lib/x86_64-linux-gnu/libgz-plugin2-loader.so.2", at 0x7f6d4b2d94dd, in gz::plugin::Loader::Implementation::LoadLib(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, bool)
#23   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f6d4f6906c7, in dlopen
#22   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f6d4f69012d, in 
#21   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f6d4f774b62, in _dl_catch_error
#20   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f6d4f774a97, in _dl_catch_exception
#19   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f6d4f69063b, in 
#18   Object "/lib64/ld-linux-x86-64.so.2", at 0x7f6d4fe4234d, in 
#17   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f6d4f774a97, in _dl_catch_exception
#16   Object "/lib64/ld-linux-x86-64.so.2", at 0x7f6d4fe41ff5, in 
#15   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f6d4f774af4, in _dl_catch_exception
#14   Object "/lib64/ld-linux-x86-64.so.2", at 0x7f6d4fe3a567, in 
#13   Object "/lib64/ld-linux-x86-64.so.2", at 0x7f6d4fe3a47d, in 
#12   Object "/lib/x86_64-linux-gnu/libgz-sim7.so.7", at 0x7f6d072b3d08, in 
#11   Object "/lib/x86_64-linux-gnu/libprotobuf.so.23", at 0x7f6d4a181951, in google::protobuf::internal::AddDescriptors(google::protobuf::internal::DescriptorTable const*)
#10   Object "/lib/x86_64-linux-gnu/libprotobuf.so.23", at 0x7f6d4a181966, in google::protobuf::internal::AddDescriptors(google::protobuf::internal::DescriptorTable const*)
#9    Object "/lib/x86_64-linux-gnu/libprotobuf.so.23", at 0x7f6d4a092c35, in 
#8    Object "/lib/x86_64-linux-gnu/libgcc_s.so.1", at 0x7f6d4bffa2dc, in _Unwind_Resume
#7    Object "/lib/x86_64-linux-gnu/libgcc_s.so.1", at 0x7f6d4bff9883, in 
#6    Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f6d4bcad958, in __gxx_personality_v0
#5    Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f6d4bcad1e8, in 
#4    Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f6d4bcae20b, in 
#3    Object "/lib/x86_64-linux-gnu/libstdc++.so.6", at 0x7f6d4bca2b9d, in 
#2    Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f6d4f6287f2, in abort
#1    Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f6d4f642475, in raise
#0    Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f6d4f6969fc, in pthread_kill
Aborted (Signal sent by tkill() 320400 1000)

I've also gotten this error:

libEGL warning: egl: failed to create dri2 screen
libEGL warning: egl: failed to create dri2 screen
libEGL warning: egl: failed to create dri2 screen
libEGL warning: egl: failed to create dri2 screen
Stack trace (most recent call last):
#28   Object "[0xffffffffffffffff]", at 0xffffffffffffffff, in 
#27   Object "gz sim server", at 0x559dd8e571c4, in _start
#26   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f1cb2c29e3f, in __libc_start_main
#25   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7f1cb2c29d8f, in 
#24   Object "gz sim server", at 0x559dd8e5717e, in 
#23   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb30a8e19, in ruby_run_node
#22   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb30a5317, in 
#21   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb323a30c, in rb_vm_exec
#20   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb3234c96, in 
#19   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb3231fc5, in 
#18   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb322fc34, in 
#17   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb317ba1e, in 
#16   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb30a69ac, in rb_protect
#15   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb323ec61, in rb_yield
#14   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb323a30c, in rb_vm_exec
#13   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb3234c96, in 
#12   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb3231fc5, in 
#11   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb322fc34, in 
#10   Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7f1cb2e3a44b, in 
#9    Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7f1cb31fd088, in rb_nogvl
#8    Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7f1cb2e39d6b, in 
#7    Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7f1caf5f2492, in 
#6    Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7f1caf5f5e2d, in 
#5    Object "/usr/lib/x86_64-linux-gnu/libgz-sim8-gz.so.8.0.0", at 0x7f1caf5967b2, in runServer
#4    Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7f1cae337cf5, in 
#3    Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7f1cae3437c2, in gz::sim::v8::SimulationRunner::Run(unsigned long)
#2    Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7f1cae34fd10, in gz::sim::v8::SimulationRunner::Step(gz::sim::v8::UpdateInfo const&)
#1    Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7f1cae342bb1, in gz::sim::v8::SimulationRunner::UpdateSystems()
#0    Object "/home/ryan/Dev/ros2_ws/src/ardupilot_gazebo/build/libCameraZoomPlugin.so", at 0x7f1c6c166f48, in gz::sim::v8::systems::CameraZoomPlugin::Impl::InitialiseCamera()
Segmentation fault (Address not mapped to object [(nil)])

Environment

Ubuntu 22.04.

ryan@B650-970:~/Dev/ros2_ws/src/ardupilot_gazebo$ echo $GZ_VERSION 
harmonic
ryan@B650-970:~/Dev/ros2_ws/src/ardupilot_gazebo$ echo $GZ_SIM_RESOURCE_PATH 
/home/ryan/Dev/ros2_ws/src/ardupilot_gazebo/models:/home/ryan/Dev/ros2_ws/src/ardupilot_gazebo/worlds:/home/ryan/Dev/ros2_ws/src/ardupilot_gazebo/models:/home/ryan/Dev/ros2_ws/src/ardupilot_gazebo/worlds:
ryan@B650-970:~/Dev/ros2_ws/src/ardupilot_gazebo$ echo $GZ_SIM_SYSTEM_PLUGIN_PATH 
/home/ryan/Dev/ros2_ws/src/ardupilot_gazebo/build:/home/ryan/Dev/ros2_ws/src/ardupilot_gazebo/build:
Package: libprotobuf-dev
Version: 3.12.4-1ubuntu7.22.04.1

Debugging

I tried the docs for GDB after building the app in debug, but it didn't give me a stack trace.
https://gazebosim.org/api/gazebo/3.0/debugging.html

ryan@B650-970:~/Dev/ros2_ws/src/ardupilot_gazebo$ gdb ruby
GNU gdb (Ubuntu 12.1-0ubuntu1~22.04) 12.1
Copyright (C) 2022 Free Software Foundation, Inc.
License GPLv3+: GNU GPL version 3 or later <http://gnu.org/licenses/gpl.html>
This is free software: you are free to change and redistribute it.
There is NO WARRANTY, to the extent permitted by law.
Type "show copying" and "show warranty" for details.
This GDB was configured as "x86_64-linux-gnu".
Type "show configuration" for configuration details.
For bug reporting instructions, please see:
<https://www.gnu.org/software/gdb/bugs/>.
Find the GDB manual and other documentation resources online at:
    <http://www.gnu.org/software/gdb/documentation/>.

For help, type "help".
Type "apropos word" to search for commands related to "word"...
Reading symbols from ruby...
(No debugging symbols found in ruby)
(gdb) r /usr/bin/gz sim -r gimbal.sdf
Starting program: /usr/bin/ruby /usr/bin/gz sim -r gimbal.sdf
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
[Detaching after fork from child process 326800]
[Detaching after fork from child process 326801]
libEGL warning: egl: failed to create dri2 screen
libEGL warning: egl: failed to create dri2 screen
libEGL warning: egl: failed to create dri2 screen
libEGL warning: egl: failed to create dri2 screen
Stack trace (most recent call last):
#29   Object "[0xffffffffffffffff]", at 0xffffffffffffffff, in 
#28   Object "gz sim server", at 0x5555555551c4, in _start
#27   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7ffff7829e3f, in __libc_start_main
#26   Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7ffff7829d8f, in 
#25   Object "gz sim server", at 0x55555555517e, in 
#24   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7ca8e19, in ruby_run_node
#23   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7ca5317, in 
#22   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7e3a30c, in rb_vm_exec
#21   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7e34c96, in 
#20   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7e31fc5, in 
#19   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7e2fc34, in 
#18   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7d7ba1e, in 
#17   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7ca69ac, in rb_protect
#16   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7e3ec61, in rb_yield
#15   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7e3a30c, in rb_vm_exec
#14   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7e34c96, in 
#13   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7e31fc5, in 
#12   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7e2fc34, in 
#11   Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7ffff7a3844b, in 
#10   Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7ffff7dfd088, in rb_nogvl
#9    Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7ffff7a37d6b, in 
#8    Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7ffff419e492, in 
#7    Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7ffff41a1e2d, in 
#6    Object "/usr/lib/x86_64-linux-gnu/libgz-sim8-gz.so.8.0.0", at 0x7ffff41427b2, in runServer
#5    Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7ffff2f37cf5, in 
#4    Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7ffff2f437c2, in gz::sim::v8::SimulationRunner::Run(unsigned long)
#3    Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7ffff2f4fd10, in gz::sim::v8::SimulationRunner::Step(gz::sim::v8::UpdateInfo const&)
#2    Object "/lib/x86_64-linux-gnu/libgz-sim8.so.8", at 0x7ffff2f42bb1, in gz::sim::v8::SimulationRunner::UpdateSystems()
#1    Object "/home/ryan/Dev/ros2_ws/src/ardupilot_gazebo/build/libCameraZoomPlugin.so", at 0x7fffaf6a9aa9, in gz::sim::v8::systems::CameraZoomPlugin::PreUpdate(gz::sim::v8::UpdateInfo const&, gz::sim::v8::EntityComponentManager&)
#0    Object "/home/ryan/Dev/ros2_ws/src/ardupilot_gazebo/build/libCameraZoomPlugin.so", at 0x7fffaf6a825c, in gz::sim::v8::systems::CameraZoomPlugin::Impl::InitialiseCamera()
Segmentation fault (Address not mapped to object [(nil)])
[Inferior 1 (process 326797) exited normally]
(gdb) bt
No stack.

Next step is to compile gazebo from source.
https://gazebosim.org/docs/harmonic/install_ubuntu_src#building-the-gazebo-libraries

make giving error while building plugins

I Followed the setup from here
This is the output of cmake .. -DCMAKE_BUILD_TYPE=RelWithDebInfo command

-- The C compiler identification is GNU 7.5.0
-- The CXX compiler identification is GNU 7.5.0
-- Check for working C compiler: /usr/lib/ccache/cc
-- Check for working C compiler: /usr/lib/ccache/cc -- works
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Detecting C compile features
-- Detecting C compile features - done
-- Check for working CXX compiler: /usr/lib/ccache/c++
-- Check for working CXX compiler: /usr/lib/ccache/c++ -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Looking for ignition-gazebo5 -- found version 5.4.0
-- Searching for dependencies of ignition-gazebo5
-- Looking for sdformat11 -- found version 11.4.1
-- Searching for dependencies of sdformat11
-- Checking for module 'tinyxml2'
--   Found tinyxml2, version 6.0.0
-- Looking for ignition-math6 -- found version 6.10.0
-- Searching for dependencies of ignition-math6
-- Looking for ignition-utils1 -- found version 1.4.0
-- Searching for dependencies of ignition-utils1
-- Looking for ignition-plugin1 -- found version 1.2.1
-- Searching for dependencies of ignition-plugin1
-- Searching for <ignition-plugin1> component [loader]
-- Looking for ignition-plugin1-loader -- found version 1.2.1
-- Searching for dependencies of ignition-plugin1-loader
-- Searching for <ignition-plugin1> component [register]
-- Looking for ignition-plugin1-register -- found version 1.2.1
-- Searching for dependencies of ignition-plugin1-register
-- Looking for ignition-transport10 -- found version 10.2.0
-- Searching for dependencies of ignition-transport10
-- Found ZLIB: /usr/lib/x86_64-linux-gnu/libz.so (found version "1.2.11") 
-- Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'
--   Found libzmq , version 4.2.5
-- Found ZeroMQ: TRUE (Required is at least version "4") 
-- Checking for module 'uuid'
--   Found uuid, version 2.31.1
-- Found UUID: TRUE  
-- Looking for ignition-utils1 -- found version 1.4.0
-- Searching for dependencies of ignition-utils1
-- Searching for <ignition-utils1> component [cli]
-- Looking for ignition-utils1-cli -- found version 1.4.0
-- Searching for dependencies of ignition-utils1-cli
-- Looking for ignition-msgs7 -- found version 7.3.0
-- Searching for dependencies of ignition-msgs7
-- Looking for ignition-math6 -- found version 6.10.0
-- Searching for <ignition-transport10> component [log]
-- Looking for ignition-transport10-log -- found version 10.2.0
-- Searching for dependencies of ignition-transport10-log
-- Looking for ignition-msgs7 -- found version 7.3.0
-- Looking for ignition-common4 -- found version 4.5.0
-- Searching for dependencies of ignition-common4
-- Looking for dlfcn.h - found
-- Looking for libdl - found
-- Found DL: TRUE  
-- Searching for <ignition-common4> component [profiler]
-- Looking for ignition-common4-profiler -- found version 4.5.0
-- Searching for dependencies of ignition-common4-profiler
-- Searching for <ignition-common4> component [events]
-- Looking for ignition-common4-events -- found version 4.5.0
-- Searching for dependencies of ignition-common4-events
-- Looking for ignition-math6 -- found version 6.10.0
-- Searching for <ignition-common4> component [av]
-- Looking for ignition-common4-av -- found version 4.5.0
-- Searching for dependencies of ignition-common4-av
-- Checking for module 'libswscale'
--   Found libswscale, version 4.8.100
-- Found SWSCALE: TRUE  
-- Checking for module 'libavdevice >= 56.4.100'
--   Found libavdevice , version 57.10.100
-- Found AVDEVICE: TRUE (Required is at least version "56.4.100") 
-- Checking for module 'libavformat'
--   Found libavformat, version 57.83.100
-- Found AVFORMAT: TRUE  
-- Checking for module 'libavcodec'
--   Found libavcodec, version 57.107.100
-- Found AVCODEC: TRUE  
-- Checking for module 'libavutil'
--   Found libavutil, version 55.78.100
-- Found AVUTIL: TRUE  
-- Looking for ignition-fuel_tools6 -- found version 6.2.0
-- Searching for dependencies of ignition-fuel_tools6
-- Found CURL: /usr/lib/x86_64-linux-gnu/libcurl.so (found version "7.58.0") 
-- Checking for module 'jsoncpp'
--   Found jsoncpp, version 1.7.4
-- Found JSONCPP: TRUE  
-- Checking for module 'yaml-0.1'
--   Found yaml-0.1, version 0.1.7
-- Found YAML: TRUE  
-- Checking for module 'libzip'
--   Found libzip, version 1.1.2
-- Found ZIP: TRUE  
-- Looking for ignition-common4 -- found version 4.5.0
-- Looking for ignition-math6 -- found version 6.10.0
-- Looking for ignition-msgs7 -- found version 7.3.0
-- Looking for ignition-gui5 -- found version 5.5.0
-- Searching for dependencies of ignition-gui5
-- Looking for ignition-math6 -- found version 6.10.0
-- Looking for ignition-common4 -- found version 4.5.0
-- Looking for ignition-plugin1 -- found version 1.2.1
-- Looking for ignition-transport10 -- found version 10.2.0
-- Looking for ignition-rendering5 -- found version 5.2.1
-- Searching for dependencies of ignition-rendering5
-- Looking for ignition-math6 -- found version 6.10.0
-- Looking for ignition-common4 -- found version 4.5.0
-- Searching for dependencies of ignition-common4
-- Looking for dlfcn.h - found
-- Looking for libdl - found
-- Searching for <ignition-common4> component [graphics]
-- Looking for ignition-common4-graphics -- found version 4.5.0
-- Searching for dependencies of ignition-common4-graphics
-- Looking for ignition-math6 -- found version 6.10.0
-- Looking for ignition-utils1 -- found version 1.4.0
-- Searching for <ignition-common4> component [events]
-- Looking for ignition-plugin1 -- found version 1.2.1
-- Searching for dependencies of ignition-plugin1
-- Searching for <ignition-plugin1> component [all]
-- Looking for all libraries of ignition-plugin1 -- found version 1.2.1
-- Looking for ignition-msgs7 -- found version 7.3.0
-- Looking for ignition-physics4 -- found version 4.3.0
-- Searching for dependencies of ignition-physics4
-- Looking for ignition-math6 -- found version 6.10.0
-- Searching for dependencies of ignition-math6
-- Searching for <ignition-math6> component [eigen3]
-- Looking for ignition-math6-eigen3 -- found version 6.10.0
-- Searching for dependencies of ignition-math6-eigen3
-- Looking for ignition-plugin1 -- found version 1.2.1
-- Looking for ignition-utils1 -- found version 1.4.0
-- Searching for <ignition-physics4> component [heightmap]
-- Looking for ignition-physics4-heightmap -- found version 4.3.0
-- Searching for dependencies of ignition-physics4-heightmap
-- Looking for ignition-common4 -- found version 4.5.0
-- Searching for <ignition-physics4> component [mesh]
-- Looking for ignition-physics4-mesh -- found version 4.3.0
-- Searching for dependencies of ignition-physics4-mesh
-- Looking for ignition-common4 -- found version 4.5.0
-- Searching for <ignition-physics4> component [sdf]
-- Looking for ignition-physics4-sdf -- found version 4.3.0
-- Searching for dependencies of ignition-physics4-sdf
-- Looking for sdformat11 -- found version 11.4.1
-- Looking for ignition-sensors5 -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5
-- Looking for ignition-math6 -- found version 6.10.0
-- Looking for ignition-common4 -- found version 4.5.0
-- Looking for ignition-transport10 -- found version 10.2.0
-- Looking for ignition-rendering5 -- found version 5.2.1
-- Looking for ignition-msgs7 -- found version 7.3.0
-- Looking for ignition-plugin1 -- found version 1.2.1
-- Looking for sdformat11 -- found version 11.4.1
-- Searching for <ignition-sensors5> component [rendering]
-- Looking for ignition-sensors5-rendering -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5-rendering
-- Searching for <ignition-sensors5> component [air_pressure]
-- Looking for ignition-sensors5-air_pressure -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5-air_pressure
-- Searching for <ignition-sensors5> component [altimeter]
-- Looking for ignition-sensors5-altimeter -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5-altimeter
-- Searching for <ignition-sensors5> component [camera]
-- Looking for ignition-sensors5-camera -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5-camera
-- Searching for <ignition-sensors5> component [gpu_lidar]
-- Looking for ignition-sensors5-gpu_lidar -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5-gpu_lidar
-- Searching for <ignition-sensors5> component [imu]
-- Looking for ignition-sensors5-imu -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5-imu
-- Searching for <ignition-sensors5> component [logical_camera]
-- Looking for ignition-sensors5-logical_camera -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5-logical_camera
-- Searching for <ignition-sensors5> component [magnetometer]
-- Looking for ignition-sensors5-magnetometer -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5-magnetometer
-- Searching for <ignition-sensors5> component [depth_camera]
-- Looking for ignition-sensors5-depth_camera -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5-depth_camera
-- Searching for <ignition-sensors5> component [thermal_camera]
-- Looking for ignition-sensors5-thermal_camera -- found version 5.1.1
-- Searching for dependencies of ignition-sensors5-thermal_camera
-- Looking for ignition-rendering5 -- found version 5.2.1
-- Looking for ignition-math6 -- found version 6.10.0
-- Looking for ignition-utils1 -- found version 1.4.0
-- Looking for ignition-gazebo5 - found

-- RapidJSON found. Headers: /usr/include
-- Configuring done
-- Generating done
-- Build files have been written to: /home/asif/Desktop/ignition/ardupilot_gazebo/build

After running make -j4 I am getting this error

/home/asif/Desktop/ignition/ardupilot_gazebo/src/ArduPilotPlugin.cc: In function ‘void SendState()’:
/home/asif/Desktop/ignition/ardupilot_gazebo/src/ArduPilotPlugin.cc:1424:5: error: invalid use of ‘this’ in non-member function
     this->dataPtr->sock.sendto(
     ^~~~
/home/asif/Desktop/ignition/ardupilot_gazebo/src/ArduPilotPlugin.cc:1425:9: error: invalid use of ‘this’ in non-member function
         this->dataPtr->json_str.c_str(),
         ^~~~
/home/asif/Desktop/ignition/ardupilot_gazebo/src/ArduPilotPlugin.cc:1426:9: error: invalid use of ‘this’ in non-member function
         this->dataPtr->json_str.size(),
         ^~~~
/home/asif/Desktop/ignition/ardupilot_gazebo/src/ArduPilotPlugin.cc:1427:9: error: invalid use of ‘this’ in non-member function
         this->dataPtr->fcu_address,
         ^~~~
/home/asif/Desktop/ignition/ardupilot_gazebo/src/ArduPilotPlugin.cc:1428:9: error: invalid use of ‘this’ in non-member function
         this->dataPtr->fcu_port_out);
         ^~~~
CMakeFiles/ArduPilotPlugin.dir/build.make:62: recipe for target 'CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o' failed
make[2]: *** [CMakeFiles/ArduPilotPlugin.dir/src/ArduPilotPlugin.cc.o] Error 1
CMakeFiles/Makefile2:67: recipe for target 'CMakeFiles/ArduPilotPlugin.dir/all' failed
make[1]: *** [CMakeFiles/ArduPilotPlugin.dir/all] Error 2
Makefile:83: recipe for target 'all' failed
make: *** [all] Error 2

Full error log is here

My system:
Ubuntu 18.04 (Bionic)
Ignition Edifice

Zephyr elevon servo inconsistency with ardupilot parameters

Servo reverse inconsistency

In zephyr model.sdf servos determined as

``

      SERVO1_FUNCTION   77 (Elevon Left)
      SERVO1_MAX        1900
      SERVO1_MIN        1100
      SERVO1_REVERSED   0
      SERVO1_TRIM       1500

      pwm:          =>  [1100, 1900] 
      input:        =>  [0, 1]
      offset: -0.5  =>  [-0.5, 0.5]
      scale:   2.0  =>  [-1.0, 1.0]
      scale: 0.524  =>  [-0.524, 0.524]

``

But gazebo-zephyr.parm in ardupilot assuming, that

SERVO1_REVERSED = 1 SERVO2_REVERSED = 1

Fix transform from ENU to NED in examples

Bug report

The plugin xml has an incorrect mapping between the world frames used in Gazebo and ArduPilot.

The change required to correct the transform from ENU to NED is:

-      <gazeboXYZToNED>0 0 0 3.141593 0 0</gazeboXYZToNED>
+      <gazeboXYZToNED>0 0 0 3.141593 0 1.57079632</gazeboXYZToNED>

The inconsistency becomes apparent when fixing geo coordinates in a Gazebo world file and using the NavSat sensor, or when using ROS to bridge data via MAVProxy or DDS to the flight controller.

Multi Vehicle SITL support

IF YOU DON'T REMOVE THESE FOUR LINES, THEN YOUR REQUEST WILL BE CLOSED AUTOMATICALLY
Questions and user problems should be directed at the forum (http://discuss.ardupilot.org)
Please do a careful search before opening this, there are already a lot of feature requests
If there was a previous discussion in the forum, link to it

Feature request

Is your feature request related to a problem? Please describe.
A clear and concise description of what the problem is. Ex. I'm always frustrated when [...]

Describe the solution you'd like
A clear and concise description of what you want to happen.

Describe alternatives you've considered
A clear and concise description of any alternative solutions or features you've considered.

Platform
[ ] All
[ ] AntennaTracker
[ ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Additional context
Add any other context or screenshots about the feature request here.

Add multi-agent heterogenous demo with zephyr and iris in one environment

Feature request

Is your feature request related to a problem? Please describe.

I want to simulate a mixed fleet of vehicle types in Gazebo, but it's not clear how to do that.

Describe the solution you'd like

https://discuss.ardupilot.org/t/multi-vehicle-zephyr-and-iris-ardupilot-gazebo-simulation-going-to-different-points-in-gazebo-simulation-for-the-same-lat-lon-alt/90686

Add the iris and the zephyr models to the same environment, as requested above. Then, demonstrate how to run SITL where you can have two mavproxy sessions, one for each vehicle, and have both vehicles flying at the same time (perhaps hover the iris, and then have the plane do a loiter circle around).

Describe alternatives you've considered

Platform
[ ] All
[ ] AntennaTracker
[x] Copter
[x] Plane
[ ] Rover
[ ] Submarine

Additional context

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.