SITL Gazebo simulation fails on macOS - 'cv.h' file not found

I’m on the stable branch and when I try to build for gazebo I get the following error:

➜  Firmware git:(stable) make posix_sitl_default gazebo
ninja: Entering directory `/Users/dlw/Workspace/PX4/Firmware/build/posix_sitl_default'
[3/7] Performing configure step for 'sitl_gazebo'
-- install-prefix: /usr/local
-- Boost version: 1.68.0
-- Found the following Boost libraries:
--   system
--   thread
--   timer
--   chrono
--   date_time
--   atomic
-- Boost version: 1.68.0
-- Found the following Boost libraries:
--   thread
--   signals
--   system
--   filesystem
--   program_options
--   regex
--   iostreams
--   date_time
--   chrono
--   atomic
-- Boost version: 1.68.0
-- Looking for OGRE...
-- Found Ogre Ghadamon (1.9.0)
-- Looking for OGRE_Paging...
-- Found OGRE_Paging: optimized;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgrePaging.dylib;debug;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgrePaging.dylib
-- Looking for OGRE_Terrain...
-- Found OGRE_Terrain: optimized;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgreTerrain.dylib;debug;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgreTerrain.dylib
-- Looking for OGRE_Property...
-- Found OGRE_Property: optimized;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgreProperty.dylib;debug;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgreProperty.dylib
-- Looking for OGRE_RTShaderSystem...
-- Found OGRE_RTShaderSystem: optimized;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgreRTShaderSystem.dylib;debug;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgreRTShaderSystem.dylib
-- Looking for OGRE_Volume...
-- Found OGRE_Volume: optimized;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgreVolume.dylib;debug;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgreVolume.dylib
-- Looking for OGRE_Overlay...
-- Found OGRE_Overlay: optimized;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgreOverlay.dylib;debug;/usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/lib/libOgreOverlay.dylib
-- Checking for module 'libzmq>=3.2.0'
--   Package 'libunwind', required by 'libzmq', not found
-- Looking for zmq pkgconfig file - not found
-- Looking for ignition-msgs - found
-- Building klt_feature_tracker without catkin
-- Building OpticalFlow with OpenCV
-- catkin DISABLED
Gazebo version: 8.6
-- Using C++17 compiler
-- Configuring done
-- Generating done
-- Build files have been written to: /Users/dlw/Workspace/PX4/Firmware/build/posix_sitl_default/build_gazebo
[4/7] Performing build step for 'sitl_gazebo'
FAILED: external/Stamp/sitl_gazebo/sitl_gazebo-build
cd /Users/dlw/Workspace/PX4/Firmware/build/posix_sitl_default/build_gazebo && /usr/local/Cellar/cmake/3.13.3/bin/cmake --build . && /usr/local/Cellar/cmake/3.13.3/bin/cmake -E touch /Users/dlw/Workspace/PX4/Firmware/build/posix_sitl_default/external/Stamp/sitl_gazebo/sitl_gazebo-build
[1/46] Building CXX object CMakeFiles/sensor_msgs.dir/OpticalFlow.pb.cc.o
[2/46] Building CXX object CMakeFiles/sensor_msgs.dir/IRLock.pb.cc.o
[3/46] Building CXX object CMakeFiles/mav_msgs.dir/CommandMotorSpeed.pb.cc.o
[4/46] Building CXX object CMakeFiles/mav_msgs.dir/MotorSpeed.pb.cc.o
[5/46] Linking CXX shared library libmav_msgs.dylib
[6/46] Building CXX object CMakeFiles/sensor_msgs.dir/Imu.pb.cc.o
[7/46] Building CXX object CMakeFiles/sensor_msgs.dir/Float.pb.cc.o
[8/46] Building CXX object CMakeFiles/sensor_msgs.dir/Range.pb.cc.o
[9/46] Building CXX object CMakeFiles/sensor_msgs.dir/Groundtruth.pb.cc.o
[10/46] Linking CXX shared library libstd_msgs.dylib
[11/46] Building CXX object CMakeFiles/sensor_msgs.dir/SITLGps.pb.cc.o
[12/46] Linking CXX shared library libsensor_msgs.dylib
[13/46] Generating /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/px4flow/px4flow-gen.sdf
/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/px4flow/px4flow.sdf.jinja -> /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/px4flow/px4flow-gen.sdf
[14/46] Generating /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/pixhawk/pixhawk-gen.sdf
/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/pixhawk/pixhawk.sdf.jinja -> /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/pixhawk/pixhawk-gen.sdf
[15/46] Generating /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/r200/r200-gen.sdf
/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/r200/r200.sdf.jinja -> /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/r200/r200-gen.sdf
[16/46] Generating /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/sf10a/sf10a-gen.sdf
/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/sf10a/sf10a.sdf.jinja -> /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/models/sf10a/sf10a-gen.sdf
[17/46] Building CXX object OpticalFlow/CMakeFiles/OpticalFlow.dir/src/px4flow.cpp.o
[18/46] Building CXX object OpticalFlow/CMakeFiles/OpticalFlow.dir/src/optical_flow.cpp.o
[19/46] Building CXX object OpticalFlow/CMakeFiles/OpticalFlow.dir/src/flow_px4.cpp.o
[20/46] Building CXX object CMakeFiles/nav_msgs.dir/Odometry.pb.cc.o
[21/46] Linking CXX shared library libnav_msgs.dylib
[22/46] Building CXX object OpticalFlow/CMakeFiles/OpticalFlow.dir/src/flow_opencv.cpp.o
FAILED: OpticalFlow/CMakeFiles/OpticalFlow.dir/src/flow_opencv.cpp.o
/Library/Developer/CommandLineTools/usr/bin/c++  -DLIBBULLET_VERSION=2.88 -DLIBBULLET_VERSION_GT_282 -DOpticalFlow_EXPORTS -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/OpticalFlow_INCLUDE_DIRS -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/include -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/external/klt_feature_tracker/include -isystem /usr/local/Cellar/gazebo8/8.6.0_5/include -isystem /usr/local/Cellar/gazebo8/8.6.0_5/include/gazebo-8 -isystem /usr/local/Cellar/bullet/2.88/include/bullet -isystem /usr/local/Cellar/bullet/2.88/include -isystem /usr/local/include/simbody -isystem /usr/local/include -isystem /usr/local/Cellar/sdformat5/5.3.0_4/include/sdformat-5.3 -isystem /usr/local/include/ignition/math3 -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE/Terrain -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE/Paging -isystem /usr/local/Cellar/ignition-transport3/3.1.0_2/include/ignition/transport3 -isystem /usr/local/Cellar/ossp-uuid/1.6.2_2/include/ossp -isystem /usr/local/include/ignition/msgs0 -isystem /usr/local/include/opencv4 -fpic -O3 -DNDEBUG -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -fPIC -MD -MT OpticalFlow/CMakeFiles/OpticalFlow.dir/src/flow_opencv.cpp.o -MF OpticalFlow/CMakeFiles/OpticalFlow.dir/src/flow_opencv.cpp.o.d -o OpticalFlow/CMakeFiles/OpticalFlow.dir/src/flow_opencv.cpp.o -c /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/src/flow_opencv.cpp
In file included from /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/src/flow_opencv.cpp:41:
/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/include/flow_opencv.hpp:44:10: fatal error: 'cv.h' file not found
#include <cv.h>
         ^~~~~~
1 error generated.
[23/46] Linking CXX shared library libgazebo_vision_plugin.dylib
[24/46] Linking CXX shared library libgazebo_motor_model.dylib
[25/46] Building CXX object OpticalFlow/klt_feature_tracker/CMakeFiles/klt_feature_tracker.dir/src/trackFeatures.cpp.o
FAILED: OpticalFlow/klt_feature_tracker/CMakeFiles/klt_feature_tracker.dir/src/trackFeatures.cpp.o
/Library/Developer/CommandLineTools/usr/bin/c++  -DLIBBULLET_VERSION=2.88 -DLIBBULLET_VERSION_GT_282 -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/external/klt_feature_tracker/include -isystem /usr/local/Cellar/gazebo8/8.6.0_5/include -isystem /usr/local/Cellar/gazebo8/8.6.0_5/include/gazebo-8 -isystem /usr/local/Cellar/bullet/2.88/include/bullet -isystem /usr/local/Cellar/bullet/2.88/include -isystem /usr/local/include/simbody -isystem /usr/local/include -isystem /usr/local/Cellar/sdformat5/5.3.0_4/include/sdformat-5.3 -isystem /usr/local/include/ignition/math3 -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE/Terrain -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE/Paging -isystem /usr/local/Cellar/ignition-transport3/3.1.0_2/include/ignition/transport3 -isystem /usr/local/Cellar/ossp-uuid/1.6.2_2/include/ossp -isystem /usr/local/include/ignition/msgs0 -isystem /usr/local/include/opencv4 -fpic -O3 -DNDEBUG -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -MD -MT OpticalFlow/klt_feature_tracker/CMakeFiles/klt_feature_tracker.dir/src/trackFeatures.cpp.o -MF OpticalFlow/klt_feature_tracker/CMakeFiles/klt_feature_tracker.dir/src/trackFeatures.cpp.o.d -o OpticalFlow/klt_feature_tracker/CMakeFiles/klt_feature_tracker.dir/src/trackFeatures.cpp.o -c /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/external/klt_feature_tracker/src/trackFeatures.cpp
In file included from /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/external/klt_feature_tracker/src/trackFeatures.cpp:40:
In file included from /usr/local/include/opencv4/opencv2/core/core.hpp:48:
/usr/local/include/opencv4/opencv2/core/matx.hpp:203:28: note: candidate constructor not viable: no known conversion from 'const Matx<[2 * ...], 4>' to 'const Matx<[2 * ...], 1 aka 1>' for 1st argument
    template<typename _T2> Matx(const Matx<_Tp, m, n>& a, _T2 alpha, Matx_ScaleOp);
                           ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:122:5: note: candidate constructor not viable: no known conversion from 'const Matx<double, 4, 4>' to 'double' for 1st argument
    Matx(_Tp v0, _Tp v1, _Tp v2); //!< 1x3 or 3x1 matrix
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:201:5: note: candidate constructor not viable: no known conversion from 'const Matx<[2 * ...], 4>' to 'const Matx<[2 * ...], 1 aka 1>' for 1st argument
    Matx(const Matx<_Tp, m, n>& a, const Matx<_Tp, m, n>& b, Matx_AddOp);
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:202:5: note: candidate constructor not viable: no known conversion from 'const Matx<[2 * ...], 4>' to 'const Matx<[2 * ...], 1 aka 1>' for 1st argument
    Matx(const Matx<_Tp, m, n>& a, const Matx<_Tp, m, n>& b, Matx_SubOp);
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:204:5: note: candidate constructor not viable: no known conversion from 'const Matx<[2 * ...], 4>' to 'const Matx<[2 * ...], 1 aka 1>' for 1st argument
    Matx(const Matx<_Tp, m, n>& a, const Matx<_Tp, m, n>& b, Matx_MulOp);
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:205:5: note: candidate constructor not viable: no known conversion from 'const Matx<[2 * ...], 4>' to 'const Matx<[2 * ...], 1 aka 1>' for 1st argument
    Matx(const Matx<_Tp, m, n>& a, const Matx<_Tp, m, n>& b, Matx_DivOp);
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:206:21: note: candidate template ignored: could not match 'Matx' against 'Scalar_'
    template<int l> Matx(const Matx<_Tp, m, l>& a, const Matx<_Tp, l, n>& b, Matx_MatMulOp);
                    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:121:5: note: candidate constructor not viable: requires 2 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1); //!< 1x2 or 2x1 matrix
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:207:5: note: candidate constructor not viable: requires 2 arguments, but 3 were provided
    Matx(const Matx<_Tp, n, m>& a, Matx_TOp);
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:123:5: note: candidate constructor not viable: requires 4 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1, _Tp v2, _Tp v3); //!< 1x4, 2x2 or 4x1 matrix
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:120:14: note: candidate constructor not viable: requires single argument 'v0', but 3 arguments were provided
    explicit Matx(_Tp v0); //!< 1x1 matrix
             ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:141:14: note: candidate constructor not viable: requires single argument 'vals', but 3 arguments were provided
    explicit Matx(const _Tp* vals); //!< initialize from a plain array
             ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:99:44: note: candidate constructor (the implicit copy constructor) not viable: requires 1 argument, but 3 were provided
template<typename _Tp, int m, int n> class Matx
                                           ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:124:5: note: candidate constructor not viable: requires 5 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4); //!< 1x5 or 5x1 matrix
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:118:5: note: candidate constructor not viable: requires 0 arguments, but 3 were provided
    Matx();
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:125:5: note: candidate constructor not viable: requires 6 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4, _Tp v5); //!< 1x6, 2x3, 3x2 or 6x1 matrix
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:126:5: note: candidate constructor not viable: requires 7 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4, _Tp v5, _Tp v6); //!< 1x7 or 7x1 matrix
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:127:5: note: candidate constructor not viable: requires 8 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4, _Tp v5, _Tp v6, _Tp v7); //!< 1x8, 2x4, 4x2 or 8x1 matrix
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:128:5: note: candidate constructor not viable: requires 9 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4, _Tp v5, _Tp v6, _Tp v7, _Tp v8); //!< 1x9, 3x3 or 9x1 matrix
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:129:5: note: candidate constructor not viable: requires 10 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1, _Tp v2, _Tp v3, _Tp v4, _Tp v5, _Tp v6, _Tp v7, _Tp v8, _Tp v9); //!< 1x10, 2x5 or 5x2 or 10x1 matrix
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:130:5: note: candidate constructor not viable: requires 12 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1, _Tp v2, _Tp v3,
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:133:5: note: candidate constructor not viable: requires 14 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1, _Tp v2, _Tp v3,
    ^
/usr/local/include/opencv4/opencv2/core/matx.hpp:137:5: note: candidate constructor not viable: requires 16 arguments, but 3 were provided
    Matx(_Tp v0, _Tp v1, _Tp v2, _Tp v3,
    ^
In file included from /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/external/klt_feature_tracker/src/trackFeatures.cpp:40:
In file included from /usr/local/include/opencv4/opencv2/core/core.hpp:48:
In file included from /usr/local/include/opencv4/opencv2/core.hpp:59:
/usr/local/include/opencv4/opencv2/core/mat.hpp:1007:29: error: no template named 'initializer_list' in namespace 'std'
    explicit Mat(const std::initializer_list<_Tp> list);
                       ~~~~~^
/usr/local/include/opencv4/opencv2/core/mat.hpp:1011:52: error: no template named 'initializer_list' in namespace 'std'
    template<typename _Tp> explicit Mat(const std::initializer_list<int> sizes, const std::initializer_list<_Tp> list);
                                              ~~~~~^
/usr/local/include/opencv4/opencv2/core/mat.hpp:1011:92: error: no template named 'initializer_list' in namespace 'std'
    template<typename _Tp> explicit Mat(const std::initializer_list<int> sizes, const std::initializer_list<_Tp> list);
                                                                                      ~~~~~^
/usr/local/include/opencv4/opencv2/core/mat.hpp:2222:15: error: no template named 'initializer_list' in namespace 'std'
    Mat_(std::initializer_list<_Tp> values);
         ~~~~~^
fatal error: too many errors emitted, stopping now [-ferror-limit=]
20 errors generated.
[26/46] Building CXX object CMakeFiles/gazebo_irlock_plugin.dir/src/gazebo_irlock_plugin.cpp.o
FAILED: CMakeFiles/gazebo_irlock_plugin.dir/src/gazebo_irlock_plugin.cpp.o
/Library/Developer/CommandLineTools/usr/bin/c++  -DLIBBULLET_VERSION=2.88 -DLIBBULLET_VERSION_GT_282 -Dgazebo_irlock_plugin_EXPORTS -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/include -I. -I/usr/local/include/eigen3 -I/usr/local/include/eigen3/eigen3 -I/usr/local/Cellar/gazebo8/8.6.0_5/include/gazebo-8/gazebo/msgs -I/Users/dlw/Workspace/PX4/Firmware/mavlink/include -I/usr/local/include/Paging -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/include -isystem /usr/local/Cellar/gazebo8/8.6.0_5/include -isystem /usr/local/Cellar/gazebo8/8.6.0_5/include/gazebo-8 -isystem /usr/local/Cellar/bullet/2.88/include/bullet -isystem /usr/local/Cellar/bullet/2.88/include -isystem /usr/local/include/simbody -isystem /usr/local/include -isystem /usr/local/Cellar/sdformat5/5.3.0_4/include/sdformat-5.3 -isystem /usr/local/include/ignition/math3 -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE/Terrain -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE/Paging -isystem /usr/local/Cellar/ignition-transport3/3.1.0_2/include/ignition/transport3 -isystem /usr/local/Cellar/ossp-uuid/1.6.2_2/include/ossp -isystem /usr/local/include/ignition/msgs0 -isystem /usr/local/include/opencv4 -std=c++17 -std=c++11 -stdlib=libc++ -Wno-deprecated-declarations -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -fPIC   -F/Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX10.14.sdk/System/Library/Frameworks  -std=c++11 -MD -MT CMakeFiles/gazebo_irlock_plugin.dir/src/gazebo_irlock_plugin.cpp.o -MF CMakeFiles/gazebo_irlock_plugin.dir/src/gazebo_irlock_plugin.cpp.o.d -o CMakeFiles/gazebo_irlock_plugin.dir/src/gazebo_irlock_plugin.cpp.o -c /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/src/gazebo_irlock_plugin.cpp
/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/src/gazebo_irlock_plugin.cpp:26:10: fatal error: 'highgui.h' file not found
#include <highgui.h>
         ^~~~~~~~~~~
1 error generated.
[27/46] Building CXX object CMakeFiles/gazebo_sonar_plugin.dir/src/gazebo_sonar_plugin.cpp.o
[28/46] Building CXX object CMakeFiles/gazebo_imu_plugin.dir/src/gazebo_imu_plugin.cpp.o
In file included from /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/src/gazebo_imu_plugin.cpp:21:
In file included from /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/include/gazebo_imu_plugin.h:33:
/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/include/common.h:68:10: warning: expression result unused [-Wunused-value]
    for( e_model; e_model; e_model=e_model->NextSiblingElement("model") )
         ^~~~~~~
1 warning generated.
[29/46] Building CXX object CMakeFiles/gazebo_opticalflow_plugin.dir/src/gazebo_opticalflow_plugin.cpp.o
FAILED: CMakeFiles/gazebo_opticalflow_plugin.dir/src/gazebo_opticalflow_plugin.cpp.o
/Library/Developer/CommandLineTools/usr/bin/c++  -DLIBBULLET_VERSION=2.88 -DLIBBULLET_VERSION_GT_282 -Dgazebo_opticalflow_plugin_EXPORTS -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/include -I. -I/usr/local/include/eigen3 -I/usr/local/include/eigen3/eigen3 -I/usr/local/Cellar/gazebo8/8.6.0_5/include/gazebo-8/gazebo/msgs -I/Users/dlw/Workspace/PX4/Firmware/mavlink/include -I/usr/local/include/Paging -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/include -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/external/klt_feature_tracker/include -isystem /usr/local/Cellar/gazebo8/8.6.0_5/include -isystem /usr/local/Cellar/gazebo8/8.6.0_5/include/gazebo-8 -isystem /usr/local/Cellar/bullet/2.88/include/bullet -isystem /usr/local/Cellar/bullet/2.88/include -isystem /usr/local/include/simbody -isystem /usr/local/include -isystem /usr/local/Cellar/sdformat5/5.3.0_4/include/sdformat-5.3 -isystem /usr/local/include/ignition/math3 -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE/Terrain -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE/Paging -isystem /usr/local/Cellar/ignition-transport3/3.1.0_2/include/ignition/transport3 -isystem /usr/local/Cellar/ossp-uuid/1.6.2_2/include/ossp -isystem /usr/local/include/ignition/msgs0 -isystem /usr/local/include/opencv4 -std=c++17 -std=c++11 -stdlib=libc++ -Wno-deprecated-declarations -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -fPIC   -F/Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX10.14.sdk/System/Library/Frameworks  -std=c++11 -MD -MT CMakeFiles/gazebo_opticalflow_plugin.dir/src/gazebo_opticalflow_plugin.cpp.o -MF CMakeFiles/gazebo_opticalflow_plugin.dir/src/gazebo_opticalflow_plugin.cpp.o.d -o CMakeFiles/gazebo_opticalflow_plugin.dir/src/gazebo_opticalflow_plugin.cpp.o -c /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/src/gazebo_opticalflow_plugin.cpp
In file included from /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/src/gazebo_opticalflow_plugin.cpp:24:
In file included from /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/include/gazebo_opticalflow_plugin.h:37:
/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/include/flow_opencv.hpp:44:10: fatal error: 'cv.h' file not found
#include <cv.h>
         ^~~~~~
1 error generated.
[30/46] Building CXX object CMakeFiles/gazebo_geotagged_images_plugin.dir/src/gazebo_geotagged_images_plugin.cpp.o
FAILED: CMakeFiles/gazebo_geotagged_images_plugin.dir/src/gazebo_geotagged_images_plugin.cpp.o
/Library/Developer/CommandLineTools/usr/bin/c++  -DLIBBULLET_VERSION=2.88 -DLIBBULLET_VERSION_GT_282 -Dgazebo_geotagged_images_plugin_EXPORTS -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/include -I. -I/usr/local/include/eigen3 -I/usr/local/include/eigen3/eigen3 -I/usr/local/Cellar/gazebo8/8.6.0_5/include/gazebo-8/gazebo/msgs -I/Users/dlw/Workspace/PX4/Firmware/mavlink/include -I/usr/local/include/Paging -I/Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/external/OpticalFlow/include -isystem /usr/local/Cellar/gazebo8/8.6.0_5/include -isystem /usr/local/Cellar/gazebo8/8.6.0_5/include/gazebo-8 -isystem /usr/local/Cellar/bullet/2.88/include/bullet -isystem /usr/local/Cellar/bullet/2.88/include -isystem /usr/local/include/simbody -isystem /usr/local/include -isystem /usr/local/Cellar/sdformat5/5.3.0_4/include/sdformat-5.3 -isystem /usr/local/include/ignition/math3 -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE/Terrain -isystem /usr/local/Cellar/ogre1.9/1.9-20160714-108ab0bcc69603dba32c0ffd4bbbc39051f421c9_7/include/OGRE/Paging -isystem /usr/local/Cellar/ignition-transport3/3.1.0_2/include/ignition/transport3 -isystem /usr/local/Cellar/ossp-uuid/1.6.2_2/include/ossp -isystem /usr/local/include/ignition/msgs0 -isystem /usr/local/include/opencv4 -std=c++17 -std=c++11 -stdlib=libc++ -Wno-deprecated-declarations -isysroot /Library/Developer/CommandLineTools/SDKs/MacOSX10.14.sdk -fPIC   -F/Applications/Xcode.app/Contents/Developer/Platforms/MacOSX.platform/Developer/SDKs/MacOSX10.14.sdk/System/Library/Frameworks  -std=c++11 -MD -MT CMakeFiles/gazebo_geotagged_images_plugin.dir/src/gazebo_geotagged_images_plugin.cpp.o -MF CMakeFiles/gazebo_geotagged_images_plugin.dir/src/gazebo_geotagged_images_plugin.cpp.o.d -o CMakeFiles/gazebo_geotagged_images_plugin.dir/src/gazebo_geotagged_images_plugin.cpp.o -c /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/src/gazebo_geotagged_images_plugin.cpp
In file included from /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/src/gazebo_geotagged_images_plugin.cpp:18:
In file included from /Users/dlw/Workspace/PX4/Firmware/Tools/sitl_gazebo/include/gazebo_geotagged_images_plugin.h:20:
In file included from /Users/dlw/Workspace/PX4/Firmware/mavlink/include/mavlink/v2.0/common/mavlink.h:32:
In file included from /Users/dlw/Workspace/PX4/Firmware/mavlink/include/mavlink/v2.0/common/common.h:30:
In file included from /Users/dlw/Workspace/PX4/Firmware/mavlink/include/mavlink/v2.0/common/../protocol.h:83:
/Users/dlw/Workspace/PX4/Firmware/mavlink/include/mavlink/v2.0/common/../mavlink_helpers.h:248:25: warning: taking address of packed member 'checksum' of class or structure '__mavlink_message' may result in an unaligned pointer value [-Waddress-of-packed-member]
        crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);
                               ^~~~~~~~~~~~~

ninja: build stopped: subcommand failed.
ninja: build stopped: subcommand failed.
make: *** [posix_sitl_default] Error 1

This was fixed here: https://github.com/PX4/sitl_gazebo/pull/252

You can either switch to master instead of stable or you have to manually cherry-pick the commits of this pull request for your sitl_gazebo submodule.

1 Like