26 changed files with 718 additions and 159 deletions
@ -0,0 +1,107 @@
@@ -0,0 +1,107 @@
|
||||
#!nsh |
||||
# |
||||
# Flight startup script for PX4FMU with PWM outputs. |
||||
# |
||||
|
||||
# disable USB and autostart |
||||
set USB no |
||||
set MODE custom |
||||
|
||||
echo "[init] doing PX4FMU Quad startup..." |
||||
|
||||
# |
||||
# Start the ORB |
||||
# |
||||
uorb start |
||||
|
||||
# |
||||
# Load microSD params |
||||
# |
||||
echo "[init] loading microSD params" |
||||
param select /fs/microsd/params |
||||
if [ -f /fs/microsd/params ] |
||||
then |
||||
param load /fs/microsd/params |
||||
fi |
||||
|
||||
# |
||||
# Load default params for this platform |
||||
# |
||||
if param compare SYS_AUTOCONFIG 1 |
||||
then |
||||
# Set all params here, then disable autoconfig |
||||
param set MC_ATTRATE_P 0.14 |
||||
param set MC_ATTRATE_I 0 |
||||
param set MC_ATTRATE_D 0.006 |
||||
param set MC_ATT_P 5.5 |
||||
param set MC_ATT_I 0 |
||||
param set MC_ATT_D 0 |
||||
param set MC_YAWPOS_D 0 |
||||
param set MC_YAWPOS_I 0 |
||||
param set MC_YAWPOS_P 0.6 |
||||
param set MC_YAWRATE_D 0 |
||||
param set MC_YAWRATE_I 0 |
||||
param set MC_YAWRATE_P 0.08 |
||||
param set RC_SCALE_PITCH 1 |
||||
param set RC_SCALE_ROLL 1 |
||||
param set RC_SCALE_YAW 3 |
||||
|
||||
param set SYS_AUTOCONFIG 0 |
||||
param save /fs/microsd/params |
||||
fi |
||||
|
||||
# |
||||
# Force some key parameters to sane values |
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor |
||||
# see https://pixhawk.ethz.ch/mavlink/ |
||||
# |
||||
param set MAV_TYPE 2 |
||||
|
||||
# |
||||
# Start MAVLink |
||||
# |
||||
mavlink start -d /dev/ttyS0 -b 57600 |
||||
usleep 5000 |
||||
|
||||
# |
||||
# Start the sensors and test them. |
||||
# |
||||
sh /etc/init.d/rc.sensors |
||||
|
||||
# |
||||
# Start the commander. |
||||
# |
||||
commander start |
||||
|
||||
# |
||||
# Start GPS interface (depends on orb) |
||||
# |
||||
gps start |
||||
|
||||
# |
||||
# Start the attitude estimator |
||||
# |
||||
attitude_estimator_ekf start |
||||
|
||||
echo "[init] starting PWM output" |
||||
fmu mode_pwm |
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix |
||||
pwm -u 400 -m 0xff |
||||
|
||||
# |
||||
# Start attitude control |
||||
# |
||||
multirotor_att_control start |
||||
|
||||
# |
||||
# Start logging |
||||
# |
||||
sdlog2 start -r 50 -a -b 14 |
||||
|
||||
# |
||||
# Start system state |
||||
# |
||||
if blinkm start |
||||
then |
||||
blinkm systemstate |
||||
fi |
@ -0,0 +1,139 @@
@@ -0,0 +1,139 @@
|
||||
#!nsh |
||||
# |
||||
# Flight startup script for PX4FMU+PX4IO |
||||
# |
||||
|
||||
# disable USB and autostart |
||||
set USB no |
||||
set MODE custom |
||||
|
||||
# |
||||
# Load default params for this platform |
||||
# |
||||
if param compare SYS_AUTOCONFIG 1 |
||||
then |
||||
# Set all params here, then disable autoconfig |
||||
param set SYS_AUTOCONFIG 0 |
||||
|
||||
param set MC_ATTRATE_D 0.007 |
||||
param set MC_ATTRATE_I 0.0 |
||||
param set MC_ATTRATE_P 0.13 |
||||
param set MC_ATT_D 0.0 |
||||
param set MC_ATT_I 0.0 |
||||
param set MC_ATT_P 7.0 |
||||
param set MC_POS_P 0.1 |
||||
param set MC_RCLOSS_THR 0.0 |
||||
param set MC_YAWPOS_D 0.0 |
||||
param set MC_YAWPOS_I 0.5 |
||||
param set MC_YAWPOS_P 1.0 |
||||
param set MC_YAWRATE_D 0.0 |
||||
param set MC_YAWRATE_I 0.0 |
||||
param set MC_YAWRATE_P 0.2 |
||||
|
||||
param save /fs/microsd/params |
||||
fi |
||||
|
||||
# |
||||
# Force some key parameters to sane values |
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor |
||||
# see https://pixhawk.ethz.ch/mavlink/ |
||||
# |
||||
param set MAV_TYPE 2 |
||||
|
||||
# |
||||
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell) |
||||
# |
||||
if [ -f /fs/microsd/px4io2.bin ] |
||||
then |
||||
echo "PX4IO Firmware found. Checking Upgrade.." |
||||
if cmp /fs/microsd/px4io2.bin /fs/microsd/px4io2.cur |
||||
then |
||||
echo "No newer version, skipping upgrade." |
||||
else |
||||
echo "Loading /fs/microsd/px4io2.bin" |
||||
if px4io update /fs/microsd/px4io2.bin > /fs/microsd/px4io2.log |
||||
then |
||||
cp /fs/microsd/px4io2.bin /fs/microsd/px4io2.cur |
||||
echo "Flashed /fs/microsd/px4io2.bin OK" >> /fs/microsd/px4io2.log |
||||
else |
||||
echo "Failed flashing /fs/microsd/px4io2.bin" >> /fs/microsd/px4io2.log |
||||
echo "Failed to upgrade PX4IO2 firmware - check if PX4IO2 is in bootloader mode" |
||||
fi |
||||
fi |
||||
fi |
||||
|
||||
# |
||||
# Start MAVLink (depends on orb) |
||||
# |
||||
mavlink start |
||||
usleep 5000 |
||||
|
||||
# |
||||
# Start PX4IO interface (depends on orb, commander) |
||||
# |
||||
px4io start |
||||
pwm -u 400 -m 0xff |
||||
|
||||
# |
||||
# Allow PX4IO to recover from midair restarts. |
||||
# this is very unlikely, but quite safe and robust. |
||||
px4io recovery |
||||
|
||||
# |
||||
# Disable px4io topic limiting |
||||
# |
||||
px4io limit 200 |
||||
|
||||
# |
||||
# This sets a PWM right after startup (regardless of safety button) |
||||
# |
||||
px4io idle 900 900 900 900 |
||||
|
||||
# |
||||
# The values are for spinning motors when armed using DJI ESCs |
||||
# |
||||
px4io min 1200 1200 1200 1200 |
||||
|
||||
# |
||||
# Upper limits could be higher, this is on the safe side |
||||
# |
||||
px4io max 1800 1800 1800 1800 |
||||
|
||||
# |
||||
# Start the sensors (depends on orb, px4io) |
||||
# |
||||
sh /etc/init.d/rc.sensors |
||||
|
||||
# |
||||
# Start the commander (depends on orb, mavlink) |
||||
# |
||||
commander start |
||||
|
||||
# |
||||
# Start GPS interface (depends on orb) |
||||
# |
||||
gps start |
||||
|
||||
# |
||||
# Start the attitude estimator (depends on orb) |
||||
# |
||||
attitude_estimator_ekf start |
||||
|
||||
# |
||||
# Load mixer and start controllers (depends on px4io) |
||||
# |
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix |
||||
multirotor_att_control start |
||||
|
||||
# |
||||
# Start logging |
||||
# |
||||
sdlog2 start -r 20 -a -b 14 |
||||
|
||||
# |
||||
# Start system state |
||||
# |
||||
if blinkm start |
||||
then |
||||
blinkm systemstate |
||||
fi |
@ -0,0 +1,121 @@
@@ -0,0 +1,121 @@
|
||||
#!nsh |
||||
# |
||||
# Flight startup script for PX4FMU+PX4IO |
||||
# |
||||
|
||||
# disable USB and autostart |
||||
set USB no |
||||
set MODE custom |
||||
|
||||
# |
||||
# Start the ORB (first app to start) |
||||
# |
||||
uorb start |
||||
|
||||
# |
||||
# Load microSD params |
||||
# |
||||
echo "[init] loading microSD params" |
||||
param select /fs/microsd/params |
||||
if [ -f /fs/microsd/params ] |
||||
then |
||||
param load /fs/microsd/params |
||||
fi |
||||
|
||||
# |
||||
# Load default params for this platform |
||||
# |
||||
if param compare SYS_AUTOCONFIG 1 |
||||
then |
||||
# Set all params here, then disable autoconfig |
||||
param set SYS_AUTOCONFIG 0 |
||||
param save /fs/microsd/params |
||||
fi |
||||
|
||||
# |
||||
# Force some key parameters to sane values |
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor |
||||
# see https://pixhawk.ethz.ch/mavlink/ |
||||
# |
||||
param set MAV_TYPE 1 |
||||
|
||||
# |
||||
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell) |
||||
# |
||||
if [ -f /fs/microsd/px4io.bin ] |
||||
then |
||||
echo "PX4IO Firmware found. Checking Upgrade.." |
||||
if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current |
||||
then |
||||
echo "No newer version, skipping upgrade." |
||||
else |
||||
echo "Loading /fs/microsd/px4io.bin" |
||||
if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log |
||||
then |
||||
cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current |
||||
echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log |
||||
else |
||||
echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log |
||||
echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode" |
||||
fi |
||||
fi |
||||
fi |
||||
|
||||
# |
||||
# Start MAVLink (depends on orb) |
||||
# |
||||
mavlink start -d /dev/ttyS1 -b 57600 |
||||
usleep 5000 |
||||
|
||||
# |
||||
# Start the commander (depends on orb, mavlink) |
||||
# |
||||
commander start |
||||
|
||||
# |
||||
# Start PX4IO interface (depends on orb, commander) |
||||
# |
||||
px4io start |
||||
|
||||
# |
||||
# Allow PX4IO to recover from midair restarts. |
||||
# this is very unlikely, but quite safe and robust. |
||||
px4io recovery |
||||
|
||||
# |
||||
# Set actuator limit to 100 Hz update (50 Hz PWM) |
||||
px4io limit 100 |
||||
|
||||
# |
||||
# Start the sensors (depends on orb, px4io) |
||||
# |
||||
sh /etc/init.d/rc.sensors |
||||
|
||||
# |
||||
# Start GPS interface (depends on orb) |
||||
# |
||||
gps start |
||||
|
||||
# |
||||
# Start the attitude estimator (depends on orb) |
||||
# |
||||
kalman_demo start |
||||
|
||||
# |
||||
# Load mixer and start controllers (depends on px4io) |
||||
# |
||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix |
||||
control_demo start |
||||
|
||||
# |
||||
# Start logging |
||||
# |
||||
sdlog2 start -r 50 -a -b 14 |
||||
|
||||
# |
||||
# Start system state |
||||
# |
||||
if blinkm start |
||||
then |
||||
blinkm systemstate |
||||
fi |
@ -1,67 +0,0 @@
@@ -1,67 +0,0 @@
|
||||
#!nsh |
||||
# |
||||
# Flight startup script for PX4FMU with PWM outputs. |
||||
# |
||||
|
||||
# Disable the USB interface |
||||
set USB no |
||||
|
||||
# Disable autostarting other apps |
||||
set MODE custom |
||||
|
||||
echo "[init] doing PX4FMU Quad startup..." |
||||
|
||||
# |
||||
# Start the ORB |
||||
# |
||||
uorb start |
||||
|
||||
# |
||||
# Load microSD params |
||||
# |
||||
echo "[init] loading microSD params" |
||||
param select /fs/microsd/params |
||||
if [ -f /fs/microsd/params ] |
||||
then |
||||
param load /fs/microsd/params |
||||
fi |
||||
|
||||
# |
||||
# Force some key parameters to sane values |
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor |
||||
# see https://pixhawk.ethz.ch/mavlink/ |
||||
# |
||||
param set MAV_TYPE 2 |
||||
|
||||
# |
||||
# Start MAVLink |
||||
# |
||||
mavlink start -d /dev/ttyS0 -b 57600 |
||||
usleep 5000 |
||||
|
||||
# |
||||
# Start the sensors and test them. |
||||
# |
||||
sh /etc/init.d/rc.sensors |
||||
|
||||
# |
||||
# Start the commander. |
||||
# |
||||
commander start |
||||
|
||||
# |
||||
# Start the attitude estimator |
||||
# |
||||
attitude_estimator_ekf start |
||||
|
||||
echo "[init] starting PWM output" |
||||
fmu mode_pwm |
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix |
||||
|
||||
# |
||||
# Start attitude control |
||||
# |
||||
multirotor_att_control start |
||||
|
||||
echo "[init] startup done, exiting" |
||||
exit |
@ -0,0 +1,47 @@
@@ -0,0 +1,47 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (c) 2013 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. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/*
|
||||
* @file system_params.c |
||||
* |
||||
* System wide parameters |
||||
*/ |
||||
|
||||
#include <nuttx/config.h> |
||||
#include <systemlib/param/param.h> |
||||
|
||||
// Auto-start script with index #n
|
||||
PARAM_DEFINE_INT32(SYS_AUTOSTART, 0); |
||||
|
||||
// Automatically configure default values
|
||||
PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0); |
Loading…
Reference in new issue