Skip to content

Commit

Permalink
CI: Add RoboStack cross-platform build (#1636)
Browse files Browse the repository at this point in the history
Co-authored-by: Robert Haschke <[email protected]>
  • Loading branch information
Tobias-Fischer and rhaschke authored Nov 3, 2021
1 parent a4919f5 commit 3924f0e
Show file tree
Hide file tree
Showing 12 changed files with 185 additions and 3 deletions.
16 changes: 16 additions & 0 deletions .github/robostack_env.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
name: test
channels:
- robostack
- conda-forge
dependencies:
- compilers
- ninja
- cmake
- catkin_pkg
- pkg-config
- rosdep
- rosdistro
- ros-distro-mutex 0.1 noetic
- ros-noetic-catkin
- ros-noetic-ros-environment
- openssl 1.1.1*
File renamed without changes.
103 changes: 103 additions & 0 deletions .github/workflows/robostack.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
name: RoboStack

on:
workflow_dispatch:
pull_request:
push:
branches:
- master
- "[kmn]*-devel*"

jobs:
run_rviz_compilation:
runs-on: ${{ matrix.os }}
name: ${{ matrix.os }}
strategy:
fail-fast: false
matrix:
os: [ubuntu-latest, macos-latest, windows-latest]

steps:
- uses: actions/checkout@v2

- name: Set up Build Dependencies
uses: mamba-org/provision-with-micromamba@v11
with:
environment-file: .github/robostack_env.yaml
micromamba-version: "0.17.0"

- name: Set up rviz Dependencies on Unix
if: runner.os == 'Linux' || runner.os == 'macOS'
shell: bash -l -eo pipefail {0}
run: |
micromamba activate test
export PATH=$HOME/micromamba-bin:$PATH
if [[ `uname -s` == "Linux" ]]; then
CDT="-cos6-x86_64"
micromamba install -y mesa-libgl-devel$CDT mesa-dri-drivers$CDT \
libselinux$CDT libxdamage$CDT libxxf86vm$CDT \
libxext$CDT libxfixes$CDT -c conda-forge
fi
rosdep init
rosdep update
rosdep install --from-paths . --ignore-src -r -y
- name: Build rviz on Unix
if: runner.os == 'Linux' || runner.os == 'macOS'
shell: bash -l -eo pipefail {0}
run: |
export CTEST_OUTPUT_ON_FAILURE=1
mkdir build
cd build
cmake .. -DCMAKE_PREFIX_PATH=$CONDA_PREFIX \
-DCMAKE_INSTALL_PREFIX=$CONDA_PREFIX \
-DCMAKE_BUILD_TYPE=Release \
-DCATKIN_SKIP_TESTING=OFF \
-G "Ninja"
ninja
ninja run_tests
- name: Set up rviz Dependencies on Windows
if: runner.os == 'Windows'
shell: cmd
run: |
echo "Activate environment, and use rosdep to install dependencies"
call C:\Users\runneradmin\micromamba\condabin\micromamba.bat activate test
rosdep init
rosdep update
rosdep install --from-paths . --ignore-src -r -y
- name: Build rviz on Windows
if: runner.os == 'Windows'
shell: cmd
run: |
echo "Remove unnecessary / colliding things from PATH"
set "PATH=%PATH:C:\ProgramData\Chocolatey\bin;=%"
set "PATH=%PATH:C:\Program Files (x86)\sbt\bin;=%"
set "PATH=%PATH:C:\Rust\.cargo\bin;=%"
set "PATH=%PATH:C:\Program Files\Git\usr\bin;=%"
set "PATH=%PATH:C:\Program Files\Git\cmd;=%"
set "PATH=%PATH:C:\Program Files\Git\mingw64\bin;=%"
set "PATH=%PATH:C:\Program Files (x86)\Subversion\bin;=%"
set "PATH=%PATH:C:\Program Files\CMake\bin;=%"
set "PATH=%PATH:C:\Program Files\OpenSSL\bin;=%"
set "PATH=%PATH:C:\Strawberry\c\bin;=%"
set "PATH=%PATH:C:\Strawberry\perl\bin;=%"
set "PATH=%PATH:C:\Strawberry\perl\site\bin;=%"
set "PATH=%PATH:c:\tools\php;=%"
set "PATH=%PATH:ostedtoolcache=%"
call C:\Users\runneradmin\micromamba\condabin\micromamba.bat activate test
mkdir build
cd build
SET "CTEST_OUTPUT_ON_FAILURE=1"
cmake .. -DCMAKE_PREFIX_PATH="%CONDA_PREFIX%\Library" ^
-DCMAKE_INSTALL_PREFIX="%CONDA_PREFIX%\Library" ^
-DCMAKE_BUILD_TYPE=Release ^
-DCATKIN_SKIP_TESTING=OFF ^
-DBoost_USE_STATIC_LIBS=OFF ^
-G "Ninja"
ninja
ninja run_tests
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ find_package(Boost REQUIRED
find_package(urdfdom_headers REQUIRED)

set(CMAKE_POLICY_DEFAULT_CMP0012 NEW) # required due to a bug in assimp 5.0
find_package(ASSIMP REQUIRED)
find_package(assimp REQUIRED)
if(NOT DEFINED ASSIMP_LIBRARIES AND TARGET assimp::assimp)
# ASSIMP >= 5.0 no longer defines ASSIMP_LIBRARIES
set(ASSIMP_LIBRARIES assimp::assimp)
Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
<build_depend>liburdfdom-dev</build_depend>
<build_depend>liburdfdom-headers-dev</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>assimp</build_depend>

<build_export_depend>libogre-dev</build_export_depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@
#ifndef INTERACTIVE_MARKER_CONTROL_H_
#define INTERACTIVE_MARKER_CONTROL_H_


#ifndef Q_MOC_RUN
#include <boost/shared_ptr.hpp>
#include <boost/enable_shared_from_this.hpp>
Expand All @@ -45,6 +44,7 @@

#include <visualization_msgs/InteractiveMarkerControl.h>

#include <rviz/windows_compat.h>
#include <rviz/default_plugin/markers/marker_base.h>
#include <rviz/selection/forwards.h>
#include <rviz/viewport_mouse_event.h>
Expand Down
2 changes: 2 additions & 0 deletions src/rviz/default_plugin/marker_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,11 @@
#include <rviz/properties/property.h>
#include <rviz/properties/ros_topic_property.h>
#include <rviz/selection/selection_manager.h>
#include <rviz/windows_compat.h>

#include <rviz/default_plugin/marker_display.h>


namespace rviz
{
////////////////////////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
2 changes: 2 additions & 0 deletions src/rviz/default_plugin/marker_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@
#include <rviz/properties/status_list.h>
#include <rviz/validate_quaternions.h>
#include <rviz/validate_floats.h>
#include <rviz/windows_compat.h>


namespace rviz
{
Expand Down
3 changes: 2 additions & 1 deletion src/rviz/mesh_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -768,7 +768,8 @@ Ogre::SkeletonPtr loadSkeletonFromResource(const std::string& resource_path)
Ogre::SkeletonSerializer ser;
Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
Ogre::SkeletonPtr skeleton = Ogre::SkeletonManager::getSingleton().create(
skeleton_path.filename().c_str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, true);
skeleton_path.filename().string().c_str(),
Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, true);
ser.importSkeleton(stream, skeleton.get());

return skeleton;
Expand Down
8 changes: 8 additions & 0 deletions src/rviz/ogre_helpers/render_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,10 @@
#include <GL/glx.h>
#endif

#if defined(Q_OS_MAC)
#include <OpenGL/gl.h>
#endif

// X.h #defines CursorShape to be "0". Qt uses CursorShape in normal
// C++ way. This wasn't an issue until ogre_logging.h (below)
// introduced a #include of <QString>.
Expand Down Expand Up @@ -183,9 +187,13 @@ void RenderSystem::detectGlVersion()
int minor = caps->getDriverVersion().minor;
gl_version_ = major * 100 + minor * 10;

#ifdef __linux__
std::string gl_version_string = (const char*)glGetString(GL_VERSION);
// The "Mesa 2" string is intended to match "Mesa 20.", "Mesa 21." and so on
mesa_workaround = gl_version_string.find("Mesa 2") != std::string::npos && gl_version_ >= 320;
#else
mesa_workaround = false;
#endif
}

switch (gl_version_)
Expand Down
45 changes: 45 additions & 0 deletions src/rviz/windows_compat.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
/*
* Copyright (c) 2021, Tobias Fischer, Queensland University of Technology
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Queensland Uni of Technology nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef WINDOWS_COMPAT_H
#define WINDOWS_COMPAT_H

#ifdef _WIN32

#ifdef ERROR
#undef ERROR
#endif

#ifdef DELETE
#undef DELETE
#endif

#endif // _WIN32

#endif // WINDOWS_COMPAT_H
4 changes: 4 additions & 0 deletions src/rviz/yaml_config_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,11 @@ void YamlConfigWriter::writeConfigNode(const Config& config, YAML::Emitter& emit
break;
}
default:
// Workaround as YAML::Null is missing from Windows DLLs;
// see https://github.com/jbeder/yaml-cpp/issues/950
#ifndef _WIN32
emitter << YAML::Null;
#endif
break;
}
}
Expand Down

0 comments on commit 3924f0e

Please sign in to comment.