diff --git a/CMakeLists.txt b/CMakeLists.txt
index b5a36e31af..01c633bfe0 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -124,6 +124,11 @@ cmake_minimum_required(VERSION 2.8 FATAL_ERROR)
set(PX4_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}")
set(PX4_BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}")
+execute_process(
+ COMMAND Tools/check_submodules.sh
+ WORKING_DIRECTORY ${PX4_SOURCE_DIR}
+ )
+
# Use clang
#SET (CMAKE_C_COMPILER /usr/bin/clang-3.6)
#SET (CMAKE_CXX_COMPILER /usr/bin/clang++-3.6)
@@ -158,6 +163,9 @@ message(STATUS "${target_name}")
# Define GNU standard installation directories
include(GNUInstallDirs)
+# Add support for external project building
+include(ExternalProject)
+
# Setup install paths
if(NOT CMAKE_INSTALL_PREFIX)
if (${OS} STREQUAL "posix")
@@ -198,6 +206,9 @@ if(DEFINED config_df_driver_list)
message("DF Drivers: ${config_df_driver_list}")
endif()
+# force static lib build
+set(BUILD_SHARED_LIBS OFF)
+
#=============================================================================
# project definition
#
@@ -218,8 +229,22 @@ set(version "${version_major}.${version_minor}.${version_patch}")
set(package-contact "px4users@googlegroups.com")
#=============================================================================
-# programs
+# find programs and packages
#
+
+# 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()
+
find_package(PythonInterp REQUIRED)
#=============================================================================
@@ -398,14 +423,13 @@ set(CPACK_GENERATOR "ZIP")
set(CPACK_PACKAGE_FILE_NAME "${PROJECT_NAME}-${CONFIG}-${version}")
set(CPACK_SOURCE_PACKAGE_FILE_NAME "${PROJECT_NAME}-${version}")
set(CPACK_SOURCE_GENERATOR "ZIP;TBZ2")
+set(CPACK_PACKAGING_INSTALL_PREFIX "/usr")
+set(CPACK_SET_DESTDIR "OFF")
if ("${CMAKE_SYSTEM}" MATCHES "Linux")
- find_program(DPKG_PROGRAM dpkg)
- if (EXISTS ${DPKG_PROGRAM})
- list (APPEND CPACK_GENERATOR "DEB")
- endif()
-endif()
-if (${OS} STREQUAL "posix")
- set(CPACK_SET_DESTDIR "ON")
+ find_program(DPKG_PROGRAM dpkg)
+ if (EXISTS ${DPKG_PROGRAM})
+ list (APPEND CPACK_GENERATOR "DEB")
+ endif()
endif()
include(CPack)
diff --git a/Makefile b/Makefile
index 730b59cc70..e942c8e405 100644
--- a/Makefile
+++ b/Makefile
@@ -111,20 +111,23 @@ else
BUILD_DIR_SUFFIX :=
endif
+SRC_DIR := $(shell dirname $(realpath $(lastword $(MAKEFILE_LIST))))
+
# Functions
# --------------------------------------------------------------------
# describe how to build a cmake config
define cmake-build
-+@if [ $(PX4_CMAKE_GENERATOR) = "Ninja" ] && [ -e ./build_$@$(BUILD_DIR_SUFFIX)/Makefile ]; then rm -rf ./build_$@$(BUILD_DIR_SUFFIX); fi
-+@if [ ! -e ./build_$@$(BUILD_DIR_SUFFIX)/CMakeCache.txt ]; then Tools/check_submodules.sh && mkdir -p ./build_$@$(BUILD_DIR_SUFFIX) && cd ./build_$@$(BUILD_DIR_SUFFIX) && cmake .. -G$(PX4_CMAKE_GENERATOR) -DCONFIG=$(1) || (cd .. && rm -rf ./build_$@$(BUILD_DIR_SUFFIX)); fi
-+@Tools/check_submodules.sh
-+@(echo "PX4 CONFIG: $@$(BUILD_DIR_SUFFIX)" && cd ./build_$@$(BUILD_DIR_SUFFIX) && $(PX4_MAKE) $(PX4_MAKE_ARGS) $(ARGS))
++@$(eval BUILD_DIR = $(SRC_DIR)/build_$@$(BUILD_DIR_SUFFIX))
++@if [ $(PX4_CMAKE_GENERATOR) = "Ninja" ] && [ -e $(BUILD_DIR)/Makefile ]; then rm -rf $(BUILD_DIR); fi
++@if [ ! -e $(BUILD_DIR)/CMakeCache.txt ]; then mkdir -p $(BUILD_DIR) && cd $(BUILD_DIR) && cmake .. -G$(PX4_CMAKE_GENERATOR) -DCONFIG=$(1) || (cd .. && rm -rf $(BUILD_DIR)); fi
++@(echo "PX4 CONFIG: $(BUILD_DIR)" && cd $(BUILD_DIR) && $(PX4_MAKE) $(PX4_MAKE_ARGS) $(ARGS))
endef
define cmake-build-other
-+@if [ $(PX4_CMAKE_GENERATOR) = "Ninja" ] && [ -e ./build_$@/Makefile ]; then rm -rf ./build_$@; fi
-+@if [ ! -e ./build_$@/CMakeCache.txt ]; then Tools/check_submodules.sh && mkdir -p ./build_$@ && cd ./build_$@ && cmake $(2) -G$(PX4_CMAKE_GENERATOR) || (cd .. && rm -rf ./build_$@); fi
-+@(cd ./build_$@ && $(PX4_MAKE) $(PX4_MAKE_ARGS) $(ARGS))
++@$(eval BUILD_DIR = $(SRC_DIR)/build_$@$(BUILD_DIR_SUFFIX))
++@if [ $(PX4_CMAKE_GENERATOR) = "Ninja" ] && [ -e $(BUILD_DIR)/Makefile ]; then rm -rf $(BUILD_DIR); fi
++@if [ ! -e $(BUILD_DIR)/CMakeCache.txt ]; then mkdir -p $(BUILD_DIR) && cd $(BUILD_DIR) && cmake $(2) -G$(PX4_CMAKE_GENERATOR) -DCONFIG=$(1) || (cd .. && rm -rf $(BUILD_DIR)); fi
++@(cd $(BUILD_DIR) && $(PX4_MAKE) $(PX4_MAKE_ARGS) $(ARGS))
endef
# create empty targets to avoid msgs for targets passed to cmake
@@ -174,6 +177,9 @@ posix_sitl_default:
posix_sitl_lpe:
$(call cmake-build,$@)
+posix_sitl_ekf2:
+ $(call cmake-build,$@)
+
posix_sitl_replay:
$(call cmake-build,$@)
@@ -233,14 +239,8 @@ run_sitl_ros: sitl_deprecation
# Other targets
# --------------------------------------------------------------------
-.PHONY: gazebo_build uavcan_firmware check check_format format unittest tests qgc_firmware package_firmware clean submodulesclean distclean
-.NOTPARALLEL: gazebo_build uavcan_firmware check check_format format unittest tests qgc_firmware package_firmware clean submodulesclean distclean
-
-gazebo_build:
- @mkdir -p build_gazebo
- @if [ ! -e ./build_gazebo/CMakeCache.txt ];then cd build_gazebo && cmake -Wno-dev -G$(PX4_CMAKE_GENERATOR) ../Tools/sitl_gazebo; fi
- @cd build_gazebo && $(PX4_MAKE) $(PX4_MAKE_ARGS)
- @cd build_gazebo && $(PX4_MAKE) $(PX4_MAKE_ARGS) sdf
+.PHONY: uavcan_firmware check check_format unittest tests qgc_firmware package_firmware clean submodulesclean distclean
+.NOTPARALLEL: uavcan_firmware check check_format unittest tests qgc_firmware package_firmware clean submodulesclean distclean
uavcan_firmware:
ifeq ($(VECTORCONTROL),1)
@@ -308,11 +308,7 @@ unittest: posix_sitl_default
@(cd build_unittest && ctest -j2 --output-on-failure)
run_tests_posix: posix_sitl_default
- @mkdir -p build_posix_sitl_default/src/firmware/posix/rootfs/fs/microsd
- @mkdir -p build_posix_sitl_default/src/firmware/posix/rootfs/eeprom
- @touch build_posix_sitl_default/src/firmware/posix/rootfs/eeprom/parameters
- @(cd build_posix_sitl_default/src/firmware/posix && ./px4 -d ../../../../posix-configs/SITL/init/rcS_tests | tee test_output)
- @(cd build_posix_sitl_default/src/firmware/posix && grep --color=always "All tests passed" test_output)
+ @(cd build_posix_sitl_default/ && ctest -V)
tests: check_unittest run_tests_posix
diff --git a/Tools/setup_gazebo.bash b/Tools/setup_gazebo.bash
new file mode 100755
index 0000000000..ace73d44d3
--- /dev/null
+++ b/Tools/setup_gazebo.bash
@@ -0,0 +1,28 @@
+#!/bin/bash
+#
+# Setup environment to make PX4 visible to Gazebo.
+#
+# Note, this is not necessary if using a ROS catkin workspace with the px4
+# package as the paths are exported.
+#
+# License: according to LICENSE.md in the root directory of the PX4 Firmware repository
+
+if [ "$#" != 2 ]
+then
+ echo usage: source setup_gazebo.bash src_dir build_dir
+ echo ""
+ return 1
+fi
+
+SRC_DIR=$1
+BUILD_DIR=$2
+
+# setup Gazebo env and update package path
+export GAZEBO_PLUGIN_PATH=${BUILD_DIR}/build_gazebo:${GAZEBO_PLUGIN_PATH}
+export GAZEBO_MODEL_PATH=${GAZEBO_MODEL_PATH}:${SRC_DIR}/Tools/sitl_gazebo/models
+# Disabling the remote model download seems only necessary with Gazebo 6
+#export GAZEBO_MODEL_DATABASE_URI=""
+export LD_LIBRARY_PATH=${LD_LIBRARY_PATH}:${SRC_DIR}/Tools/sitl_gazebo/Build/msgs/:${BUILD_DIR}/build_gazebo
+echo -e "GAZEBO_PLUGIN_PATH $GAZEBO_PLUGIN_PATH"
+echo -e "GAZEBO_MODEL_PATH $GAZEBO_MODEL_PATH"
+echo -e "LD_LIBRARY_PATH $LD_LIBRARY_PATH"
diff --git a/Tools/sitl_run.sh b/Tools/sitl_run.sh
index b1bbf458fe..e887db4375 100755
--- a/Tools/sitl_run.sh
+++ b/Tools/sitl_run.sh
@@ -1,22 +1,29 @@
#!/bin/bash
-rc_script=$1
-debugger=$2
-program=$3
-model=$4
-build_path=$5
-curr_dir=`pwd`
+set -e
+
+echo args: $@
+
+sitl_bin=$1
+label=$2
+debugger=$3
+program=$4
+model=$5
+src_path=$6
+build_path=$7
echo SITL ARGS
-echo rc_script: $rc_script
+
+echo sitl_bin: $sitl_bin
+echo label: $label
echo debugger: $debugger
echo program: $program
echo model: $model
+echo src_path: $src_path
echo build_path: $build_path
-mkdir -p $build_path/src/firmware/posix/rootfs/fs/microsd
-mkdir -p $build_path/src/firmware/posix/rootfs/eeprom
-touch $build_path/src/firmware/posix/rootfs/eeprom/parameters
+working_dir=`pwd`
+sitl_bin=$build_path/src/firmware/posix/px4
if [ "$chroot" == "1" ]
then
@@ -35,32 +42,29 @@ fi
if [ "$#" -lt 5 ]
then
- echo usage: sitl_run.sh rc_script debugger program model build_path
+ echo usage: sitl_run.sh rc_script debugger program model devel_path
echo ""
exit 1
fi
# kill process names that might stil
# be running from last time
-pkill gazebo
-pkill px4
+pgrep gazebo && pkill gazebo
+pgrep px4 && pkill px4
jmavsim_pid=`ps aux | grep java | grep Simulator | cut -d" " -f1`
if [ -n "$jmavsim_pid" ]
then
kill $jmavsim_pid
fi
-set -e
-
-cd $build_path/..
-cp Tools/posix_lldbinit $build_path/src/firmware/posix/.lldbinit
-cp Tools/posix.gdbinit $build_path/src/firmware/posix/.gdbinit
+cp $src_path/Tools/posix_lldbinit $working_dir/.lldbinit
+cp $src_path/Tools/posix.gdbinit $working_dir/.gdbinit
SIM_PID=0
if [ "$program" == "jmavsim" ] && [ ! -n "$no_sim" ]
then
- cd Tools/jMAVSim
+ cd $src_path/Tools/jMAVSim
ant create_run_jar copy_res
cd out/production
java -Djava.ext.dirs= -jar jmavsim_run.jar -udp 127.0.0.1:14560 &
@@ -71,15 +75,9 @@ then
if [ -x "$(command -v gazebo)" ]
then
# Set the plugin path so Gazebo finds our model and sim
- export GAZEBO_PLUGIN_PATH=$curr_dir/build_gazebo:${GAZEBO_PLUGIN_PATH}
- # Set the model path so Gazebo finds the airframes
- export GAZEBO_MODEL_PATH=${GAZEBO_MODEL_PATH}:$curr_dir/Tools/sitl_gazebo/models
- # The next line would disable online model lookup, can be commented in, in case of unstable behaviour.
- # export GAZEBO_MODEL_DATABASE_URI=""
- export SITL_GAZEBO_PATH=$curr_dir/Tools/sitl_gazebo
- make --no-print-directory gazebo_build
+ source $src_path/Tools/setup_gazebo.bash ${src_path} ${build_path}
- gzserver --verbose $curr_dir/Tools/sitl_gazebo/worlds/${model}.world &
+ gzserver --verbose ${src_path}/Tools/sitl_gazebo/worlds/${model}.world &
SIM_PID=`echo $!`
if [[ -n "$HEADLESS" ]]; then
@@ -98,37 +96,41 @@ then
# This is not a simulator, but a log file to replay
# Check if we need to creat a param file to allow user to change parameters
- if ! [ -f "${build_path}/src/firmware/posix/rootfs/replay_params.txt" ]
+ if ! [ -f "$rootfs/replay_params.txt" ]
then
- touch ${build_path}/src/firmware/posix/rootfs/replay_params.txt
+ touch $rootfs/replay_params.txt
fi
fi
-cd $build_path/src/firmware/posix
+cd $working_dir
if [ "$logfile" != "" ]
then
- cp $logfile rootfs/replay.px4log
+ cp $logfile $rootfs/replay.px4log
fi
# Do not exit on failure now from here on because we want the complete cleanup
set +e
+sitl_command="$sudo_enabled $sitl_bin $chroot_enabled $src_path $src_path/${label}/${model}"
+
+echo SITL COMMAND: $sitl_command
+
# Start Java simulator
if [ "$debugger" == "lldb" ]
then
- lldb -- px4 ../../../../${rc_script}_${program}_${model}
+ lldb -- $sitl_command
elif [ "$debugger" == "gdb" ]
then
- gdb --args px4 ../../../../${rc_script}_${program}_${model}
+ gdb --args $sitl_command
elif [ "$debugger" == "ddd" ]
then
- ddd --debugger gdb --args px4 ../../../../${rc_script}_${program}_${model}
+ ddd --debugger gdb --args $sitl_command
elif [ "$debugger" == "valgrind" ]
then
- valgrind ./px4 ../../../../${rc_script}_${program}_${model}
+ valgrind $sitl_command
else
- $sudo_enabled ./px4 $chroot_enabled ../../../../${rc_script}_${program}_${model}
+ $sitl_command
fi
if [ "$program" == "jmavsim" ]
diff --git a/cmake/configs/posix_sitl_broadcast.cmake b/cmake/configs/posix_sitl_broadcast.cmake
index 1f94b67603..35ca4885f3 100644
--- a/cmake/configs/posix_sitl_broadcast.cmake
+++ b/cmake/configs/posix_sitl_broadcast.cmake
@@ -72,8 +72,8 @@ set(config_extra_builtin_cmds
sercon
)
-set(config_sitl_rcS
- posix-configs/SITL/init/rcS
+set(config_sitl_rcS_dir
+ posix-configs/SITL/init/
CACHE FILEPATH "init script for sitl"
)
diff --git a/cmake/configs/posix_sitl_default.cmake b/cmake/configs/posix_sitl_default.cmake
index d4934ce2d3..a901add0a1 100644
--- a/cmake/configs/posix_sitl_default.cmake
+++ b/cmake/configs/posix_sitl_default.cmake
@@ -96,9 +96,9 @@ set(config_extra_builtin_cmds
sercon
)
-set(config_sitl_rcS
- posix-configs/SITL/init/rcS
- CACHE FILEPATH "init script for sitl"
+set(config_sitl_rcS_dir
+ posix-configs/SITL/init/lpe
+ CACHE FILEPATH "init script dir for sitl"
)
set(config_sitl_viewer
diff --git a/cmake/configs/posix_sitl_ekf2.cmake b/cmake/configs/posix_sitl_ekf2.cmake
new file mode 100644
index 0000000000..13c2d4591e
--- /dev/null
+++ b/cmake/configs/posix_sitl_ekf2.cmake
@@ -0,0 +1,5 @@
+include(cmake/configs/posix_sitl_default.cmake)
+
+set(config_sitl_rcS_dir
+ posix-configs/SITL/init/ekf2/
+ )
diff --git a/cmake/configs/posix_sitl_lpe.cmake b/cmake/configs/posix_sitl_lpe.cmake
index c098b72bf0..41d020048e 100644
--- a/cmake/configs/posix_sitl_lpe.cmake
+++ b/cmake/configs/posix_sitl_lpe.cmake
@@ -1,5 +1,5 @@
include(cmake/configs/posix_sitl_default.cmake)
-set(config_sitl_rcS
- posix-configs/SITL/init/rcS_lpe
+set(config_sitl_rcS_dir
+ posix-configs/SITL/init/lpe/
)
diff --git a/integrationtests/run_tests.bash b/integrationtests/run_tests.bash
index 2a3a4c2a0d..4454c34f43 100755
--- a/integrationtests/run_tests.bash
+++ b/integrationtests/run_tests.bash
@@ -5,26 +5,27 @@
# License: according to LICENSE.md in the root directory of the PX4 Firmware repository
set -e
-if [ "$#" -lt 1 ]
+# handle cleaning command
+do_clean=true
+if [ "$1" = "-o" ]
then
- echo usage: run_tests.bash firmware_src_dir
- echo ""
- exit 1
+ echo not cleaning
+ do_clean=false
fi
-SRC_DIR=$1
-JOB_DIR=$SRC_DIR/..
-BUILD=posix_sitl_default
-# TODO
-ROS_TEST_RESULT_DIR=/root/.ros/test_results/px4
-ROS_LOG_DIR=/root/.ros/log
-PX4_LOG_DIR=${SRC_DIR}/build_${BUILD}/src/firmware/posix/rootfs/fs/microsd/log
-TEST_RESULT_TARGET_DIR=$JOB_DIR/test_results
-# BAGS=/root/.ros
-# CHARTS=/root/.ros/charts
-# EXPORT_CHARTS=/sitl/testing/export_charts.py
+# determine the directory of the source given the directory of this script
+pushd `dirname $0` > /dev/null
+SCRIPTPATH=`pwd`
+popd > /dev/null
+ORIG_SRC=$(dirname $SCRIPTPATH)
-# source ROS env
+# set paths
+JOB_DIR=$(dirname $ORIG_SRC)
+CATKIN_DIR=$JOB_DIR/catkin
+BUILD_DIR=$CATKIN_DIR/build/px4
+SRC_DIR=${CATKIN_DIR}/src/px4
+
+echo setting up ROS paths
if [ -f /opt/ros/indigo/setup.bash ]
then
source /opt/ros/indigo/setup.bash
@@ -35,26 +36,53 @@ else
echo "could not find /opt/ros/{ros-distro}/setup.bash"
exit 1
fi
-source $SRC_DIR/integrationtests/setup_gazebo_ros.bash $SRC_DIR
+export ROS_HOME=$JOB_DIR/.ros
+export ROS_LOG_DIR=$ROS_HOME/log
+export ROS_TEST_RESULT_DIR=$ROS_HOME/test_results/px4
-echo "deleting previous test results ($TEST_RESULT_TARGET_DIR)"
-if [ -d ${TEST_RESULT_TARGET_DIR} ]; then
- rm -r ${TEST_RESULT_TARGET_DIR}
-fi
+PX4_LOG_DIR=$ROS_HOME/rootfs/fs/microsd/log
+TEST_RESULT_TARGET_DIR=$JOB_DIR/test_results
-# FIXME: Firmware compilation seems to CD into this directory (/root/Firmware)
-# when run from "run_container.bash". Why?
-if [ -d /root/Firmware ]; then
- rm /root/Firmware
+# TODO
+# BAGS=$ROS_HOME
+# CHARTS=$ROS_HOME/charts
+# EXPORT_CHARTS=/sitl/testing/export_charts.py
+
+if $do_clean
+then
+ echo cleaning
+ rm -rf $CATKIN_DIR
+ rm -rf $ROS_HOME
+ rm -rf $TEST_RESULT_TARGET_DIR
+else
+ echo skipping clean step
fi
-ln -s ${SRC_DIR} /root/Firmware
echo "=====> compile ($SRC_DIR)"
-cd $SRC_DIR
-make ${BUILD}
-make --no-print-directory gazebo_build
+mkdir -p $ROS_HOME
+mkdir -p $CATKIN_DIR/src
+mkdir -p $TEST_RESULT_TARGET_DIR
+if ! [ -d $SRC_DIR ]
+then
+ ln -s $ORIG_SRC $SRC_DIR
+ ln -s $ORIG_SRC/Tools/sitl_gazebo ${CATKIN_DIR}/src/mavlink_sitl_gazebo
+fi
+cd $CATKIN_DIR
+catkin_make
+. ./devel/setup.bash
echo "<====="
+# print paths to user
+echo -e "JOB_DIR\t\t: $JOB_DIR"
+echo -e "ROS_HOME\t: $ROS_HOME"
+echo -e "CATKIN_DIR\t: $CATKIN_DIR"
+echo -e "BUILD_DIR\t: $BUILD_DIR"
+echo -e "SRC_DIR\t\t: $SRC_DIR"
+echo -e "ROS_TEST_RESULT_DIR\t: $ROS_TEST_RESULT_DIR"
+echo -e "ROS_LOG_DIR\t\t: $ROS_LOG_DIR"
+echo -e "PX4_LOG_DIR\t\t: $PX4_LOG_DIR"
+echo -e "TEST_RESULT_TARGET_DIR\t: $TEST_RESULT_TARGET_DIR"
+
# don't exit on error anymore from here on (because single tests or exports might fail)
set +e
echo "=====> run tests"
@@ -73,7 +101,6 @@ echo "=====> process test results"
# done
echo "copy build test results to job directory"
-mkdir -p ${TEST_RESULT_TARGET_DIR}
cp -r $ROS_TEST_RESULT_DIR/* ${TEST_RESULT_TARGET_DIR}
cp -r $ROS_LOG_DIR/* ${TEST_RESULT_TARGET_DIR}
cp -r $PX4_LOG_DIR/* ${TEST_RESULT_TARGET_DIR}
diff --git a/integrationtests/setup_gazebo_ros.bash b/integrationtests/setup_gazebo_ros.bash
deleted file mode 100755
index 6c22bbe192..0000000000
--- a/integrationtests/setup_gazebo_ros.bash
+++ /dev/null
@@ -1,22 +0,0 @@
-#!/bin/bash
-#
-# Setup environment to make PX4 visible to ROS/Gazebo.
-#
-# License: according to LICENSE.md in the root directory of the PX4 Firmware repository
-
-if [ "$#" -lt 1 ]
-then
- echo usage: source setup_gazebo_ros.bash firmware_src_dir
- echo ""
- return 1
-fi
-
-SRC_DIR=$1
-
-# setup Gazebo env and update package path
-export GAZEBO_MODEL_PATH=${GAZEBO_MODEL_PATH}:${SRC_DIR}/Tools/sitl_gazebo/models
-export GAZEBO_PLUGIN_PATH=${SRC_DIR}/build_gazebo:${GAZEBO_PLUGIN_PATH}
-export LD_LIBRARY_PATH=${LD_LIBRARY_PATH}:${SRC_DIR}/Tools/sitl_gazebo/Build/msgs/
-export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:${SRC_DIR}
-export GAZEBO_MODEL_DATABASE_URI=""
-export SITL_GAZEBO_PATH=$SRC_DIR/Tools/sitl_gazebo
diff --git a/launch/mavros_posix_sitl.launch b/launch/mavros_posix_sitl.launch
index 558f3bbadb..fea6b03940 100644
--- a/launch/mavros_posix_sitl.launch
+++ b/launch/mavros_posix_sitl.launch
@@ -1,19 +1,47 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
+
+
+
@@ -22,3 +50,5 @@
+
+
diff --git a/launch/mavros_posix_tests_iris.launch b/launch/mavros_posix_tests_iris.launch
index 235acda6f2..d482859927 100644
--- a/launch/mavros_posix_tests_iris.launch
+++ b/launch/mavros_posix_tests_iris.launch
@@ -4,11 +4,14 @@
+
+
+
diff --git a/launch/mavros_posix_tests_standard_vtol.launch b/launch/mavros_posix_tests_standard_vtol.launch
index d5aa9e285e..278bead65f 100644
--- a/launch/mavros_posix_tests_standard_vtol.launch
+++ b/launch/mavros_posix_tests_standard_vtol.launch
@@ -4,12 +4,14 @@
+
-
+
+
diff --git a/launch/posix_sitl.launch b/launch/posix_sitl.launch
index 9895ee9d43..4228924b65 100644
--- a/launch/posix_sitl.launch
+++ b/launch/posix_sitl.launch
@@ -1,19 +1,44 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
+
+
+
+
+
-
+
+
+
+
+
+
+
+
+
+
diff --git a/posix-configs/SITL/README.md b/posix-configs/SITL/README.md
index 2588c4b09b..a98a6515fa 100644
--- a/posix-configs/SITL/README.md
+++ b/posix-configs/SITL/README.md
@@ -105,5 +105,5 @@ param set RC_MAP_POSCTL_SW 7
param set RC_MAP_RETURN_SW 8
param set MC_PITCHRATE_P 0.05
param set MC_ROLLRATE_P 0.05
-mixer load /dev/pwm_output0 ../../ROMFS/px4fmu_common/mixers/quad_x.main.mix
+mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_x.main.mix
```
diff --git a/posix-configs/SITL/init/rcS_gazebo_tailsitter b/posix-configs/SITL/init/ekf2/gazebo_tailsitter
similarity index 95%
rename from posix-configs/SITL/init/rcS_gazebo_tailsitter
rename to posix-configs/SITL/init/ekf2/gazebo_tailsitter
index 2ba72c5b8c..04d3a2b2f2 100644
--- a/posix-configs/SITL/init/rcS_gazebo_tailsitter
+++ b/posix-configs/SITL/init/ekf2/gazebo_tailsitter
@@ -60,7 +60,7 @@ mc_pos_control start
mc_att_control start
fw_pos_control_l1 start
fw_att_control start
-mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix
+mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
diff --git a/posix-configs/SITL/init/rcS_gazebo_iris b/posix-configs/SITL/init/ekf2/iris
similarity index 96%
rename from posix-configs/SITL/init/rcS_gazebo_iris
rename to posix-configs/SITL/init/ekf2/iris
index d985929601..6b93b86c2e 100644
--- a/posix-configs/SITL/init/rcS_gazebo_iris
+++ b/posix-configs/SITL/init/ekf2/iris
@@ -60,7 +60,7 @@ navigator start
ekf2 start
mc_pos_control start
mc_att_control start
-mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_w.main.mix
+mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_w.main.mix
mavlink start -u 14556 -r 4000000
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
diff --git a/posix-configs/SITL/init/rcS_multiple_gazebo_iris b/posix-configs/SITL/init/ekf2/multiple_iris
similarity index 100%
rename from posix-configs/SITL/init/rcS_multiple_gazebo_iris
rename to posix-configs/SITL/init/ekf2/multiple_iris
diff --git a/posix-configs/SITL/init/rcS_gazebo_plane b/posix-configs/SITL/init/ekf2/plane
similarity index 95%
rename from posix-configs/SITL/init/rcS_gazebo_plane
rename to posix-configs/SITL/init/ekf2/plane
index b4f40ce2dd..bc837d2acd 100644
--- a/posix-configs/SITL/init/rcS_gazebo_plane
+++ b/posix-configs/SITL/init/ekf2/plane
@@ -47,7 +47,7 @@ ekf2 start
fw_pos_control_l1 start
fw_att_control start
land_detector start fixedwing
-mixer load /dev/pwm_output0 ../../../../ROMFS/sitl/mixers/plane_sitl.main.mix
+mixer load /dev/pwm_output0 ROMFS/sitl/mixers/plane_sitl.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
diff --git a/posix-configs/SITL/init/rcS_gazebo_solo b/posix-configs/SITL/init/ekf2/solo
similarity index 96%
rename from posix-configs/SITL/init/rcS_gazebo_solo
rename to posix-configs/SITL/init/ekf2/solo
index 008261b6ec..8701609064 100644
--- a/posix-configs/SITL/init/rcS_gazebo_solo
+++ b/posix-configs/SITL/init/ekf2/solo
@@ -57,7 +57,7 @@ navigator start
ekf2 start
mc_pos_control start
mc_att_control start
-mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x.main.mix
+mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_x.main.mix
mavlink start -u 14556 -r 4000000
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
diff --git a/posix-configs/SITL/init/rcS_gazebo_standard_vtol b/posix-configs/SITL/init/ekf2/standard_vtol
similarity index 96%
rename from posix-configs/SITL/init/rcS_gazebo_standard_vtol
rename to posix-configs/SITL/init/ekf2/standard_vtol
index a1f448bb58..d90ddfa891 100644
--- a/posix-configs/SITL/init/rcS_gazebo_standard_vtol
+++ b/posix-configs/SITL/init/ekf2/standard_vtol
@@ -69,7 +69,7 @@ mc_pos_control start
mc_att_control start
fw_pos_control_l1 start
fw_att_control start
-mixer load /dev/pwm_output0 ../../../../ROMFS/sitl/mixers/standard_vtol_sitl.main.mix
+mixer load /dev/pwm_output0 ROMFS/sitl/mixers/standard_vtol_sitl.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
diff --git a/posix-configs/SITL/init/rcS_gazebo_typhoon_h480 b/posix-configs/SITL/init/ekf2/typohoon_h480
similarity index 96%
rename from posix-configs/SITL/init/rcS_gazebo_typhoon_h480
rename to posix-configs/SITL/init/ekf2/typohoon_h480
index 87c620c750..8713c62f74 100644
--- a/posix-configs/SITL/init/rcS_gazebo_typhoon_h480
+++ b/posix-configs/SITL/init/ekf2/typohoon_h480
@@ -59,7 +59,7 @@ navigator start
ekf2 start
mc_pos_control start
mc_att_control start
-mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/hexa_x.main.mix
+mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/hexa_x.main.mix
mavlink start -u 14556 -r 4000000
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
diff --git a/posix-configs/SITL/init/rc_iris_ros b/posix-configs/SITL/init/inav/iris
similarity index 95%
rename from posix-configs/SITL/init/rc_iris_ros
rename to posix-configs/SITL/init/inav/iris
index ca1cf0961e..2aa41cdbc8 100644
--- a/posix-configs/SITL/init/rc_iris_ros
+++ b/posix-configs/SITL/init/inav/iris
@@ -60,7 +60,7 @@ attitude_estimator_q start
position_estimator_inav start
mc_pos_control_m start
mc_att_control_m start
-mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x.main.mix
+mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_x.main.mix
mavlink start -u 14556 -r 2000000
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
diff --git a/posix-configs/SITL/init/rcS_gazebo_iris_opt_flow b/posix-configs/SITL/init/inav/iris_opt_flow
similarity index 96%
rename from posix-configs/SITL/init/rcS_gazebo_iris_opt_flow
rename to posix-configs/SITL/init/inav/iris_opt_flow
index 2be4900b81..44060e1b52 100644
--- a/posix-configs/SITL/init/rcS_gazebo_iris_opt_flow
+++ b/posix-configs/SITL/init/inav/iris_opt_flow
@@ -59,7 +59,7 @@ attitude_estimator_q start
position_estimator_inav start
mc_pos_control start
mc_att_control start
-mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_w.main.mix
+mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_w.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
diff --git a/posix-configs/SITL/init/rcS_lpe_gazebo_iris b/posix-configs/SITL/init/lpe/iris
similarity index 96%
rename from posix-configs/SITL/init/rcS_lpe_gazebo_iris
rename to posix-configs/SITL/init/lpe/iris
index 9c84018e98..59b11d1c5e 100644
--- a/posix-configs/SITL/init/rcS_lpe_gazebo_iris
+++ b/posix-configs/SITL/init/lpe/iris
@@ -60,7 +60,7 @@ attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
-mixer load /dev/pwm_output0 /usr/share/px4/ROMFS/px4fmu_common/mixers/quad_w.main.mix
+mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_w.main.mix
mavlink start -u 14556 -r 4000000
mavlink start -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
diff --git a/posix-configs/SITL/init/rcS_lpe_gazebo_iris_opt_flow b/posix-configs/SITL/init/lpe/iris_opt_flow
similarity index 96%
rename from posix-configs/SITL/init/rcS_lpe_gazebo_iris_opt_flow
rename to posix-configs/SITL/init/lpe/iris_opt_flow
index c1a6a2eae5..759831595a 100644
--- a/posix-configs/SITL/init/rcS_lpe_gazebo_iris_opt_flow
+++ b/posix-configs/SITL/init/lpe/iris_opt_flow
@@ -69,7 +69,7 @@ attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
-mixer load /dev/pwm_output0 /usr/share/px4/ROMFS/px4fmu_common/mixers/quad_w.main.mix
+mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/quad_w.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
diff --git a/posix-configs/SITL/init/rcS_lpe_gazebo_standard_vtol b/posix-configs/SITL/init/lpe/standard_vtol
similarity index 100%
rename from posix-configs/SITL/init/rcS_lpe_gazebo_standard_vtol
rename to posix-configs/SITL/init/lpe/standard_vtol
diff --git a/posix-configs/SITL/init/rcS_jmavsim_iris b/posix-configs/SITL/init/rcS_jmavsim_iris
deleted file mode 100644
index 26db22d8f0..0000000000
--- a/posix-configs/SITL/init/rcS_jmavsim_iris
+++ /dev/null
@@ -1,80 +0,0 @@
-uorb start
-param load
-param set MAV_TYPE 2
-param set SYS_AUTOSTART 4010
-param set SYS_RESTART_TYPE 2
-dataman start
-param set BAT_N_CELLS 3
-param set CAL_GYRO0_ID 2293768
-param set CAL_ACC0_ID 1376264
-param set CAL_ACC1_ID 1310728
-param set CAL_MAG0_ID 196616
-param set CAL_GYRO0_XOFF 0.01
-param set CAL_ACC0_XOFF 0.01
-param set CAL_ACC0_YOFF -0.01
-param set CAL_ACC0_ZOFF 0.01
-param set CAL_ACC0_XSCALE 1.01
-param set CAL_ACC0_YSCALE 1.01
-param set CAL_ACC0_ZSCALE 1.01
-param set CAL_ACC1_XOFF 0.01
-param set CAL_MAG0_XOFF 0.01
-param set MPC_XY_P 0.4
-param set MPC_XY_VEL_P 0.2
-param set MPC_XY_VEL_D 0.005
-param set SENS_BOARD_ROT 0
-param set SENS_BOARD_X_OFF 0.000001
-param set COM_RC_IN_MODE 1
-param set NAV_DLL_ACT 2
-param set COM_DISARM_LAND 3
-param set NAV_ACC_RAD 2.0
-param set RTL_RETURN_ALT 30.0
-param set RTL_DESCEND_ALT 10.0
-param set RTL_LAND_DELAY 0
-param set MIS_TAKEOFF_ALT 2.5
-param set MC_ROLLRATE_P 0.2
-param set MC_PITCHRATE_P 0.2
-param set MC_PITCH_P 6
-param set MC_ROLL_P 6
-param set MPC_HOLD_MAX_Z 2.0
-param set MPC_HOLD_XY_DZ 0.1
-param set MPC_Z_VEL_MAX 2.0
-param set MPC_Z_VEL_P 0.4
-param set EKF2_GBIAS_INIT 0.01
-param set EKF2_ANGERR_INIT 0.01
-param set EKF2_MAG_TYPE 1
-replay tryapplyparams
-simulator start -s
-rgbledsim start
-tone_alarm start
-gyrosim start
-accelsim start
-barosim start
-adcsim start
-gpssim start
-#gps start -d /dev/ttyACM0 -s
-pwm_out_sim mode_pwm
-sleep 1
-sensors start
-commander start
-land_detector start multicopter
-navigator start
-ekf2 start
-mc_pos_control start
-mc_att_control start
-mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x.main.mix
-mavlink start -u 14556 -r 2000000
-mavlink start -u 14557 -r 2000000 -m onboard -o 14540
-mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
-mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
-mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
-mavlink stream -r 80 -s ATTITUDE -u 14556
-mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
-mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
-mavlink stream -r 20 -s RC_CHANNELS -u 14556
-mavlink stream -r 250 -s HIGHRES_IMU -u 14556
-mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
-mavlink stream -r 20 -s MANUAL_CONTROL -u 14556
-sdlog2 start -r 100 -e -t -a
-logger start -e -t
-mavlink boot_complete
-replay trystart
diff --git a/posix-configs/SITL/init/rcS_lpe_jmavsim_iris b/posix-configs/SITL/init/rcS_lpe_jmavsim_iris
deleted file mode 100644
index 106d032275..0000000000
--- a/posix-configs/SITL/init/rcS_lpe_jmavsim_iris
+++ /dev/null
@@ -1,80 +0,0 @@
-uorb start
-param load
-param set MAV_TYPE 2
-param set SYS_AUTOSTART 4010
-param set SYS_RESTART_TYPE 2
-dataman start
-param set BAT_N_CELLS 3
-param set CAL_GYRO0_ID 2293768
-param set CAL_ACC0_ID 1376264
-param set CAL_ACC1_ID 1310728
-param set CAL_MAG0_ID 196616
-param set CAL_GYRO0_XOFF 0.01
-param set CAL_ACC0_XOFF 0.01
-param set CAL_ACC0_YOFF -0.01
-param set CAL_ACC0_ZOFF 0.01
-param set CAL_ACC0_XSCALE 1.01
-param set CAL_ACC0_YSCALE 1.01
-param set CAL_ACC0_ZSCALE 1.01
-param set CAL_ACC1_XOFF 0.01
-param set CAL_MAG0_XOFF 0.01
-param set MPC_XY_P 0.4
-param set MPC_XY_VEL_P 0.2
-param set MPC_XY_VEL_D 0.005
-param set SENS_BOARD_ROT 0
-param set SENS_BOARD_X_OFF 0.000001
-param set COM_RC_IN_MODE 1
-param set NAV_DLL_ACT 2
-param set COM_DISARM_LAND 3
-param set NAV_ACC_RAD 2.0
-param set RTL_RETURN_ALT 30.0
-param set RTL_DESCEND_ALT 10.0
-param set RTL_LAND_DELAY 0
-param set MIS_TAKEOFF_ALT 2.5
-param set MC_ROLLRATE_P 0.2
-param set MC_PITCHRATE_P 0.2
-param set MC_PITCH_P 6
-param set MC_ROLL_P 6
-param set MPC_HOLD_MAX_Z 2.0
-param set MPC_HOLD_XY_DZ 0.1
-param set MPC_Z_VEL_MAX 2.0
-param set MPC_Z_VEL_P 0.4
-param set EKF2_GBIAS_INIT 0.01
-param set EKF2_ANGERR_INIT 0.01
-replay tryapplyparams
-simulator start -s
-rgbledsim start
-tone_alarm start
-gyrosim start
-accelsim start
-barosim start
-adcsim start
-gpssim start
-#gps start -d /dev/ttyACM0 -s
-pwm_out_sim mode_pwm
-sleep 1
-sensors start
-commander start
-land_detector start multicopter
-navigator start
-attitude_estimator_q start
-local_position_estimator start
-mc_pos_control start
-mc_att_control start
-mixer load /dev/pwm_output0 /usr/share/px4/ROMFS/px4fmu_common/mixers/quad_x.main.mix
-mavlink start -u 14556 -r 2000000
-mavlink start -u 14557 -r 2000000 -m onboard -o 14540
-mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
-mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
-mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
-mavlink stream -r 80 -s ATTITUDE -u 14556
-mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
-mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
-mavlink stream -r 20 -s RC_CHANNELS -u 14556
-mavlink stream -r 250 -s HIGHRES_IMU -u 14556
-mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
-mavlink stream -r 20 -s MANUAL_CONTROL -u 14556
-sdlog2 start -r 100 -e -t -a
-logger start -e -t
-mavlink boot_complete
-replay trystart
diff --git a/posix-configs/SITL/init/rcS_replay_iris b/posix-configs/SITL/init/replay/iris
similarity index 100%
rename from posix-configs/SITL/init/rcS_replay_iris
rename to posix-configs/SITL/init/replay/iris
diff --git a/posix-configs/SITL/init/rcS_tests b/posix-configs/SITL/init/test/iris
similarity index 100%
rename from posix-configs/SITL/init/rcS_tests
rename to posix-configs/SITL/init/test/iris
diff --git a/src/firmware/posix/CMakeLists.txt b/src/firmware/posix/CMakeLists.txt
index 64cbbf786d..dcba5f5851 100644
--- a/src/firmware/posix/CMakeLists.txt
+++ b/src/firmware/posix/CMakeLists.txt
@@ -118,17 +118,43 @@ else()
endif()
endif()
+#=============================================================================
+# sitl run targets
+#
+
+set(SITL_WORKING_DIR ${PX4_BINARY_DIR}/tmp)
+file(MAKE_DIRECTORY ${SITL_WORKING_DIR})
+
add_custom_target(run_config
- COMMAND Tools/sitl_run.sh "${config_sitl_rcS}" "${config_sitl_debugger}"
- "${config_sitl_viewer}" "${config_sitl_model}" "${PX4_BINARY_DIR}"
- WORKING_DIRECTORY ${PX4_SOURCE_DIR}
+ COMMAND Tools/sitl_run.sh
+ $
+ ${config_sitl_rcS_dir}
+ ${config_sitl_debugger}
+ ${config_sitl_viewer}
+ ${config_sitl_model}
+ ${PX4_SOURCE_DIR}
+ ${PX4_BINARY_DIR}
+ WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
)
add_dependencies(run_config px4)
-foreach(viewer none jmavsim gazebo replay)
- foreach(debugger none gdb lldb ddd valgrind)
- foreach(model none iris iris_opt_flow tailsitter standard_vtol plane solo typhoon_h480)
+# 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}
+ BINARY_DIR ${PX4_BINARY_DIR}/build_gazebo
+ INSTALL_COMMAND ""
+ )
+set_target_properties(sitl_gazebo PROPERTIES EXCLUDE_FROM_ALL TRUE)
+
+# create targets for each viewer/model/debugger combination
+set(viewers none jmavsim gazebo replay)
+set(debuggers none gdb lldb ddd valgrind)
+set(models none iris iris_opt_flow tailsitter standard_vtol plane solo typhoon_h480)
+foreach(viewer ${viewers})
+ foreach(debugger ${debuggers})
+ foreach(model ${models})
if (debugger STREQUAL "none")
if (model STREQUAL "none")
set(_targ_name "${viewer}")
@@ -143,13 +169,20 @@ foreach(viewer none jmavsim gazebo replay)
endif()
endif()
add_custom_target(${_targ_name}
- COMMAND Tools/sitl_run.sh "${config_sitl_rcS}"
- "${debugger}"
- "${viewer}" "${model}" "${PX4_BINARY_DIR}"
- WORKING_DIRECTORY ${PX4_SOURCE_DIR}
+ COMMAND ${PX4_SOURCE_DIR}/Tools/sitl_run.sh
+ $
+ ${config_sitl_rcS_dir}
+ ${debugger}
+ ${viewer}
+ ${model}
+ ${PX4_SOURCE_DIR}
+ ${PX4_BINARY_DIR}
+ WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
)
- add_dependencies(${_targ_name} px4)
+ if (viewer STREQUAL "gazebo")
+ add_dependencies(${_targ_name} sitl_gazebo)
+ endif()
endforeach()
endforeach()
endforeach()
@@ -158,8 +191,25 @@ endforeach()
# install
#
-install(TARGETS px4 DESTINATION bin)
+install(TARGETS px4 DESTINATION ${CMAKE_INSTALL_BINDIR})
install(DIRECTORY ${PROJECT_SOURCE_DIR}/ROMFS DESTINATION ${CMAKE_INSTALL_DATADIR}/${PROJECT_NAME})
install(DIRECTORY ${PROJECT_SOURCE_DIR}/posix-configs DESTINATION ${CMAKE_INSTALL_DATADIR}/${PROJECT_NAME})
+#=============================================================================
+# tests
+#
+
+add_test(NAME rcS_tests
+ COMMAND ${PX4_SOURCE_DIR}/Tools/sitl_run.sh
+ $
+ posix-configs/SITL/init/test
+ none
+ none
+ none
+ ${PX4_SOURCE_DIR}
+ ${PX4_BINARY_DIR}
+ WORKING_DIRECTORY ${SITL_WORKING_DIR})
+set_tests_properties(rcS_tests PROPERTIES
+ PASS_REGULAR_EXPRESSION "All tests passed")
+
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
diff --git a/src/lib/rc/rc_tests/RCTest.cpp b/src/lib/rc/rc_tests/RCTest.cpp
index 6b0c33cafc..f5f2cedfd1 100644
--- a/src/lib/rc/rc_tests/RCTest.cpp
+++ b/src/lib/rc/rc_tests/RCTest.cpp
@@ -16,7 +16,7 @@
#if !defined(CONFIG_ARCH_BOARD_SITL)
#define TEST_DATA_PATH "/fs/microsd"
#else
-#define TEST_DATA_PATH "../../../../test_data/"
+#define TEST_DATA_PATH "./test_data/"
#endif
extern "C" __EXPORT int rc_tests_main(int argc, char *argv[]);
diff --git a/src/platforms/posix/main.cpp b/src/platforms/posix/main.cpp
index fe2cf8f88c..e1c32d8a54 100644
--- a/src/platforms/posix/main.cpp
+++ b/src/platforms/posix/main.cpp
@@ -50,6 +50,7 @@
#include "px4_middleware.h"
#include "DriverFramework.hpp"
#include
+#include
namespace px4
{
@@ -62,6 +63,12 @@ typedef int (*px4_main_t)(int argc, char *argv[]);
#define CMD_BUFF_SIZE 100
+#ifdef PATH_MAX
+const unsigned path_max_len = PATH_MAX;
+#else
+const unsigned path_max_len = 1024;
+#endif
+
static bool _ExitFlag = false;
static struct termios orig_term;
@@ -85,6 +92,96 @@ extern "C" {
}
}
+static inline bool fileExists(const string &name)
+{
+ struct stat buffer;
+ return (stat(name.c_str(), &buffer) == 0);
+}
+
+static inline bool dirExists(const string &path)
+{
+ struct stat info;
+
+ if (stat(path.c_str(), &info) != 0) {
+ return false;
+
+ } else if (info.st_mode & S_IFDIR) {
+ return true;
+
+ } else {
+ return false;
+ }
+}
+
+static inline void touch(const string &name)
+{
+ fstream fs;
+ fs.open(name, ios::out);
+ fs.close();
+}
+
+static int mkpath(const char *path, mode_t mode);
+
+static int do_mkdir(const char *path, mode_t mode)
+{
+ struct stat st;
+ int status = 0;
+
+ if (stat(path, &st) != 0) {
+ /* Directory does not exist. EEXIST for race condition */
+ if (mkdir(path, mode) != 0 && errno != EEXIST) {
+ status = -1;
+ }
+
+ } else if (!S_ISDIR(st.st_mode)) {
+ errno = ENOTDIR;
+ status = -1;
+ }
+
+ return (status);
+}
+
+/**
+** mkpath - ensure all directories in path exist
+** Algorithm takes the pessimistic view and works top-down to ensure
+** each directory in path exists, rather than optimistically creating
+** the last element and working backwards.
+*/
+static int mkpath(const char *path, mode_t mode)
+{
+ char *pp;
+ char *sp;
+ int status;
+ char *copypath = strdup(path);
+
+ status = 0;
+ pp = copypath;
+
+ while (status == 0 && (sp = strchr(pp, '/')) != 0) {
+ if (sp != pp) {
+ /* Neither root nor double slash in path */
+ *sp = '\0';
+ status = do_mkdir(copypath, mode);
+ *sp = '/';
+ }
+
+ pp = sp + 1;
+ }
+
+ if (status == 0) {
+ status = do_mkdir(path, mode);
+ }
+
+ free(copypath);
+ return (status);
+}
+
+static string pwd()
+{
+ char temp[path_max_len];
+ return (getcwd(temp, path_max_len) ? string(temp) : string(""));
+}
+
static void print_prompt()
{
cout.flush();
@@ -134,12 +231,13 @@ static void run_cmd(const vector &appargs, bool exit_on_fail, bool silen
static void usage()
{
- cout << "./px4 [-d] [startup_config] -h" << std::endl;
+ cout << "./px4 [-d] data_directory startup_config [-h]" << endl;
cout << " -d - Optional flag to run the app in daemon mode and does not listen for user input." <<
- std::endl;
- cout << " This is needed if px4 is intended to be run as a upstart job on linux" << std::endl;
- cout << " - config file for starting/stopping px4 modules" << std::endl;
- cout << " -h - help/usage information" << std::endl;
+ endl;
+ cout << " This is needed if px4 is intended to be run as a upstart job on linux" << endl;
+ cout << " - directory where romfs and posix-configs are located" << endl;
+ cout << " - config file for starting/stopping px4 modules" << endl;
+ cout << " -h - help/usage information" << endl;
}
static void process_line(string &line, bool exit_on_fail)
@@ -202,52 +300,131 @@ int main(int argc, char **argv)
set_cpu_scaling();
int index = 1;
- char *commands_file = nullptr;
+ string commands_file = "";
+ int positional_arg_count = 0;
+ string data_path = "";
+ string node_name = "";
+ // parse arguments
while (index < argc) {
+ //cout << "arg: " << index << " : " << argv[index] << endl;
+
if (argv[index][0] == '-') {
// the arg starts with -
- if (strcmp(argv[index], "-d") == 0) {
+ if (strncmp(argv[index], "-d", 2) == 0) {
daemon_mode = true;
- } else if (strcmp(argv[index], "-h") == 0) {
+ } else if (strncmp(argv[index], "-h", 2) == 0) {
usage();
return 0;
- } else if (strcmp(argv[index], "-c") == 0) {
+ } else if (strncmp(argv[index], "-c", 2) == 0) {
chroot_on = true;
} else {
- PX4_WARN("Unknown/unhandled parameter: %s", argv[index]);
+ PX4_ERR("Unknown/unhandled parameter: %s", argv[index]);
return 1;
}
+ } else if (!strncmp(argv[index], "__", 2)) {
+ //cout << "ros argument" << endl;
+
+ // ros arguments
+ if (!strncmp(argv[index], "__name:=", 8)) {
+ string name_arg = argv[index];
+ node_name = name_arg.substr(8);
+ cout << "node name: " << node_name << endl;
+ }
+
} else {
- // this is an argument that does not have '-' prefix; treat it like a file name
- ifstream infile(argv[index]);
+ //cout << "positional argument" << endl;
- if (infile.good()) {
- infile.close();
+ positional_arg_count += 1;
+
+ if (positional_arg_count == 1) {
+ data_path = argv[index];
+ cout << "data path: " << data_path << endl;
+
+ } else if (positional_arg_count == 2) {
commands_file = argv[index];
-
- } else {
- PX4_WARN("Error opening file: %s", argv[index]);
- return -1;
+ cout << "commands file: " << commands_file << endl;
}
}
++index;
}
+ if (positional_arg_count != 2) {
+ PX4_ERR("Error expected 2 position arguments, got %d", positional_arg_count);
+ usage();
+ return -1;
+ }
+ if (commands_file.size() < 1) {
+ PX4_ERR("Error commands file not specified");
+ return -1;
+ }
+
+ if (!fileExists(commands_file)) {
+ PX4_ERR("Error opening commands file, does not exist: %s", commands_file.c_str());
+ return -1;
+ }
+
+ // create sym-links
+ vector path_sym_links;
+ path_sym_links.push_back("ROMFS");
+ path_sym_links.push_back("posix-configs");
+ path_sym_links.push_back("test_data");
+
+ for (int i = 0; i < path_sym_links.size(); i++) {
+ string path_sym_link = path_sym_links[i];
+ //cout << "path sym link: " << path_sym_link << endl;
+ string src_path = data_path + "/" + path_sym_link;
+ string dest_path = pwd() + "/" + path_sym_link;
+
+ PX4_DEBUG("Creating symlink %s -> %s", src_path.c_str(), dest_path.c_str());
+
+ if (dirExists(path_sym_link)) { continue; }
+
+ // create sym-links
+ int ret = symlink(src_path.c_str(), dest_path.c_str());
+
+ if (ret != 0) {
+ PX4_ERR("Error creating symlink %s -> %s",
+ src_path.c_str(), dest_path.c_str());
+ return ret;
+
+ } else {
+ PX4_DEBUG("Successfully created symlink %s -> %s",
+ src_path.c_str(), dest_path.c_str());
+ }
+ }
+
+ // setup rootfs
+ const string eeprom_path = "./rootfs/eeprom/";
+ const string microsd_path = "./rootfs/fs/microsd/";
+
+ if (!fileExists(eeprom_path + "parameters")) {
+ cout << "creating new parameters file" << endl;
+ mkpath(eeprom_path.c_str(), S_IRUSR | S_IWUSR | S_IXUSR);
+ touch(eeprom_path + "parameters");
+ }
+
+ if (!fileExists(microsd_path + "dataman")) {
+ cout << "creating new dataman file" << endl;
+ mkpath(microsd_path.c_str(), S_IRUSR | S_IWUSR | S_IXUSR);
+ touch(microsd_path + "dataman");
+ }
+
+ // initialize
DriverFramework::Framework::initialize();
px4::init_once();
px4::init(argc, argv, "px4");
// if commandfile is present, process the commands from the file
- if (commands_file != nullptr) {
- ifstream infile(commands_file);
+ if (commands_file.size() != 0) {
+ ifstream infile(commands_file.c_str());
if (infile.is_open()) {
for (string line; getline(infile, line, '\n');) {
@@ -261,7 +438,7 @@ int main(int argc, char **argv)
}
} else {
- PX4_WARN("Error opening file: %s", commands_file);
+ PX4_ERR("Error opening commands file: %s", commands_file.c_str());
}
}
@@ -270,12 +447,6 @@ int main(int argc, char **argv)
// this is not an attempt to secure the environment,
// rather, to replicate a deployed file system.
-#ifdef PATH_MAX
- const unsigned path_max_len = PATH_MAX;
-#else
- const unsigned path_max_len = 1024;
-#endif
-
char pwd_path[path_max_len];
const char *folderpath = "/rootfs/";
diff --git a/src/systemcmds/tests/test_mixer.cpp b/src/systemcmds/tests/test_mixer.cpp
index ec595199c7..ac07dd6a70 100644
--- a/src/systemcmds/tests/test_mixer.cpp
+++ b/src/systemcmds/tests/test_mixer.cpp
@@ -96,7 +96,7 @@ int test_mixer(int argc, char *argv[])
#if !defined(CONFIG_ARCH_BOARD_SITL)
const char *filename = "/etc/mixers/IO_pass.mix";
#else
- const char *filename = "../../../../ROMFS/px4fmu_test/mixers/IO_pass.mix";
+ const char *filename = "ROMFS/px4fmu_test/mixers/IO_pass.mix";
#endif
//PX4_INFO("loading: %s", filename);
@@ -406,7 +406,7 @@ int test_mixer(int argc, char *argv[])
#if !defined(CONFIG_ARCH_BOARD_SITL)
filename = "/etc/mixers/quad_test.mix";
#else
- filename = "../../../../ROMFS/px4fmu_test/mixers/quad_test.mix";
+ filename = "ROMFS/px4fmu_test/mixers/quad_test.mix";
#endif
load_mixer_file(filename, &buf[0], sizeof(buf));