posix shell: lots of cleanup and fixes

- move posix-configs/SITL/init/{rcS,10016_iris,6011_typhoon_h480} to ROMFS/px4fmu_common/init.d-posix
  allows for easier unification, only one symlink is required.
  - rcS: add AUTOCNF support. Update scripts to match with behavior of PX4
    master (parameter values, some sitl driver got removed)
- add alias to allow 'set variable value' syntax in scripts to px4-alias.sh
- use px4_getopt
- use separate argument for the test_data directory
- append PATH from within the px4 binary: this simplifies the usage
  w/o the sitl_run.sh script.
- add 'source px4-alias.sh' to all existing sitl startup scripts
- move sitl mixers to ROMFS/px4fmu_common/mixers-sitl
  makes it easier to use existing mixers and sitl-specific ones.
- remove unused rcS_gazebo_delta_wing
This commit is contained in:
Beat Küng 2018-08-04 12:01:12 +02:00 committed by Lorenz Meier
parent 413c09e20e
commit 7822e5b5c3
58 changed files with 472 additions and 371 deletions

View File

@ -4,7 +4,7 @@
#
# @type Quadrotor Wide
#
# @maintainer Anton Babushkin <julian@oes.ch>
# @maintainer Julian Oes <julian@oes.ch>
#
pwm_out_sim mode_pwm

View File

@ -0,0 +1,32 @@
#!nsh
#
# @name Typhoon H480 SITL
#
# @type Hexarotor x
#
if [ $AUTOCNF == yes ]
then
param set MAV_TYPE 13
param set MC_PITCHRATE_P 0.1
param set MC_ROLLRATE_P 0.05
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set TRIG_INTERFACE 3
param set TRIG_MODE 4
param set MNT_MODE_IN 0
param set MAV_PROTO_VER 2
fi
mavlink start -x -u 14558 -r 4000 -f -m onboard -o 14530
pwm_out_sim mode_pwm16
mixer load /dev/pwm_output0 etc/mixers/hexa_x.main.mix
mixer append /dev/pwm_output0 etc/mixers/mount_legs.aux.mix
vmount start
camera_trigger start

View File

@ -7,10 +7,35 @@ source px4-alias.sh
# TODO: In the future we want to share rc.autostart with NuttX
#source rc.autostart
# Use the variable set by sitl_run.sh to choose the model settings.
if [ "$PX4_SIM_MODEL" == "iris" ]; then
set REQUESTED_AUTOSTART 10016
elif [ "$PX4_SIM_MODEL" == "typhoon_h480" ]; then
set REQUESTED_AUTOSTART 6011
else
echo "Unknown model"
exit -1
fi
uorb start
if ! param load
if [ -f eeprom/parameters ]
then
# param load fails the first time, set defaults
param load
fi
if param compare SYS_AUTOSTART $REQUESTED_AUTOSTART
then
set AUTOCNF no
else
set AUTOCNF yes
fi
if [ $AUTOCNF == yes ]
then
param set SYS_AUTOSTART $REQUESTED_AUTOSTART
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
@ -54,6 +79,7 @@ then
param set SYS_RESTART_TYPE 2
fi
# Use environment variable PX4_ESTIMATOR to choose estimator.
if [ "$PX4_ESTIMATOR" == "ekf2" ]; then
param set SYS_MC_EST_GROUP 2
@ -61,17 +87,6 @@ elif [ "$PX4_ESTIMATOR" == "lpe" ]; then
param set SYS_MC_EST_GROUP 1
fi
# Use the variable set by sitl_run.sh to choose the model settings.
if [ "$PX4_SIM_MODEL" == "iris" ]; then
param set SYS_AUTOSTART 10016
elif [ "$PX4_SIM_MODEL" == "typhoon_h480" ]; then
param set SYS_AUTOSTART 6011
else
echo "Unknown model"
exit -1
fi
dataman start
replay tryapplyparams
simulator start -s
@ -104,11 +119,11 @@ mc_att_control start
# infrastructure already available on NuttX.
if param compare SYS_AUTOSTART 10016
then
source etc/init/10016_iris
source etc/init.d-posix/10016_iris
elif param compare SYS_AUTOSTART 6011
then
source etc/init/6011_typhoon_h480
source etc/init.d-posix/6011_typhoon_h480
fi
@ -125,6 +140,11 @@ 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
# Required for the typhoon
mavlink stream -r 10 -s MOUNT_ORIENTATION -u 14556
mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14557
mavlink stream -r 10 -s MOUNT_ORIENTATION -u 14557
logger start -e -t -b 1000
mavlink boot_complete

View File

@ -0,0 +1,24 @@
M: 4
O: 10000 10000 0 -10000 10000
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 1 -10000 -10000 0 -10000 10000
S: 0 2 +10000 +10000 0 -10000 10000
S: 0 3 +10000 +10000 0 -10000 10000
M: 4
O: 10000 10000 0 -10000 10000
S: 0 0 +10000 +10000 0 -10000 10000
S: 0 1 -10000 -10000 0 -10000 10000
S: 0 2 -10000 -10000 0 -10000 10000
S: 0 3 +10000 +10000 0 -10000 10000
M: 4
O: 10000 10000 0 -10000 10000
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 1 +10000 +10000 0 -10000 10000
S: 0 2 -10000 -10000 0 -10000 10000
S: 0 3 +10000 +10000 0 -10000 10000
M: 4
O: 10000 10000 0 -10000 10000
S: 0 0 +10000 +10000 0 -10000 10000
S: 0 1 +10000 +10000 0 -10000 10000
S: 0 2 +10000 +10000 0 -10000 10000
S: 0 3 +10000 +10000 0 -10000 10000

View File

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

View File

@ -2,15 +2,13 @@
set -e
echo args: $@
sitl_bin=$1
rcS_path=$2
debugger=$3
program=$4
model=$5
src_path=$6
build_path=$7
sitl_bin="$1"
rcS_path="$2"
debugger="$3"
program="$4"
model="$5"
src_path="$6"
build_path="$7"
echo SITL ARGS
@ -22,17 +20,8 @@ echo model: $model
echo src_path: $src_path
echo build_path: $build_path
working_dir=`pwd`
rootfs=$build_path/tmp/rootfs
if [ "$chroot" == "1" ]
then
chroot_enabled=-c
sudo_enabled=sudo
else
chroot_enabled=""
sudo_enabled=""
fi
rootfs="$build_path/tmp/rootfs" # this is the working directory
mkdir -p "$rootfs"
# To disable user input
if [[ -n "$NO_PXH" ]]; then
@ -52,7 +41,6 @@ if [ "$replay_mode" == "ekf2" ]
then
model="iris_replay"
# create the publisher rules
mkdir -p $rootfs
publisher_rules_file="$rootfs/orb_publisher.rules"
cat <<EOF > "$publisher_rules_file"
restrict_topics: sensor_combined, vehicle_gps_position, vehicle_land_detected
@ -80,16 +68,16 @@ then
kill $jmavsim_pid
fi
cp $src_path/Tools/posix_lldbinit $working_dir/.lldbinit
cp $src_path/Tools/posix.gdbinit $working_dir/.gdbinit
cp $src_path/Tools/posix_lldbinit $rootfs/.lldbinit
cp $src_path/Tools/posix.gdbinit $rootfs/.gdbinit
SIM_PID=0
if [ "$program" == "jmavsim" ] && [ ! -n "$no_sim" ]
then
# Start Java simulator
$src_path/Tools/jmavsim_run.sh -r 500 &
SIM_PID=`echo $!`
cd ../..
elif [ "$program" == "gazebo" ] && [ ! -n "$no_sim" ]
then
if [ -x "$(command -v gazebo)" ]
@ -118,27 +106,29 @@ then
fi
fi
cd $working_dir
pushd "$rootfs" >/dev/null
# Do not exit on failure now from here on because we want the complete cleanup
set +e
sitl_command="$sitl_bin $no_pxh $rootfs $rootfs/${rcS_path}"
# Use the new unified rcS for the supported models
# (All models will be transitioned over)
if [[ ($rcS_path == posix-configs/SITL/init/ekf2 || $rcS_path == posix-configs/SITL/init/lpe)
&& ($model == "iris" || $model == "typhoon_h480") ]]; then
echo "Using new unified rcS for $model"
sitl_command="$sitl_bin $no_pxh $src_path/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -t $src_path/test_data"
else
sitl_command="$sitl_bin $no_pxh $src_path/ROMFS/px4fmu_common -s ${src_path}/${rcS_path}/${model} -t $src_path/test_data"
fi
echo SITL COMMAND: $sitl_command
# Prepend to path to prioritize PX4 commands over potentially already
# installed PX4 commands.
export PATH="$build_path/bin":$PATH
export PX4_SIM_MODEL=${model}
pushd $rootfs
if [[ -n "$DONT_RUN" ]]
then
echo "Not running simulation (\$DONT_RUN is set)."
# Start Java simulator
elif [ "$debugger" == "lldb" ]
then
lldb -- $sitl_command
@ -167,7 +157,7 @@ else
eval $sitl_command
fi
popd
popd >/dev/null
if [[ -z "$DONT_RUN" ]]
then

View File

@ -148,7 +148,7 @@ set(config_module_list
# Default config_sitl_rcS_dir (posix_sitl_default), this is overwritten later
# for the config posix_sitl_efk2 and set again, explicitly, for posix_sitl_lpe,
# which are based on posix_sitl_default.
set(config_sitl_rcS_dir etc/init/rcS CACHE INTERNAL "init script dir for sitl")
set(config_sitl_rcS_dir posix-configs/SITL/init/ekf2 CACHE INTERNAL "init script dir for sitl")
set(config_sitl_viewer jmavsim CACHE STRING "viewer for sitl")
set_property(CACHE config_sitl_viewer PROPERTY STRINGS "jmavsim;none")

View File

@ -7,6 +7,14 @@ if [ ! -n "$ZSH_VERSION" ]; then
shopt -s expand_aliases
fi
# Map the NuttX-style variable definition 'set <var> <value>' to something that
# bash and alternatives understand
set() {
eval $1=$2
}
# alternative method with an alias:
# alias set='f(){ set -- "$1=$2"; eval "$1"; unset -f f; }; eval f'
# Don't stop on errors.
#set -e

View File

@ -207,27 +207,3 @@ px4_posix_generate_symlinks(
TARGET px4
)
add_custom_command(TARGET px4
POST_BUILD
COMMAND mkdir -p ${CMAKE_BINARY_DIR}/rootfs/etc/
)
add_custom_command(TARGET px4
POST_BUILD
COMMAND mkdir -p ${CMAKE_BINARY_DIR}/rootfs/etc/
)
add_custom_command(TARGET px4
POST_BUILD
COMMAND cp -R ${PROJECT_SOURCE_DIR}/posix-configs/SITL/init ${CMAKE_BINARY_DIR}/rootfs/etc/
)
add_custom_command(TARGET px4
POST_BUILD
COMMAND cp -R ${PROJECT_SOURCE_DIR}/ROMFS/sitl/mixers ${CMAKE_BINARY_DIR}/rootfs/etc/
)
add_custom_command(TARGET px4
POST_BUILD
COMMAND cp -R ${PROJECT_SOURCE_DIR}/ROMFS/px4fmu_common/mixers ${CMAKE_BINARY_DIR}/rootfs/etc/
)

View File

@ -3,7 +3,7 @@ file(MAKE_DIRECTORY ${SITL_WORKING_DIR})
# 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/fs/microsd/log 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)

View File

@ -52,14 +52,17 @@
*/
#include <string>
#include <algorithm>
#include <fstream>
#include <signal.h>
#include <stdio.h>
#include <errno.h>
#include <fcntl.h>
#include <sys/stat.h>
#include <stdlib.h>
#include <px4_log.h>
#include <px4_getopt.h>
#include <px4_tasks.h>
#include <px4_posix.h>
#include <px4_log.h>
@ -96,12 +99,14 @@ static void register_sig_handler();
static void set_cpu_scaling();
static int create_symlinks_if_needed(std::string &data_path);
static int create_dirs();
static int run_startup_bash_script(const char *commands_file);
static int run_startup_bash_script(const std::string &commands_file, const std::string &absolute_binary_path);
static std::string get_absolute_binary_path(const std::string &argv0);
static void wait_to_exit();
static bool is_already_running();
static void print_usage();
static bool dir_exists(const std::string &path);
static bool file_exists(const std::string &name);
static std::string file_basename(std::string const &pathname);
static std::string pwd();
@ -120,16 +125,20 @@ int main(int argc, char **argv)
const char prefix[] = PX4_BASH_PREFIX;
int path_length = 0;
std::string absolute_binary_path; // full path to the px4 binary being executed
if (argc > 0) {
/* The executed binary name could start with a path, so strip it away */
const std::string full_binary_name = argv[0];
const std::string binary_name = file_basename(full_binary_name);
if (binary_name.compare(0, strlen(prefix), prefix) == 0) {
is_client = true;
}
path_length = full_binary_name.length() - binary_name.length();
absolute_binary_path = get_absolute_binary_path(full_binary_name);
}
if (is_client) {
@ -155,78 +164,68 @@ int main(int argc, char **argv)
/* Server/daemon apps need to parse the command line arguments. */
int positional_arg_count = 0;
std::string data_path = "";
std::string commands_file = "";
std::string node_name = "";
std::string commands_file = "etc/init.d/rcS";
std::string test_data_path = "";
// parse arguments
for (int i = 1; i < argc; ++i) {
if (argv[i][0] == '-') {
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
if (strcmp(argv[i], "-h") == 0) {
print_usage();
return 0;
while ((ch = px4_getopt(argc, argv, "hdt:s:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'h':
print_usage();
return 0;
} else if (strcmp(argv[i], "-d") == 0) {
pxh_off = true;
case 'd':
pxh_off = true;
break;
} else {
printf("Unknown/unhandled parameter: %s\n", argv[i]);
print_usage();
return 1;
}
case 't':
test_data_path = myoptarg;
break;
} else if (!strncmp(argv[i], "__", 2)) {
case 's':
commands_file = myoptarg;
break;
// FIXME: what is this?
// ros arguments
if (!strncmp(argv[i], "__name:=", 8)) {
std::string name_arg = argv[i];
node_name = name_arg.substr(8);
PX4_INFO("node name: %s", node_name.c_str());
}
} else {
//printf("positional argument\n");
positional_arg_count += 1;
if (positional_arg_count == 1) {
commands_file = argv[i];
} else if (positional_arg_count == 2) {
data_path = commands_file;
commands_file = argv[i];
}
}
if (positional_arg_count != 2 && positional_arg_count != 1) {
PX4_ERR("Error expected 1 or 2 position arguments, got %d", positional_arg_count);
default:
PX4_ERR("unrecognized flag");
print_usage();
return -1;
}
}
if (myoptind < argc) {
data_path = argv[myoptind];
}
int ret = create_symlinks_if_needed(data_path);
if (ret != PX4_OK) {
return ret;
}
if (test_data_path != "") {
const std::string required_test_data_path = "./test_data";
if (!dir_exists(required_test_data_path.c_str())) {
symlink(test_data_path.c_str(), required_test_data_path.c_str());
}
}
if (!file_exists(commands_file)) {
PX4_ERR("Error opening startup file, does not exist: %s", commands_file.c_str());
return -1;
}
PX4_INFO("startup file: %s", commands_file.c_str());
register_sig_handler();
set_cpu_scaling();
px4_daemon::Server server;
server.start();
int ret = create_symlinks_if_needed(data_path);
if (ret != PX4_OK) {
return ret;
}
ret = create_dirs();
if (ret != PX4_OK) {
@ -238,7 +237,7 @@ int main(int argc, char **argv)
px4::init_once();
px4::init(argc, argv, "px4");
ret = run_startup_bash_script(commands_file.c_str());
ret = run_startup_bash_script(commands_file, absolute_binary_path);
// We now block here until we need to exit.
if (pxh_off) {
@ -283,33 +282,28 @@ int create_symlinks_if_needed(std::string &data_path)
return PX4_OK;
}
std::vector<std::string> path_sym_links;
path_sym_links.push_back("etc");
path_sym_links.push_back("test_data");
const std::string path_sym_link = "etc";
for (const auto &it = path_sym_links.begin(); it != path_sym_links.end(); ++it) {
PX4_DEBUG("path sym link: %s", path_sym_link.c_str());
PX4_DEBUG("path sym link: %s", it->c_str());;
std::string src_path = data_path;
std::string dest_path = current_path + "/" + path_sym_link;
std::string src_path = data_path + "/" + *it;
std::string dest_path = current_path + "/" + *it;
if (dir_exists(dest_path.c_str())) {
return PX4_OK;
}
if (dir_exists(dest_path.c_str())) {
continue;
}
PX4_INFO("Creating symlink %s -> %s", src_path.c_str(), dest_path.c_str());
PX4_INFO("Creating symlink %s -> %s", src_path.c_str(), dest_path.c_str());
// create sym-link
int ret = symlink(src_path.c_str(), dest_path.c_str());
// 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;
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());
}
} else {
PX4_DEBUG("Successfully created symlink %s -> %s", src_path.c_str(), dest_path.c_str());
}
return PX4_OK;
@ -416,13 +410,71 @@ void set_cpu_scaling()
#endif
}
int run_startup_bash_script(const char *commands_file)
std::string get_absolute_binary_path(const std::string &argv0)
{
// On Linux we could also use readlink("/proc/self/exe", buf, bufsize) to get the absolute path
std::size_t last_slash = argv0.find_last_of("/");
if (last_slash == std::string::npos) {
// either relative path or in PATH (PATH is ignored here)
return pwd();
}
std::string base = argv0.substr(0, last_slash);
if (base.length() > 0 && base[0] == '/') {
// absolute path
return base;
}
// relative path
return pwd() + "/" + base;
}
int run_startup_bash_script(const std::string &commands_file, const std::string &absolute_binary_path)
{
std::string bash_command("bash ");
bash_command += commands_file;
PX4_INFO("Calling bash script: %s", bash_command.c_str());
// Update the PATH variable to include the absolute_binary_path
// (required for the px4-alias.sh script and px4-* commands).
// They must be within the same directory as the px4 binary
const char *path_variable = "PATH";
std::string updated_path = absolute_binary_path;
const char *path = getenv(path_variable);
if (path) {
std::string spath = path;
// Check if absolute_binary_path already in PATH
bool already_in_path = false;
std::size_t current, previous = 0;
current = spath.find(':');
while (current != std::string::npos) {
if (spath.substr(previous, current - previous) == absolute_binary_path) {
already_in_path = true;
}
previous = current + 1;
current = spath.find(':', previous);
}
if (spath.substr(previous, current - previous) == absolute_binary_path) {
already_in_path = true;
}
if (!already_in_path) {
// Prepend to path to prioritize PX4 commands over potentially already installed PX4 commands.
updated_path = updated_path + ":" + path;
setenv(path_variable, updated_path.c_str(), 1);
}
}
PX4_INFO("Calling startup script: %s", bash_command.c_str());
int ret = 0;
@ -454,11 +506,11 @@ void print_usage()
{
printf("Usage for Server/daemon process: \n");
printf("\n");
printf(" px4 [-h|-d] [rootfs_directory] startup_file\n");
printf(" px4 [-h|-d] [-s <startup_file>] [-d <test_data_directory>] [<rootfs_directory>]\n");
printf("\n");
printf(" <startup_file> bash start script to be used as startup (default=etc/init.d/rcS)\n");
printf(" <rootfs_directory> directory where startup files and mixers are located,\n");
printf(" (if not given, CWD is used)\n");
printf(" <startup_file> bash start script to be used as startup\n");
printf(" -h help/usage information\n");
printf(" -d daemon mode, don't start pxh shell\n");
printf("\n");
@ -505,6 +557,18 @@ bool file_exists(const std::string &name)
return (stat(name.c_str(), &buffer) == 0);
}
static std::string file_basename(std::string const &pathname)
{
struct MatchPathSeparator {
bool operator()(char ch) const
{
return ch == '/';
}
};
return std::string(std::find_if(pathname.rbegin(), pathname.rend(),
MatchPathSeparator()).base(), pathname.end());
}
bool dir_exists(const std::string &path)
{
struct stat info;

View File

@ -227,6 +227,7 @@ px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int
pthread_mutex_lock(&task_mutex);
px4_task_t taskid = 0;
for (i = 0; i < PX4_MAX_TASKS; ++i) {
if (!taskmap[i].isused) {
taskmap[i].name = name;

View File

@ -1,15 +0,0 @@
#!nsh
#
# @name Typhoon H480 SITL
#
# @type Hexarotor x
#
# @maintainer empty@empty.com
#
param set MAV_TYPE 13
pwm_out_sim mode_pwm16
mixer load /dev/pwm_output0 etc/mixers/hexa_x.main.mix
mixer append /dev/pwm_output0 etc/mixers/mount_legs.aux.mix
vmount start

View File

@ -1,59 +0,0 @@
############################################################################
#
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
set(posix_init_file_names
rcS
rcS_tests
6011_typhoon_h480
10016_iris
)
# Get absolute paths
set(posix_init_files)
foreach(posix_file ${posix_init_file_names})
list(APPEND posix_init_files ${CMAKE_CURRENT_SOURCE_DIR}/${posix_file})
endforeach()
set(init_directory ${ROOTFS_DIRECTORY}/etc/init)
add_custom_target(posix_init_dir
COMMAND ${CMAKE_COMMAND} -E make_directory ${init_directory}
)
# cmake -E copy with version < 3.5 does not support copying multiple files yet, therefore use cp.
add_custom_target(posix_init
COMMAND cp ${posix_init_files} ${init_directory}
DEPENDS posix_init_dir
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set CAL_GYRO0_ID 2293768
@ -14,7 +19,7 @@ dataman start
simulator start -s
pwm_out_sim start
mixer load /dev/pwm_output0 ROMFS/px4fmu_test/mixers/uuv_quad_x.mix
mixer load /dev/pwm_output0 etc/mixers/uuv_quad_x.mix
gyrosim start
accelsim start

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -60,7 +65,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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -62,7 +67,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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -62,7 +67,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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14558 -r 4000000
mavlink start -x -u 14559 -r 4000000 -m onboard -o 14541
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14558

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -62,7 +67,7 @@ ekf2 start
landing_target_estimator 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 etc/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

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
@ -64,7 +69,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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param set SDLOG_DIRS_MAX 7

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -60,7 +65,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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
@ -63,7 +68,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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -60,7 +65,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 etc/mixers/quad_w.main.mix
mavlink start -x -u _MAVPORT_ -r 4000000 -o _MAVOPORT_
mavlink start -x -u _MAVPORT2_ -r 4000000 -m onboard -o _MAVOPORT2_
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u _MAVPORT_

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -84,7 +89,7 @@ fw_pos_control_l1 start
fw_att_control start
land_detector start fixedwing
wind_estimator start
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/plane_sitl.main.mix
mixer load /dev/pwm_output0 etc/mixers-sitl/plane_sitl.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -65,7 +70,7 @@ navigator start
ekf2 start
gnd_pos_control start
gnd_att_control start
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/rover_sitl.main.mix
mixer load /dev/pwm_output0 etc/mixers-sitl/rover_sitl.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -57,7 +62,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 etc/mixers/quad_x.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -80,7 +85,7 @@ mc_att_control start
fw_pos_control_l1 start
fw_att_control start
wind_estimator start
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/standard_vtol_sitl.main.mix
mixer load /dev/pwm_output0 etc/mixers-sitl/standard_vtol_sitl.main.mix
mavlink start -x -u 14556 -r 2000000 -f
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540 -f
mavlink stream -r 20 -s EXTENDED_SYS_STATE -u 14557

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -63,7 +68,7 @@ mc_att_control start
fw_pos_control_l1 start
fw_att_control start
wind_estimator start
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/quad_x_vtol.main.mix
mixer load /dev/pwm_output0 etc/mixers-sitl/quad_x_vtol.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -97,7 +102,7 @@ mc_att_control start
fw_pos_control_l1 start
fw_att_control start
wind_estimator start
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/tiltrotor_sitl.main.mix
mixer load /dev/pwm_output0 etc/mixers-sitl/tiltrotor_sitl.main.mix
mavlink start -x -u 14556 -r 2000000 -f
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540 -f
mavlink stream -r 20 -s EXTENDED_SYS_STATE -u 14557

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -63,8 +68,8 @@ 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 append /dev/pwm_output0 ROMFS/px4fmu_common/mixers/mount_legs.aux.mix
mixer load /dev/pwm_output0 etc/mixers/hexa_x.main.mix
mixer append /dev/pwm_output0 etc/mixers/mount_legs.aux.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink start -x -u 14558 -r 4000 -f -m onboard -o 14530

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
@ -59,7 +64,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_x.main.mix
mixer load /dev/pwm_output0 etc/mixers/quad_x.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
@ -61,7 +66,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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set CAL_GYRO0_ID 2293768
@ -14,7 +19,7 @@ dataman start
simulator start -s
pwm_out_sim start
mixer load /dev/pwm_output0 ROMFS/px4fmu_test/mixers/uuv_quad_x.mix
mixer load /dev/pwm_output0 etc/mixers/uuv_quad_x.mix
gyrosim start
accelsim start

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
@ -61,7 +66,7 @@ attitude_estimator_q start
local_position_estimator 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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_SYS_ID 1
@ -63,7 +68,7 @@ attitude_estimator_q start
local_position_estimator 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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_SYS_ID 2
@ -63,7 +68,7 @@ attitude_estimator_q start
local_position_estimator 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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14558 -r 4000000
mavlink start -x -u 14559 -r 4000000 -m onboard -o 14541
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14558

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
@ -70,7 +75,7 @@ local_position_estimator start
landing_target_estimator 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 etc/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

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
@ -79,7 +84,7 @@ attitude_estimator_q start
local_position_estimator 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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
@ -37,7 +42,6 @@ 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_P 0.6
param set MPC_Z_VEL_I 0.15
param set LPE_FUSION 242
@ -61,7 +65,7 @@ attitude_estimator_q start
local_position_estimator 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 etc/mixers/quad_w.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 1
@ -66,7 +71,7 @@ local_position_estimator 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 etc/mixers-sitl/plane_sitl.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
dataman start
@ -61,7 +66,7 @@ navigator start
ekf2 start
gnd_pos_control start
gnd_att_control start
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/rover_sitl.main.mix
mixer load /dev/pwm_output0 etc/mixers-sitl/rover_sitl.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 2
@ -61,7 +66,7 @@ attitude_estimator_q start
local_position_estimator 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 etc/mixers/quad_x.main.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 22
@ -74,7 +79,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 etc/mixers-sitl/standard_vtol_sitl.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 20 -s EXTENDED_SYS_STATE -u 14540

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set MAV_TYPE 13
@ -58,8 +63,8 @@ attitude_estimator_q start
local_position_estimator start
mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 ROMFS/px4fmu_common/mixers/hexa_x.main.mix
mixer append /dev/pwm_output0 ROMFS/px4fmu_common/mixers/mount_legs.aux.mix
mixer load /dev/pwm_output0 etc/mixers/hexa_x.main.mix
mixer append /dev/pwm_output0 etc/mixers/mount_legs.aux.mix
mavlink start -x -u 14556 -r 4000000
mavlink start -x -u 14557 -r 4000000 -m onboard -o 14540
mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556

View File

@ -1,59 +0,0 @@
uorb start
param load
param set MAV_TYPE 1
param set SYS_AUTOSTART 3033
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 SENS_BOARD_ROT 8
param set SENS_DPRES_OFF 0.001
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set NAV_ACC_RAD 15.0
param set FW_THR_IDLE 0.6
param set FS_GCS_ENABLE 2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
gpssim start
measairspeedsim start
pwm_out_sim start
sensors start
commander start
navigator start
ekf2 start
fw_pos_control_l1 start
fw_att_control start
land_detector start fixedwing
mixer load /dev/pwm_output0 ../../../../ROMFS/sitl/mixers/delta_wing_sitl.main.mix
mavlink start -x -u 14556 -r 2000000
mavlink start -x -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
logger start -e -t
mavlink boot_complete
replay trystart

View File

@ -1,21 +0,0 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load
param set SYS_RESTART_TYPE 0
dataman start
rgbledsim start
tone_alarm start
ver all
tests all
shutdown

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load

View File

@ -1,3 +1,8 @@
#!/usr/bin/bash
# PX4 commands need the 'px4-' prefix in bash.
# (px4-alias.sh is expected to be in the PATH)
source px4-alias.sh
uorb start
param load