-
Notifications
You must be signed in to change notification settings - Fork 104
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
[Zephyr] add zephyr plane model and demo world (#1)
Add an ArduPilot enabled Zephyr delta wing adpated from the model provided by OpenRobotics. The model is configured to work with ignition-gazebo. Changes include: - Rename the model to avoid conflict - Update the location of the wing mesh texture in the collada file - Disable the GPS sensor - Use the ignition-gazebo version of the lift-drag plugin - Provide a new runway / ground plane model for demonstration (contains assets from ambientCG.com, licensed under CC0 1.0 Universal: textures https://ambientcg.com/view?id=Grass004) - Update the iris_arducopter_runway world to use the new model - Clean up CMakeLists.txt to use ignition conventions - Only require ignition-gazebo package as other dependencies are pulled in recursively. - This version of the mode will fly with ArduPilot plane4.1 - Add imu link and set pose: <pose>0 0 0 3.141593 0 -1.5707963</pose>. This is to adjust for the Zephyr model having a non-standard orientation (x : -R, y : -F, z : -D) - Add joint-force system plugins - Add ArduPilot plugin and configure: - Gazebo body frame to ArudPilot FRD has an extra rotation about z to correct for the non-standard wing orientation. - Gazebo world to NED is the usual rotation - The elevon mappings are different from the model in SwiftGust's repo. The elevon channels are swapped and no servo reverse is required. - Upstream: gazebo-zephyr.parm needs to have SERVO1_REVERSED = 0 SERVO2_REVERSED = 0 - Orient the model for vertical takeoff - Update the default transform for rotating from the Gazebo world frame to NED. Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
- Loading branch information
1 parent
2b89c78
commit a4be78d
Showing
23 changed files
with
1,735 additions
and
307 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,205 +1,110 @@ | ||
cmake_minimum_required(VERSION 2.8 FATAL_ERROR) | ||
|
||
cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) | ||
|
||
#============================================================================ | ||
# Initialize the project | ||
#============================================================================ | ||
project(ardupilot_sitl_gazebo) | ||
|
||
#------------------------------------------------------------------------ | ||
# Compile as C++14 | ||
|
||
####################### | ||
## Find Dependencies ## | ||
####################### | ||
set(CMAKE_CXX_STANDARD 14) | ||
set(CMAKE_CXX_STANDARD_REQUIRED ON) | ||
|
||
#============================================================================ | ||
# Find ignition-cmake | ||
#============================================================================ | ||
find_package(ignition-cmake2 2.8.0 REQUIRED) | ||
set(IGN_CMAKE_VER ${ignition-cmake2_VERSION_MAJOR}) | ||
|
||
ign_find_package(sdformat11 REQUIRED VERSION 11.2.1) | ||
set(SDF_VER ${sdformat11_VERSION_MAJOR}) | ||
|
||
ign_find_package(ignition-plugin1 REQUIRED) | ||
set(IGN_PLUGIN_VER ${ignition-plugin1_VERSION_MAJOR}) | ||
|
||
ign_find_package(ignition-msgs7 REQUIRED VERSION 7.1) | ||
set(IGN_MSGS_VER ${ignition-msgs7_VERSION_MAJOR}) | ||
|
||
ign_find_package(ignition-common4 REQUIRED COMPONENTS all) | ||
set(IGN_COMMON_VER ${ignition-common4_VERSION_MAJOR}) | ||
|
||
ign_find_package(ignition-physics4 REQUIRED) | ||
set(IGN_PHYSICS_VER ${ignition-physics4_VERSION_MAJOR}) | ||
#============================================================================ | ||
# Search for project-specific dependencies | ||
#============================================================================ | ||
|
||
ign_find_package(ignition-sensors5 REQUIRED) | ||
set(IGN_SENSORS_VER ${ignition-sensors5_VERSION_MAJOR}) | ||
# ign_find_package(sdformat11 REQUIRED VERSION 11.2.2) | ||
# set(SDF_VER ${sdformat11_VERSION_MAJOR}) | ||
|
||
ign_find_package(ignition-math6 REQUIRED VERSION 6.8) | ||
set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR}) | ||
#-------------------------------------- | ||
# Find ignition-common | ||
# ign_find_package(ignition-common4 REQUIRED COMPONENTS all) | ||
# set(IGN_COMMON_VER ${ignition-common4_VERSION_MAJOR}) | ||
|
||
#-------------------------------------- | ||
# Find ignition-gazebo | ||
ign_find_package(ignition-gazebo5 REQUIRED) | ||
set(IGN_GAZEBO_VER ${ignition-gazebo5_VERSION_MAJOR}) | ||
|
||
# RapidJSON is a header only library | ||
#-------------------------------------- | ||
# Find ignition-math | ||
# ign_find_package(ignition-math6 REQUIRED VERSION 6.8) | ||
# set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR}) | ||
|
||
#-------------------------------------- | ||
# Find ignition-msgs | ||
# ign_find_package(ignition-msgs7 REQUIRED VERSION 7.1) | ||
# set(IGN_MSGS_VER ${ignition-msgs7_VERSION_MAJOR}) | ||
|
||
#-------------------------------------- | ||
# Find ignition-physics | ||
# ign_find_package(ignition-physics4 REQUIRED) | ||
# set(IGN_PHYSICS_VER ${ignition-physics4_VERSION_MAJOR}) | ||
|
||
#-------------------------------------- | ||
# Find ignition-plugin | ||
# ign_find_package(ignition-plugin1 REQUIRED) | ||
# set(IGN_PLUGIN_VER ${ignition-plugin1_VERSION_MAJOR}) | ||
|
||
#-------------------------------------- | ||
# Find ignition-sensors | ||
# ign_find_package(ignition-sensors5 REQUIRED) | ||
# set(IGN_SENSORS_VER ${ignition-sensors5_VERSION_MAJOR}) | ||
|
||
#-------------------------------------- | ||
# Find RapidJSON | ||
find_package(RapidJSON REQUIRED) | ||
|
||
###### COMPILE RULES ###### | ||
include(CheckCXXCompilerFlag) | ||
|
||
macro(filter_valid_compiler_flags) | ||
foreach(flag ${ARGN}) | ||
CHECK_CXX_COMPILER_FLAG(${flag} R${flag}) | ||
if(${R${flag}}) | ||
set(VALID_CXX_FLAGS "${VALID_CXX_FLAGS} ${flag}") | ||
endif() | ||
endforeach() | ||
endmacro() | ||
|
||
set(CMAKE_CXX_EXTENSIONS off) # see gazebo CMakeList | ||
|
||
if (NOT CMAKE_BUILD_TYPE) | ||
set (CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING | ||
"Choose the type of build, options are: Debug Release RelWithDebInfo Profile Check" FORCE) | ||
endif (NOT CMAKE_BUILD_TYPE) | ||
|
||
# Build type link flags | ||
set (CMAKE_LINK_FLAGS_RELEASE " " CACHE INTERNAL "Link flags for release" FORCE) | ||
set (CMAKE_LINK_FLAGS_RELWITHDEBINFO " " CACHE INTERNAL "Link flags for release with debug support" FORCE) | ||
set (CMAKE_LINK_FLAGS_DEBUG " " CACHE INTERNAL "Link flags for debug" FORCE) | ||
set (CMAKE_LINK_FLAGS_PROFILE " -pg" CACHE INTERNAL "Link flags for profile" FORCE) | ||
set (CMAKE_LINK_FLAGS_COVERAGE " --coverage" CACHE INTERNAL "Link flags for static code coverage" FORCE) | ||
|
||
set (CMAKE_C_FLAGS_RELEASE "") | ||
if (NOT "${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang" AND NOT MSVC) | ||
# -s doesn't work with clang or Visual Studio, see alternative in link below: | ||
# http://stackoverflow.com/questions/6085491/gcc-vs-clang-symbol-strippingu | ||
set (CMAKE_C_FLAGS_RELEASE "-s") | ||
endif() | ||
|
||
if (NOT MSVC) | ||
set (CMAKE_C_FLAGS_RELEASE " ${CMAKE_C_FLAGS_RELEASE} -O3 -DNDEBUG ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for release" FORCE) | ||
set (CMAKE_CXX_FLAGS_RELEASE ${CMAKE_C_FLAGS_RELEASE}) | ||
|
||
set (CMAKE_C_FLAGS_RELWITHDEBINFO " -g -O2 ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for release with debug support" FORCE) | ||
set (CMAKE_CXX_FLAGS_RELWITHDEBINFO ${CMAKE_C_FLAGS_RELWITHDEBINFO}) | ||
|
||
set (CMAKE_C_FLAGS_DEBUG " -ggdb3 ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for debug" FORCE) | ||
set (CMAKE_CXX_FLAGS_DEBUG ${CMAKE_C_FLAGS_DEBUG}) | ||
|
||
set (CMAKE_C_FLAGS_PROFILE " -fno-omit-frame-pointer -g -pg ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for profile" FORCE) | ||
set (CMAKE_CXX_FLAGS_PROFILE ${CMAKE_C_FLAGS_PROFILE}) | ||
|
||
set (CMAKE_C_FLAGS_COVERAGE " -g -O0 -Wformat=2 --coverage -fno-inline ${CMAKE_C_FLAGS_ALL}" CACHE INTERNAL "C Flags for static code coverage" FORCE) | ||
set (CMAKE_CXX_FLAGS_COVERAGE "${CMAKE_C_FLAGS_COVERAGE}") | ||
if (NOT "${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") | ||
# -fno-default-inline -fno-implicit-inline-templates are unimplemented, cause errors in clang | ||
# -fno-elide-constructors can cause seg-faults in clang 3.4 and earlier | ||
# http://llvm.org/bugs/show_bug.cgi?id=12208 | ||
set (CMAKE_CXX_FLAGS_COVERAGE "${CMAKE_CXX_FLAGS_COVERAGE} -fno-default-inline -fno-implicit-inline-templates -fno-elide-constructors") | ||
endif() | ||
endif() | ||
|
||
##################################### | ||
# Set all the global build flags | ||
set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") | ||
set (CMAKE_EXE_LINKER_FLAGS "${CMAKE_LINK_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") | ||
set (CMAKE_SHARED_LINKER_FLAGS "${CMAKE_LINK_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") | ||
set (CMAKE_MODULE_LINKER_FLAGS "${CMAKE_LINK_FLAGS_${CMAKE_BUILD_TYPE_UPPERCASE}}") | ||
|
||
# Compiler-specific C++11 activation. | ||
if ("${CMAKE_CXX_COMPILER_ID}" MATCHES "GNU") | ||
execute_process( | ||
COMMAND ${CMAKE_CXX_COMPILER} -dumpversion OUTPUT_VARIABLE GCC_VERSION) | ||
if (NOT (GCC_VERSION VERSION_GREATER 4.7)) | ||
message(FATAL_ERROR "${PROJECT_NAME} requires g++ 4.8 or greater.") | ||
endif () | ||
elseif ("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang") | ||
execute_process( | ||
COMMAND ${CMAKE_CXX_COMPILER} -dumpversion OUTPUT_VARIABLE CLANG_VERSION) | ||
if (NOT (CLANG_VERSION VERSION_GREATER 3.2)) | ||
message(FATAL_ERROR "${PROJECT_NAME} requires clang 3.3 or greater.") | ||
endif () | ||
|
||
if ("${CMAKE_SYSTEM_NAME}" MATCHES "Darwin") | ||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -stdlib=libc++") | ||
endif () | ||
elseif ("${CMAKE_CXX_COMPILER_ID}" STREQUAL "MSVC") | ||
if (MSVC_VERSION LESS 1800) | ||
message(FATAL_ERROR "${PROJECT_NAME} requires VS 2013 or greater.") | ||
endif () | ||
else () | ||
message(FATAL_ERROR "Your C++ compiler does not support C++11.") | ||
endif () | ||
|
||
set(WARN_LEVEL "-Wall") | ||
filter_valid_compiler_flags(${WARN_LEVEL} | ||
-Wextra -Wno-long-long -Wno-unused-value -Wfloat-equal -Wshadow | ||
-Wswitch-default -Wmissing-include-dirs -pedantic) | ||
if (UNIX AND NOT APPLE) | ||
filter_valid_compiler_flags(-fvisibility=hidden -fvisibility-inlines-hidden) | ||
endif() | ||
|
||
set(UNFILTERED_FLAGS "-std=c++14") | ||
set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${VALID_CXX_FLAGS} ${UNFILTERED_FLAGS}") | ||
|
||
########### | ||
## Build ## | ||
########### | ||
|
||
include_directories( | ||
${PROJECT_SOURCE_DIR} | ||
include | ||
${SDFORMAT-INCLUDE_DIRS} | ||
${IGNITION-COMMON_INCLUDE_DIRS} | ||
${IGNITION-GAZEBO_INCLUDE_DIRS} | ||
${IGNITION-MATH_INCLUDE_DIRS} | ||
${IGNITION-MSGS_INCLUDE_DIRS} | ||
${IGNITION-PHYSICS_INCLUDE_DIRS} | ||
${IGNITION-SENSORS_INCLUDE_DIRS} | ||
${IGNITION-TRANSPORT_INCLUDE_DIRS} | ||
${RAPIDJSON_INCLUDE_DIRS} | ||
) | ||
|
||
link_libraries( | ||
${SDFORMAT-LIBRARIES} | ||
${IGNITION-COMMON_LIBRARIES} | ||
${IGNITION-GAZEBO_LIBRARIES} | ||
${IGNITION-MATH_LIBRARIES} | ||
${IGNITION-MSGS_LIBRARIES} | ||
${IGNITION-PHYSICS_LIBRARIES} | ||
${IGNITION-SENSORS_LIBRARIES} | ||
${IGNITION-TRANSPORT_LIBRARIES} | ||
) | ||
|
||
set (plugins_single_header | ||
ArduPilotPlugin | ||
ArduCopterIRLockPlugin | ||
GimbalSmall2dPlugin | ||
) | ||
|
||
# add_library(ArduCopterIRLockPlugin SHARED src/ArduCopterIRLockPlugin.cc) | ||
# target_link_libraries(ArduCopterIRLockPlugin) | ||
#====================================== | ||
# Find Qt | ||
# find_package(Qt5 REQUIRED COMPONENTS | ||
# Core | ||
# Gui | ||
# Qml | ||
# Quick | ||
# QuickControls2 | ||
# Widgets | ||
# ) | ||
|
||
add_library(ArduPilotPlugin | ||
SHARED | ||
src/ArduPilotPlugin.cc | ||
src/Socket.cpp | ||
) | ||
target_link_libraries(ArduPilotPlugin) | ||
|
||
# if("${GAZEBO_VERSION}" VERSION_LESS "8.0") | ||
# add_library(GimbalSmall2dPlugin SHARED src/GimbalSmall2dPlugin.cc) | ||
# target_link_libraries(GimbalSmall2dPlugin ${GAZEBO_LIBRARIES}) | ||
# install(TARGETS GimbalSmall2dPlugin DESTINATION ${GAZEBO_PLUGIN_PATH}) | ||
# endif() | ||
|
||
# install(TARGETS ArduCopterIRLockPlugin DESTINATION ${GAZEBO_PLUGIN_PATH}) | ||
# install(TARGETS ArduPilotPlugin DESTINATION ${GAZEBO_PLUGIN_PATH}) | ||
|
||
# install(DIRECTORY models DESTINATION ${GAZEBO_MODEL_PATH}/..) | ||
# install(DIRECTORY worlds DESTINATION ${GAZEBO_MODEL_PATH}/..) | ||
|
||
# uninstall target | ||
# if(NOT TARGET uninstall) | ||
# configure_file( | ||
# "${CMAKE_CURRENT_SOURCE_DIR}/cmake/cmake_uninstall.cmake.in" | ||
# "${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake" | ||
# IMMEDIATE @ONLY) | ||
|
||
# add_custom_target(uninstall | ||
# COMMAND ${CMAKE_COMMAND} -P ${CMAKE_CURRENT_BINARY_DIR}/cmake_uninstall.cmake) | ||
# endif() | ||
|
||
target_include_directories(ArduPilotPlugin PUBLIC | ||
# ${PROJECT_SOURCE_DIR} | ||
include | ||
# ${SDFORMAT-INCLUDE_DIRS} | ||
# ${IGNITION-COMMON_INCLUDE_DIRS} | ||
${IGNITION-GAZEBO_INCLUDE_DIRS} | ||
# ${IGNITION-MATH_INCLUDE_DIRS} | ||
# ${IGNITION-MSGS_INCLUDE_DIRS} | ||
# ${IGNITION-PHYSICS_INCLUDE_DIRS} | ||
# ${IGNITION-SENSORS_INCLUDE_DIRS} | ||
# ${IGNITION-TRANSPORT_INCLUDE_DIRS} | ||
# ${RAPIDJSON_INCLUDE_DIRS} | ||
) | ||
|
||
target_link_libraries(ArduPilotPlugin PUBLIC | ||
# ${SDFORMAT-LIBRARIES} | ||
# ${IGNITION-COMMON_LIBRARIES} | ||
${IGNITION-GAZEBO_LIBRARIES} | ||
# ${IGNITION-MATH_LIBRARIES} | ||
# ${IGNITION-MSGS_LIBRARIES} | ||
# ${IGNITION-PHYSICS_LIBRARIES} | ||
# ${IGNITION-SENSORS_LIBRARIES} | ||
# ${IGNITION-TRANSPORT_LIBRARIES} | ||
# Qt5::Core | ||
# Qt5::Gui | ||
# Qt5::Qml | ||
# Qt5::Quick | ||
) |
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Oops, something went wrong.