Compare commits

...

19 Commits

Author SHA1 Message Date
scorpio1 42d2b480dd switched to absolute paths 2023-06-29 11:16:41 -07:00
scorpio1 8c1a07a937 Update 'px4_setup/px4setup.sh' 2023-06-28 10:39:58 -07:00
scorpio1 1379b82794 Update 'px4_setup/px4setup.sh' 2023-06-28 10:18:22 -07:00
scorpio1 0445f906e8 Update 'px4_setup/px4setup.sh' 2023-06-28 09:47:40 -07:00
scorpio1 e7ef45ede3 Update 'px4_setup/px4setup.sh' 2023-06-28 09:21:00 -07:00
scorpio1 e3f03d59c6 Update 'px4_setup/px4setup.sh' 2023-06-28 08:58:43 -07:00
scorpio1 65cb6a6249 Update 'px4_setup/px4setup.sh' 2023-06-21 11:35:35 -07:00
scorpio1 4540aa8424 Update 'px4_setup/px4setup.sh' 2023-06-21 10:14:29 -07:00
scorpio1 a34c11fc24 Updated setup to change bash.rc file 2023-06-21 09:38:23 -07:00
scorpio1 427afafdbc Update 'px4_setup/px4setup.sh' 2023-06-14 11:17:08 -07:00
scorpio1 a61954f3d0 Update 'px4_setup/px4setup.sh' 2023-06-14 10:12:21 -07:00
scorpio1 18658eb4c1 Update 'px4_setup/px4setup.sh' 2023-06-14 09:46:08 -07:00
scorpio1 131fe1e552 Add 'px4_setup/px4_requirements.txt' 2023-06-14 08:59:02 -07:00
scorpio1 cbeb5c4ea6 Add 'px4_setup/px4setup.sh' 2023-06-14 08:46:13 -07:00
scorpio1 3140c26d5c Removed some extraneous links 2023-06-12 11:27:25 -07:00
scorpio1 be7a3341db added new cmake for version of px4 used in docker 2023-05-31 09:10:15 -07:00
scorpio1 f596964d2c Add 'px4_setup/airframe_changes' 2023-05-31 07:12:47 -07:00
scorpio1 a6b1d0a79a Update 'CMakeLists.txt' 2023-05-31 06:27:47 -07:00
scorpio1 7728fe07a3 Removed extra dependencies 2023-05-31 06:25:36 -07:00
6 changed files with 775 additions and 6 deletions

View File

@ -33,7 +33,6 @@ add_message_files(
add_service_files(
FILES
WaypointTrack.srv
BodyToWorld.srv
UseCtrl.srv
)
@ -87,11 +86,8 @@ target_link_libraries(pathFollow_node ${catkin_LIBRARIES})
add_dependencies(pathFollow_node ${${PROJECT_NAME}EXPORTEDTARGETS} ${catkin_EXPORTED_TARGETS})
#add_dependencies(pathFollow_node oscillation_ctrl_generate_messages_cpp)
add_executable(mocap_pathFollow_node src/mocap_path_follow.cpp)
target_link_libraries(mocap_pathFollow_node ${catkin_LIBRARIES})
add_dependencies(mocap_pathFollow_node ${${PROJECT_NAME}EXPORTEDTARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ library
# add_library(${PROJECT_NAME}

210
px4_setup/airframe_changes Normal file
View File

@ -0,0 +1,210 @@
set(SITL_WORKING_DIR ${PX4_BINARY_DIR}/tmp)
file(MAKE_DIRECTORY ${SITL_WORKING_DIR})
file(MAKE_DIRECTORY ${SITL_WORKING_DIR}/rootfs)
# add a symlink to the logs dir to make it easier to find them
add_custom_command(OUTPUT ${PX4_BINARY_DIR}/logs
COMMAND ${CMAKE_COMMAND} -E create_symlink ${SITL_WORKING_DIR}/rootfs/log logs
WORKING_DIRECTORY ${PX4_BINARY_DIR})
add_custom_target(logs_symlink DEPENDS ${PX4_BINARY_DIR}/logs)
add_dependencies(px4 logs_symlink)
add_custom_target(run_config
COMMAND Tools/sitl_run.sh
$<TARGET_FILE:px4>
${config_sitl_debugger}
${config_sitl_viewer}
${config_sitl_model}
${PX4_SOURCE_DIR}
${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4 logs_symlink
)
px4_add_git_submodule(TARGET git_gazebo PATH "${PX4_SOURCE_DIR}/Tools/sitl_gazebo")
px4_add_git_submodule(TARGET git_jmavsim PATH "${PX4_SOURCE_DIR}/Tools/jMAVSim")
px4_add_git_submodule(TARGET git_flightgear_bridge PATH "${PX4_SOURCE_DIR}/Tools/flightgear_bridge")
# Add support for external project building
include(ExternalProject)
# project to build sitl_gazebo if necessary
ExternalProject_Add(sitl_gazebo
SOURCE_DIR ${PX4_SOURCE_DIR}/Tools/sitl_gazebo
CMAKE_ARGS
-DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}
-DSEND_ODOMETRY_DATA=ON
BINARY_DIR ${PX4_BINARY_DIR}/build_gazebo
INSTALL_COMMAND ""
DEPENDS
git_gazebo
USES_TERMINAL_CONFIGURE true
USES_TERMINAL_BUILD true
EXCLUDE_FROM_ALL true
BUILD_ALWAYS 1
BUILD_COMMAND ${CMAKE_COMMAND} --build <BINARY_DIR> -- -j2
)
ExternalProject_Add(mavsdk_tests
SOURCE_DIR ${PX4_SOURCE_DIR}/test/mavsdk_tests
CMAKE_ARGS
-DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}
BINARY_DIR ${PX4_BINARY_DIR}/mavsdk_tests
INSTALL_COMMAND ""
USES_TERMINAL_CONFIGURE true
USES_TERMINAL_BUILD true
EXCLUDE_FROM_ALL true
BUILD_ALWAYS 1
)
ExternalProject_Add(flightgear_bridge
SOURCE_DIR ${PX4_SOURCE_DIR}/Tools/flightgear_bridge
CMAKE_ARGS
-DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}
BINARY_DIR ${PX4_BINARY_DIR}/build_flightgear_bridge
INSTALL_COMMAND ""
DEPENDS
git_flightgear_bridge
USES_TERMINAL_CONFIGURE true
USES_TERMINAL_BUILD true
EXCLUDE_FROM_ALL true
BUILD_ALWAYS 1
)
# create targets for each viewer/model/debugger combination
set(viewers none jmavsim gazebo)
set(debuggers none ide gdb lldb ddd valgrind callgrind)
set(models none shell
if750a iris iris_dual_gps iris_opt_flow iris_opt_flow_mockup iris_vision iris_rplidar iris_irlock iris_obs_avoid iris_rtps px4vision solo typhoon_h480
plane plane_cam plane_catapult plane_lidar
standard_vtol tailsitter tiltrotor
rover r1_rover boat cloudship spiri spiri_with_tether
uuv_hippocampus)
set(worlds none empty baylands ksql_airport mcmillan_airfield sonoma_raceway warehouse windy)
set(all_posix_vmd_make_targets)
foreach(viewer ${viewers})
foreach(debugger ${debuggers})
foreach(model ${models})
foreach(world ${worlds})
if (world STREQUAL "none")
if (debugger STREQUAL "none")
if (model STREQUAL "none")
set(_targ_name "${viewer}")
else()
set(_targ_name "${viewer}_${model}")
endif()
else()
if (model STREQUAL "none")
set(_targ_name "${viewer}___${debugger}")
else()
set(_targ_name "${viewer}_${model}_${debugger}")
endif()
endif()
add_custom_target(${_targ_name}
COMMAND ${PX4_SOURCE_DIR}/Tools/sitl_run.sh
$<TARGET_FILE:px4>
${debugger}
${viewer}
${model}
${world}
${PX4_SOURCE_DIR}
${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS
logs_symlink
)
list(APPEND all_posix_vmd_make_targets ${_targ_name})
if (viewer STREQUAL "gazebo")
add_dependencies(${_targ_name} px4 sitl_gazebo)
elseif(viewer STREQUAL "jmavsim")
add_dependencies(${_targ_name} px4 git_jmavsim)
endif()
else()
if (viewer STREQUAL "gazebo")
if (debugger STREQUAL "none")
if (model STREQUAL "none")
set(_targ_name "${viewer}___${world}")
else()
set(_targ_name "${viewer}_${model}__${world}")
endif()
else()
if (model STREQUAL "none")
set(_targ_name "${viewer}__${debugger}_${world}")
else()
set(_targ_name "${viewer}_${model}_${debugger}_${world}")
endif()
endif()
add_custom_target(${_targ_name}
COMMAND ${PX4_SOURCE_DIR}/Tools/sitl_run.sh
$<TARGET_FILE:px4>
${debugger}
${viewer}
${model}
${world}
${PX4_SOURCE_DIR}
${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS
logs_symlink
)
list(APPEND all_posix_vmd_make_targets ${_targ_name})
add_dependencies(${_targ_name} px4 sitl_gazebo)
endif()
endif()
endforeach()
endforeach()
endforeach()
endforeach()
#add flighgear targets
if( ENABLE_LOCKSTEP_SCHEDULER STREQUAL "no")
set(models
rascal
rascal-electric
tf-g1
tf-r1
)
set(all_posix_vmd_make_targets)
foreach(model ${models})
set(_targ_name "flightgear_${model}")
add_custom_target(${_targ_name}
COMMAND ${PX4_SOURCE_DIR}/Tools/sitl_run.sh
$<TARGET_FILE:px4>
none
flightgear
${model}
none
${PX4_SOURCE_DIR}
${PX4_BINARY_DIR}
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS
logs_symlink
)
add_dependencies(${_targ_name} px4 flightgear_bridge)
list(APPEND all_posix_vmd_make_targets ${_targ_name})
endforeach()
endif()
string(REPLACE ";" "," posix_vmd_make_target_list "${all_posix_vmd_make_targets}")
add_custom_target(list_vmd_make_targets
COMMAND sh -c "printf \"${posix_vmd_make_target_list}\\n\""
COMMENT "List of acceptable '${PX4_BOARD}' <viewer_model_debugger> targets:"
VERBATIM
)
# vscode launch.json
if(${PX4_BOARD_LABEL} MATCHES "replay")
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/Debug/launch_replay.json.in ${PX4_SOURCE_DIR}/.vscode/launch.json COPYONLY)
else()
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/Debug/launch_sim.json.in ${PX4_SOURCE_DIR}/.vscode/launch.json COPYONLY)
endif()

529
px4_setup/firmwareCmake Normal file
View File

@ -0,0 +1,529 @@
cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
cmake_policy(SET CMP0042 NEW)
cmake_policy(SET CMP0048 NEW)
cmake_policy(SET CMP0054 NEW)
if (NOT CMAKE_INSTALL_PREFIX)
set(CMAKE_INSTALL_PREFIX "/usr" CACHE STRING "install prefix" FORCE)
endif()
message(STATUS "install-prefix: ${CMAKE_INSTALL_PREFIX}")
# CMake build type (Debug Release RelWithDebInfo MinSizeRel)
if(NOT CMAKE_BUILD_TYPE)
set(CMAKE_BUILD_TYPE "RelWithDebInfo")
set(CMAKE_BUILD_TYPE ${CMAKE_BUILD_TYPE} CACHE STRING "Build type" FORCE)
endif()
set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Coverage;AddressSanitizer;UndefinedBehaviorSanitizer")
message(STATUS "cmake build type: ${CMAKE_BUILD_TYPE}")
project(mavlink_sitl_gazebo VERSION 1.0.0)
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/cmake")
# Set c++11 or higher
include(EnableC++XX)
# Set c11
set(CMAKE_C_STANDARD 11)
set(CMAKE_C_STANDARD_REQUIRED ON)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
include(GNUInstallDirs)
#######################
## Find Dependencies ##
#######################
option(BUILD_GSTREAMER_PLUGIN "enable gstreamer plugin" ON)
option(BUILD_ROS_INTERFACE "Enable building ROS dependent plugins" OFF)
option(SEND_VISION_ESTIMATION_DATA "Send Mavlink VISION_POSITION_ESTIMATE msgs" OFF)
option(SEND_ODOMETRY_DATA "Send Mavlink ODOMETRY msgs" OFF)
## System dependencies are found with CMake's conventions
find_package(Boost 1.58 REQUIRED COMPONENTS system thread filesystem)
find_package(gazebo REQUIRED)
find_package(PkgConfig REQUIRED)
# Note: If using catkin, Python 2 is found since it points
# to the Python libs installed with the ROS distro
if (NOT CATKIN_DEVEL_PREFIX)
find_package(PythonInterp 3 REQUIRED)
else()
find_package(PythonInterp REQUIRED)
endif()
find_package(OpenCV REQUIRED)
find_package(TinyXML REQUIRED)
if (BUILD_GSTREAMER_PLUGIN)
set(GStreamer_FIND_VERSION "1.0")
find_package(GStreamer REQUIRED)
if (GSTREAMER_FOUND)
if("${GAZEBO_VERSION}" VERSION_LESS "8.0")
find_package (Qt4)
include (${QT_USE_FILE})
else()
# In order to find Qt5 in macOS, the Qt5 path needs to be added to the CMake prefix path.
if(APPLE)
execute_process(COMMAND brew --prefix qt5
ERROR_QUIET
OUTPUT_VARIABLE QT5_PREFIX_PATH
OUTPUT_STRIP_TRAILING_WHITESPACE
)
list(APPEND CMAKE_PREFIX_PATH "${QT5_PREFIX_PATH}/lib/cmake")
endif()
find_package(Qt5 COMPONENTS Core Widgets REQUIRED)
endif()
endif()
endif()
pkg_check_modules(OGRE OGRE)
if("${GAZEBO_VERSION}" VERSION_LESS "8.0")
include_directories(SYSTEM ${GAZEBO_INCLUDE_DIRS})
else()
include_directories(SYSTEM ${GAZEBO_INCLUDE_DIRS} ${Qt5Core_INCLUDE_DIRS})
endif()
link_directories(${GAZEBO_LIBRARY_DIRS})
add_subdirectory( external/OpticalFlow OpticalFlow )
set( OpticalFlow_LIBS "OpticalFlow" )
# for ROS subscribers and publishers
if (BUILD_ROS_INTERFACE)
find_package(geometry_msgs REQUIRED)
find_package(roscpp REQUIRED)
find_package(sensor_msgs REQUIRED)
endif()
# find MAVLink
find_package(MAVLink)
# see if catkin was invoked to build this
if (CATKIN_DEVEL_PREFIX)
message(STATUS "catkin ENABLED")
find_package(catkin REQUIRED)
if (catkin_FOUND)
catkin_package()
else()
message(FATAL_ERROR "catkin not found")
endif()
else()
message(STATUS "catkin DISABLED")
endif()
# XXX this approach is extremely error prone
# it would be preferable to either depend on the
# compiled headers from Gazebo directly
# or to have something entirely independent.
#
set(PROTOBUF_IMPORT_DIRS "")
foreach(ITR ${GAZEBO_INCLUDE_DIRS})
if(ITR MATCHES ".*gazebo-[0-9.]+$")
set(PROTOBUF_IMPORT_DIRS "${ITR}/gazebo/msgs/proto")
endif()
endforeach()
# PROTOBUF_IMPORT_DIRS has to be set before
# find_package is called
find_package(Protobuf REQUIRED)
pkg_check_modules(PROTOBUF protobuf)
if ("${PROTOBUF_VERSION}" VERSION_LESS "2.5.0")
message(FATAL_ERROR "protobuf version: ${PROTOBUF_VERSION} not compatible, must be >= 2.5.0")
endif()
if("${GAZEBO_VERSION}" VERSION_LESS "6.0")
message(FATAL_ERROR "You need at least Gazebo 6.0. Your version: ${GAZEBO_VERSION}")
else()
message(STATUS "Gazebo version: ${GAZEBO_VERSION}")
endif()
find_package(Eigen3 QUIET)
if(NOT EIGEN3_FOUND)
# Fallback to cmake_modules
find_package(Eigen QUIET)
if(NOT EIGEN_FOUND)
pkg_check_modules(EIGEN3 REQUIRED eigen3)
else()
set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS})
set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES})
endif()
else()
set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR})
endif()
###########
## Build ##
###########
add_compile_options(-Wno-deprecated-declarations -Wno-address-of-packed-member)
set(GAZEBO_MSG_INCLUDE_DIRS)
foreach(ITR ${GAZEBO_INCLUDE_DIRS})
if(ITR MATCHES ".*gazebo-[0-9.]+$")
set(GAZEBO_MSG_INCLUDE_DIRS "${ITR}/gazebo/msgs")
endif()
endforeach()
include_directories(
include
${Boost_INCLUDE_DIR}
${CMAKE_CURRENT_BINARY_DIR}
${EIGEN3_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}/eigen3 # Workaround for Eigen3
${GAZEBO_INCLUDE_DIRS}
${GAZEBO_MSG_INCLUDE_DIRS}
${MAVLINK_INCLUDE_DIRS}
${OGRE_INCLUDE_DIRS}
${OGRE_INCLUDE_DIRS}/Paging # Workaround for "fatal error: OgrePagedWorldSection.h: No such file or directory"
${OpenCV_INCLUDE_DIRS}
${OpticalFlow_INCLUDE_DIRS}
${TinyXML_INCLUDE_DIRS}
)
if (GSTREAMER_FOUND)
include_directories(
${GSTREAMER_INCLUDE_DIRS}
)
endif()
link_libraries(
${Boost_SYSTEM_LIBRARY_RELEASE}
${Boost_THREAD_LIBRARY_RELEASE}
${Boost_TIMER_LIBRARY_RELEASE}
${GAZEBO_LIBRARIES}
${OpenCV_LIBRARIES}
${PROTOBUF_LIBRARY}
)
if (GSTREAMER_FOUND)
link_libraries(
${GSTREAMER_LIBRARIES}
glib-2.0
gobject-2.0
)
endif()
link_directories(
${GAZEBO_LIBRARY_DIRS}
${CMAKE_CURRENT_BINARY_DIR}
${OGRE_LIBRARY_DIRS}
)
#--------------------------#
# Generation of SDF models #
#--------------------------#
set(enable_mavlink_interface "true")
set(enable_ground_truth "false")
set(enable_logging "false")
set(enable_camera "false")
set(enable_wind "false")
set(rotors_description_dir "${CMAKE_CURRENT_SOURCE_DIR}/models/rotors_description")
set(scripts_dir "${CMAKE_CURRENT_SOURCE_DIR}/scripts")
# set the vision estimation to be sent if set by the CMake option SEND_VISION_ESTIMATION_DATA
set(send_vision_estimation "false")
if (SEND_VISION_ESTIMATION_DATA)
set(send_vision_estimation "true")
endif()
# if SEND_ODOMETRY_DATA option is set, then full odometry data is sent instead of
# only the visual pose estimate
set(send_odometry "false")
if (SEND_ODOMETRY_DATA)
set(send_odometry "true")
set(send_vision_estimation "false")
endif()
add_custom_command(OUTPUT ${CMAKE_CURRENT_SOURCE_DIR}/models/iris/iris.sdf
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
COMMAND rm -f ${CMAKE_CURRENT_SOURCE_DIR}/models/iris/iris.sdf
COMMAND ${PYTHON_EXECUTABLE} ${scripts_dir}/xacro.py -o ${rotors_description_dir}/urdf/iris_base.urdf ${rotors_description_dir}/urdf/iris_base.xacro enable_mavlink_interface:=${enable_mavlink_interface} enable_ground_truth:=${enable_ground_truth} enable_wind:=${enable_wind} enable_logging:=${enable_logging} rotors_description_dir:=${rotors_description_dir} send_vision_estimation:=${send_vision_estimation} send_odometry:=${send_odometry}
COMMAND gz sdf -p ${rotors_description_dir}/urdf/iris_base.urdf >> ${CMAKE_CURRENT_SOURCE_DIR}/models/iris/iris.sdf
COMMAND rm -f ${rotors_description_dir}/urdf/iris_base.urdf
DEPENDS ${rotors_description_dir}/urdf/iris.xacro
DEPENDS ${rotors_description_dir}/urdf/iris_base.xacro
DEPENDS ${rotors_description_dir}/urdf/component_snippets.xacro
)
add_custom_target(sdf ALL DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/models/iris/iris.sdf)
#-----------#
# Functions #
#-----------#
function(glob_generate target file_glob)
file(GLOB_RECURSE glob_files RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} ${file_glob})
set(gen_files)
foreach(glob_file ${glob_files})
string(REGEX REPLACE "\\.[^.]*$" "" file_name ${glob_file})
string(REGEX MATCH "[^.]*$" file_ext ${glob_file})
get_filename_component(file_dir ${glob_file} DIRECTORY)
set(in_file ${CMAKE_CURRENT_SOURCE_DIR}/${glob_file})
file(MAKE_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/${file_dir})
set(out_file ${CMAKE_CURRENT_SOURCE_DIR}/${file_name})
string(REGEX REPLACE ".sdf" "-gen.sdf" out_file ${out_file})
if (${file_ext} STREQUAL "jinja")
if(GENERATE_ROS_MODELS)
add_custom_command(OUTPUT ${out_file}
COMMAND
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py ${in_file} ${CMAKE_CURRENT_SOURCE_DIR} --generate_ros_models true
DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py ${in_file}
VERBATIM
)
else()
add_custom_command(OUTPUT ${out_file}
COMMAND
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py ${in_file} ${CMAKE_CURRENT_SOURCE_DIR}
DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py ${in_file}
VERBATIM
COMMAND
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py models/spiri_with_tether/spiri_with_tether.sdf} ${CMAKE_CURRENT_SOURCE_DIR}
DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py models/spiri_with_tether/spiri_with_tether.sdf
VERBATIM
)
endif()
add_custom_command(OUTPUT ${out_file}
COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py
${in_file} ${CMAKE_CURRENT_SOURCE_DIR}
DEPENDS ${in_file}
VERBATIM
)
list(APPEND gen_files_${target} ${out_file})
endif()
endforeach()
add_custom_target(${target} ALL DEPENDS ${gen_files_${target}})
endfunction()
glob_generate(models_gen ${CMAKE_CURRENT_SOURCE_DIR}/models/*.jinja)
#--------------------#
# Message Generation #
#--------------------#
set(mav_msgs
msgs/CommandMotorSpeed.proto
msgs/MotorSpeed.proto
)
set(nav_msgs msgs/Odometry.proto)
set(physics_msgs msgs/Wind.proto)
set(std_msgs msgs/Int32.proto)
set(sensor_msgs
msgs/Airspeed.proto
msgs/Imu.proto
msgs/IRLock.proto
msgs/Float.proto
msgs/Groundtruth.proto
msgs/Range.proto
msgs/SITLGps.proto
msgs/OpticalFlow.proto
msgs/MagneticField.proto
msgs/Pressure.proto
)
PROTOBUF_GENERATE_CPP(MAV_PROTO_SRCS MAV_PROTO_HDRS ${mav_msgs})
PROTOBUF_GENERATE_CPP(NAV_PROTO_SRCS NAV_PROTO_HDRS ${nav_msgs})
PROTOBUF_GENERATE_CPP(PHY_PROTO_SRCS PHY_PROTO_HDRS ${physics_msgs})
PROTOBUF_GENERATE_CPP(STD_PROTO_SRCS STD_PROTO_HDRS ${std_msgs})
PROTOBUF_GENERATE_CPP(SEN_PROTO_SRCS SEN_PROTO_HDRS ${sensor_msgs})
add_library(mav_msgs SHARED ${MAV_PROTO_SRCS})
add_library(nav_msgs SHARED ${NAV_PROTO_SRCS})
add_library(physics_msgs SHARED ${PHY_PROTO_SRCS})
add_library(std_msgs SHARED ${STD_PROTO_SRCS})
add_library(sensor_msgs SHARED ${SEN_PROTO_SRCS})
#---------#
# Plugins #
#---------#
link_libraries(mav_msgs nav_msgs std_msgs sensor_msgs)
link_libraries(physics_msgs)
add_library(gazebo_airspeed_plugin SHARED src/gazebo_airspeed_plugin.cpp)
add_library(gazebo_geotagged_images_plugin SHARED src/gazebo_geotagged_images_plugin.cpp)
add_library(gazebo_gps_plugin SHARED src/gazebo_gps_plugin.cpp)
add_library(gazebo_groundtruth_plugin SHARED src/gazebo_groundtruth_plugin.cpp)
add_library(gazebo_irlock_plugin SHARED src/gazebo_irlock_plugin.cpp)
add_library(gazebo_lidar_plugin SHARED src/gazebo_lidar_plugin.cpp)
add_library(gazebo_opticalflow_mockup_plugin SHARED src/gazebo_opticalflow_mockup_plugin.cpp)
add_library(gazebo_opticalflow_plugin SHARED src/gazebo_opticalflow_plugin.cpp)
add_library(gazebo_sonar_plugin SHARED src/gazebo_sonar_plugin.cpp)
add_library(gazebo_uuv_plugin SHARED src/gazebo_uuv_plugin.cpp)
add_library(gazebo_vision_plugin SHARED src/gazebo_vision_plugin.cpp)
add_library(gazebo_controller_interface SHARED src/gazebo_controller_interface.cpp)
add_library(gazebo_gimbal_controller_plugin SHARED src/gazebo_gimbal_controller_plugin.cpp)
add_library(gazebo_imu_plugin SHARED src/gazebo_imu_plugin.cpp)
add_library(gazebo_mavlink_interface SHARED src/gazebo_mavlink_interface.cpp )
add_library(gazebo_motor_model SHARED src/gazebo_motor_model.cpp)
add_library(gazebo_multirotor_base_plugin SHARED src/gazebo_multirotor_base_plugin.cpp)
add_library(gazebo_wind_plugin SHARED src/gazebo_wind_plugin.cpp)
add_library(gazebo_magnetometer_plugin SHARED src/gazebo_magnetometer_plugin.cpp src/geo_mag_declination.cpp)
add_library(gazebo_barometer_plugin SHARED src/gazebo_barometer_plugin.cpp)
add_library(gazebo_catapult_plugin SHARED src/gazebo_catapult_plugin.cpp)
add_library(gazebo_usv_dynamics_plugin SHARED src/gazebo_usv_dynamics_plugin.cpp)
add_library(gazebo_parachute_plugin SHARED src/gazebo_parachute_plugin.cpp)
add_library(gazebo_airship_dynamics_plugin SHARED src/gazebo_airship_dynamics_plugin.cpp)
set(plugins
gazebo_airspeed_plugin
gazebo_geotagged_images_plugin
gazebo_gps_plugin
gazebo_groundtruth_plugin
gazebo_irlock_plugin
gazebo_lidar_plugin
gazebo_opticalflow_mockup_plugin
gazebo_opticalflow_plugin
gazebo_sonar_plugin
gazebo_uuv_plugin
gazebo_vision_plugin
gazebo_controller_interface
gazebo_gimbal_controller_plugin
gazebo_imu_plugin
gazebo_mavlink_interface
gazebo_motor_model
gazebo_multirotor_base_plugin
gazebo_wind_plugin
gazebo_magnetometer_plugin
gazebo_barometer_plugin
gazebo_catapult_plugin
gazebo_usv_dynamics_plugin
gazebo_parachute_plugin
gazebo_airship_dynamics_plugin
)
foreach(plugin ${plugins})
target_link_libraries(${plugin} ${Boost_LIBRARIES} ${GAZEBO_LIBRARIES} ${TinyXML_LIBRARIES})
endforeach()
target_link_libraries(gazebo_opticalflow_plugin ${OpticalFlow_LIBS})
# If BUILD_ROS_INTERFACE set to ON, build plugins that have ROS dependencies
# Current plugins that can be used with ROS interface: gazebo_motor_failure_plugin
if (BUILD_ROS_INTERFACE)
add_library(gazebo_motor_failure_plugin SHARED src/gazebo_motor_failure_plugin.cpp)
target_link_libraries(gazebo_motor_failure_plugin ${GAZEBO_libraries} ${roscpp_LIBRARIES})
list(APPEND plugins gazebo_motor_failure_plugin)
message(STATUS "adding gazebo_motor_failure_plugin to build")
include_directories(
include
${geometry_msgs_INCLUDE_DIRS}
${sensor_msgs_INCLUDE_DIRS}
)
target_link_libraries(gazebo_motor_failure_plugin
${catkin_LIBRARIES}
${roscpp_LIBRARIES}
${GAZEBO_libraries}
)
endif()
if (GSTREAMER_FOUND)
add_library(gazebo_gst_camera_plugin SHARED src/gazebo_gst_camera_plugin.cpp)
set(plugins
${plugins}
gazebo_gst_camera_plugin
)
message(STATUS "Found GStreamer: adding gst_camera_plugin")
if("${GAZEBO_VERSION}" VERSION_LESS "8.0")
QT4_WRAP_CPP(headers_MOC include/gazebo_video_stream_widget.h)
add_library(gazebo_video_stream_widget SHARED ${headers_MOC} src/gazebo_video_stream_widget.cpp)
target_link_libraries(gazebo_video_stream_widget ${GAZEBO_LIBRARIES} ${QT_LIBRARIES} ${PROTOBUF_LIBRARIES})
set(plugins
${plugins}
gazebo_video_stream_widget
)
message(STATUS "Found GStreamer: adding gst_video_stream_widget")
else()
QT5_WRAP_CPP(headers_MOC include/gazebo_video_stream_widget.h)
add_library(gazebo_video_stream_widget SHARED ${headers_MOC} src/gazebo_video_stream_widget.cpp)
target_link_libraries(gazebo_video_stream_widget ${GAZEBO_LIBRARIES} ${Qt5Core_LIBRARIES} ${Qt5Widgets_LIBRARIES} ${PROTOBUF_LIBRARIES} ${Qt5Test_LIBRARIES})
set(plugins
${plugins}
gazebo_video_stream_widget
)
message(STATUS "Found GStreamer: adding gst_video_stream_widget")
endif()
endif()
# Linux is not consistent with plugin availability, even on Gazebo 7
#if("${GAZEBO_VERSION}" VERSION_LESS "7.0")
add_library(LiftDragPlugin SHARED src/liftdrag_plugin/liftdrag_plugin.cpp)
list(APPEND plugins LiftDragPlugin)
#endif()
foreach(plugin ${plugins})
add_dependencies(${plugin} mav_msgs nav_msgs std_msgs sensor_msgs)
add_dependencies(${plugin} physics_msgs)
endforeach()
# Configure the setup script
if (catkin_FOUND)
catkin_add_env_hooks(50_sitl_gazebo_setup
DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/cmake
SHELLS sh)
endif()
################
## Unit Tests ##
################
include(UnitTests)
add_subdirectory(unit_tests)
#############
## Install ##
#############
set(PLUGIN_PATH ${CMAKE_INSTALL_LIBDIR}/${PROJECT_NAME}/plugins)
set(MODEL_PATH ${CMAKE_INSTALL_DATADIR}/${PROJECT_NAME}/models)
set(RESOURCE_PATH ${CMAKE_INSTALL_DATADIR}/${PROJECT_NAME})
file(REMOVE_RECURSE ${PROJECT_SOURCE_DIR}/models/.DS_Store)
file(GLOB models_list LIST_DIRECTORIES true ${PROJECT_SOURCE_DIR}/models/*)
file(REMOVE_RECURSE ${PROJECT_SOURCE_DIR}/worlds/.DS_Store)
file(GLOB worlds_list LIST_DIRECTORIES true ${PROJECT_SOURCE_DIR}/worlds/*)
install(TARGETS ${plugins} mav_msgs nav_msgs std_msgs sensor_msgs DESTINATION ${PLUGIN_PATH})
install(DIRECTORY ${models_list} DESTINATION ${MODEL_PATH})
install(FILES ${worlds_list} DESTINATION ${RESOURCE_PATH}/worlds)
configure_file(src/setup.sh.in "${CMAKE_CURRENT_BINARY_DIR}/setup.sh" @ONLY)
install(FILES ${CMAKE_CURRENT_BINARY_DIR}/setup.sh DESTINATION ${RESOURCE_PATH})
install(FILES ${PROJECT_SOURCE_DIR}/package.xml DESTINATION ${RESOURCE_PATH})
#############
## Testing ##
#############
# TODO
###############
## Packaging ##
###############
set(CPACK_PACKAGE_NAME ${PROJECT_NAME}-${GAZEBO_MAJOR_VERSION})
set(CPACK_PACKAGE_VERSION_MAJOR ${PROJECT_VERSION_MAJOR})
set(CPACK_PACKAGE_VERSION_MINOR ${PROJECT_VERSION_MINOR})
set(CPACK_PACKAGE_VERSION_PATCH ${PROJECT_VERSION_PATCH})
set(CPACK_PACKAGE_CONTACT pxusers@googlegroups.com)
set(DEBIAN_PACKAGE_DEPENDS "")
set(RPM_PACKAGE_DEPENDS "")
set(CPACK_DEBIAN_PACKAGE_DEPENDS ${DEBIAN_PACKAGE_DEPENDS})
set(CPACK_DEBIAN_PACKAGE_SECTION "devel")
set(CPACK_DEBIAN_PACKAGE_PRIORITY "optional")
set(CPACK_DEBIAN_PACKAGE_SHLIBDEPS ON)
set(CPACK_DEBIAN_PACKAGE_DESCRIPTION "gazebo plugins for px4 sitl.")
set(CPACK_RPM_PACKAGE_REQUIRES "${DEBIAN_PACKAGE_DEPENDS}")
set(CPACK_RPM_PACKAGE_DESCRIPTION "Gazebo plugins for px4 sitl.")
set(CPACK_PACKAGE_FILE_NAME "${PROJECT_NAME}-${GAZEBO_MAJOR_VERSION}-${PROJECT_VERSION}")
set(CPACK_SOURCE_PACKAGE_FILE_NAME "${PROJECT_NAME}-${GAZEBO_MAJOR_VERSION}-${PROJECT_VERSION}")
include(CPack)

View File

@ -0,0 +1,23 @@
argcomplete
argparse>=1.2
cerberus
coverage
empy>=3.3
jinja2>=2.8
matplotlib>=3.0.*
numpy>=1.13
packaging
pandas>=0.21
pkgconfig
psutil
pygments
pymavlink
pyros-genmsg
pyserial>=3.0
pyulog>=0.5.0
pyyaml
requests
setuptools>=39.2.0
six>=1.12.0
toml>=0.9
wheel>=0.31.1

11
px4_setup/px4setup.sh Normal file
View File

@ -0,0 +1,11 @@
grep -xF 'source ~/PX4-Autopilot/Tools/setup_gazebo.bash ~/PX4-Autopilot ~/PX4-Autopilot/build/px4_sitl_default' ${HOME}/.bashrc || echo "source ~/PX4-Autopilot/Tools/setup_gazebo.bash ~/PX4-Autopilot ~/PX4-Autopilot/build/px4_sitl_default" >> ${HOME}/.bashrc
grep -xF 'export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/PX4-Autopilot' ${HOME}/.bashrc || echo "export ROS_PACKAGE_PATH=\$ROS_PACKAGE_PATH:~/PX4-Autopilot" >> ${HOME}/.bashrc
grep -xF 'export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:~/PX4-Autopilot/Tools/sitl_gazebo' ${HOME}/.bashrc || echo "export ROS_PACKAGE_PATH=\$ROS_PACKAGE_PATH:~/PX4-Autopilot/Tools/sitl_gazebo" >> ${HOME}/.bashrc
#grep -xF 'export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:/home/aaal/catkin_ws/src/swarm_sim/models' ${HOME}/.bashrc || echo "export GAZEBO_MODEL_PATH=\$GAZEBO_MODEL_PATH:/home/aaal/catkin_ws/src/swarm_sim/models" >> ${HOME}/.bashrc
grep -xF 'export GAZEBO_PLUGIN_PATH=$GAZEBO_PLUGIN_PATH:/usr/lib/x86_64-linux-gnu/gazebo-9/plugins' ${HOME}/.bashrc || echo "export GAZEBO_PLUGIN_PATH=\$GAZEBO_PLUGIN_PATH:/usr/lib/x86_64-linux-gnu/gazebo-9/plugins" >> ${HOME}/.bashrc
cd ~/PX4-Autopilot
echo 'source home/arrow/PX4-Autopilot/Tools/simulation/gazebo-classic/setup_gazebo.bash home/arrow/PX4-Autopilot/ home/arrow/PX4-Autopilot//build/px4_sitl_default' >> ${HOME}/.bashrc
echo 'export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:/home/arrow/PX4-Autopilot' >> ${HOME}/.bashrc
echo 'export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:/home/arrow/PX4-Autopilot/Tools/simulation/gazebo-classic/sitl_gazebo-classic' >> ${HOME}/.bashrc
source ${HOME}/.bashrc

View File

@ -5,8 +5,8 @@
#include <ros/ros.h>
#include <std_msgs/Bool.h>
#include <oscillation_ctrl/RefSignal.h>
#include <oscillation_ctrl/EulerAngles.h>
//#include <oscillation_ctrl/RefSignal.h>
//#include <oscillation_ctrl/EulerAngles.h>
#include <oscillation_ctrl/WaypointTrack.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Quaternion.h>