Running Ignition Fortress headless in Docker for CI
Dear Ignition Community,
i am trying to integrate Ignition Gazebo Fortress into a Continous Integration Pipeline in gitlab using Docker. Therefore, the installation instructions are followed inside Docker [1]. The linting steps, build steps, etc. are working so far.
For the test stage i have defined a *.test, where the ros_ign parameter bridge as well as ignition gazebo are to be started, since my test class is working on subscribed ROS topic, which are to be interpreted in terms of statistics (do lidars obtain the correct intensities, reflections, and so on ...).
The rostest file looks like:
<?xml version="1.0"?>
<launch>
<include file="$(find ign_my_package)/test/test_ros_gpu_lidar_subscriber.launch"/>
<test test-name="test_ros_gpu_lidar_subscriber" pkg="ign_my_package" type="test_ros_gpu_lidar_subscriber" time-limit="180.0" />
</launch>
The referenced testrosgpulidarsubscriber.launch file looks like:
<?xml version="1.0"?>
<launch>
<!-- Launch the bridge -->
<node name="parameter_bridge_ros_subscriber" pkg="ros_ign_bridge" type="parameter_bridge" args="/lidar@sensor_msgs/LaserScan@ignition.msgs.LaserScan /lidar/points@sensor_msgs/PointCloud2@ignition.msgs.PointCloudPacked"/>
<include file="$(find ros_ign_gazebo)/launch/ign_gazebo.launch">
<arg name="ign_args" value="-r -s -v 4 gpu_lidar_retro_values_sensor.sdf --headless-rendering"/>
</include>
</launch>
Since I have no rendering window available, i thought the recently released and mentioned EGL headless mode [2], would be the ideal application to enable a renderless runner via
ign gazebo -s --headless-rendering
But when my CI pipeline comes the the test stage, where i am going to run some rostests based on the execution of launch files, i obtain the following error:
[Err] [Ogre2RenderEngine.cc:394] Unable to open display: terminate called after throwing an instance of 'Ogre::RenderingAPIException' what(): OGRE EXCEPTION(3:RenderingAPIException): No Interface could be loaded. Check previous error messages.Try disabling OpenGL plugin from plugins.cfg. in GlSwitchableSupport::GlSwitchableSupport at [...]
Are there any indications why this fails? Are there positive experiences integrating rostests with IGNITION GAZEBO (FORTRESS) within Docker headless?
Update:
Using the hints from the dolly example in the comments below
export DISPLAY=:1.0
export MESA_GL_VERSION_OVERRIDE=3.3
result to the following error:
[Err] [Ogre2RenderEngine.cc:394] Unable to open display: :1.0 terminate called after throwing an instance of 'Ogre::RenderingAPIException' what(): OGRE EXCEPTION(3:RenderingAPIException): No Interface could be loaded. Check previous error messages.Try disabling OpenGL plugin from plugins.cfg. in GlSwitchableSupport::GlSwitchableSupport [...]
I can think of two reasons for this:
- Somehow, the combination of mesa/opengl/ogre-library combination does not fit well. But since i am installing the libraries as the default ignition tutorial proposes, this should work.
- Second, maybe and somehow the way how my tests are build up using rostest and therefore starting ingition via launch-files (and the headless parameter) could also potentially bring in some problems. The dolly example is based on a dedicated test fixture class [3] starting up ignition.
Are there other examples using iginition headless using test suites, to see if
- some packages/dependencies/whatever (preconditions for docker environment) are wrong or
- the rostest integration is incorrect or not suitable for headless execution in CI/CD environments?
Best regards, Marc
References:
- [1] https://ignitionrobotics.org/docs/fortress
- [2] https://community.gazebosim.org/t/egl-support-is-available-in-ignition-fortress/1183
- [3] https://github.com/chapulina/dolly/blob/galactic/dolly_tests/test/follow_ignition_TEST.cpp
Asked by Illuminatur on 2021-12-26 01:56:19 UTC
Answers
Are there positive experiences integrating rostests with IGNITION GAZEBO (FORTRESS) within Docker headless?
Here's an example: https://github.com/chapulina/dolly/pull/41/files
Maybe what you're missing are these environment variables:
export DISPLAY=:1.0
export MESA_GL_VERSION_OVERRIDE=3.3
Asked by chapulina on 2021-12-28 18:14:39 UTC
Comments
Hey chapulina,
thx lot. I just tried that solution, but that doesnt seem to work. Due to the limited amount of characters I am going to extend my problem statement above.
BR, Marc
Asked by Illuminatur on 2022-01-05 05:21:12 UTC
Dear Louise,
in my docker environment, while copying almost the dolly's example shell script, i obtain the above mentioned error. Are there any special constraints how you setup the docker environment for testing dolly in the loop? Maybe any packages or constraints i am missing?
I am using the dolly approach using catkin instead of colcon, but it fails despite using the beforementioned environment variables this way:
[Err] [Ogre2RenderEngine.cc:394] Unable to open display: :1.0
BR, Marc
Asked by Illuminatur on 2022-02-08 04:14:52 UTC
Hi,
in the meantime i adopted my example (see above) to the solution, proposed by chapulina [0]. Therefore, the resulting test launch file only invokes a spawning mechanism for a robot model sdf, the IGN2ROS1 bridging stuff and a test fixture class - similar to the dolly one -, which loads a world description and defines the server to run headless via:
ignition::gazebo::ServerConfig config;
config.SetSdfFile(ignition::common::joinPaths(std::string(PROJECT_SOURCE_PATH), "worlds", "empty.sdf"));
config.SetHeadlessRendering(true);
ignition::gazebo::TestFixture fixture(config);
I tried to track the problem down to its roots, and found some deeper lying issues:
First, according to a recently merged tutorial [1] the following user to group assignment might be necessary (for ubuntu 20.04). Although the respective tutorial aims at the use within AWS, this could also apply to Docker. I have not yet been able to check this.
sudo usermod -a -G render user
Additionally, according to [2], it might be necessary to build Ogre2 with the compile flag
OGRE_GLSUPPORT_USE_EGL_HEADLESS
Since i installed ignition gazebo dolly's way by mimicing the shell script [3] and thereby the packages libignition-rendering6-ogre2 and libignition-rendering6-ogre2-dev are installed, I would assume that those libs had been built by this.
Analyzing the Ogre2 logs, which are stored inside ~/.ignition/rendering, the EGL devices seem to be missing:
17:39:48: *-*-* OGRE Initialising
17:39:48: *-*-* Version 2.2.6 (Cerberus)
[...]
17:39:48: Loading library /usr/lib/x86_64-linux-gnu/OGRE-2.2/OGRE/RenderSystem_GL3Plus.so
17:39:48: Installing plugin: GL 3+ RenderSystem
17:39:48: OpenGL 3+ Rendering Subsystem created.
17:39:48: OGRE EXCEPTION(3:RenderingAPIException): Couldn`t open X display :1.0 in GLXGLSupport::getGLDisplay at [...]
17:39:48: Found Num EGL Devices: 0
17:39:48: OGRE EXCEPTION(3:RenderingAPIException): No EGL devices found! Update your GPU drivers and try again in EglPBufferSupport::EglPBufferSupport at [...]
17:39:48: EGL Headless raised an exception. Won't be available. Are drivers too old?
Delivering 0 EGL devices, it seems to be a problem with the EGL impl. of Ogre2 inside Docker.
Are there any other experiences, additional ideas or hints?
References:
[0] Run tests headless with EGL, https://github.com/chapulina/dolly/pull/41/files
[1] https://github.com/ignitionrobotics/ign-gazebo/pull/1386
[2] https://github.com/OGRECave/ogre-next/tree/master/Samples/2.0/Tutorials/Tutorial_EglHeadless
[3] https://github.com/chapulina/dolly/blob/galactic/.github/workflows/build-and-test.sh
Asked by Illuminatur on 2022-04-05 10:41:17 UTC
Comments