forked from Archive/PX4-Autopilot
Merge pull request #338 from PX4/autostart
Implemented new, simple system boot config and sane default value system
This commit is contained in:
commit
a8ac56b9e5
|
@ -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
|
|
@ -1,8 +1,11 @@
|
|||
#!nsh
|
||||
#
|
||||
# Flight startup script for PX4FMU+PX4IO
|
||||
#
|
||||
|
||||
# Disable USB and autostart
|
||||
# disable USB and autostart
|
||||
set USB no
|
||||
set MODE quad
|
||||
set MODE custom
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
|
@ -18,6 +21,16 @@ 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
|
||||
|
@ -68,6 +81,11 @@ px4io start
|
|||
# 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
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
|
@ -87,21 +105,19 @@ attitude_estimator_ekf start
|
|||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
|
||||
pwm -u 400 -m 0xff
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
#sdlog start -s 4
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
echo "using BlinkM for state indication"
|
||||
blinkm systemstate
|
||||
else
|
||||
echo "no BlinkM found, OK."
|
||||
fi
|
||||
fi
|
|
@ -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
|
|
@ -1,8 +1,11 @@
|
|||
#!nsh
|
||||
#
|
||||
# Flight startup script for PX4FMU+PX4IO
|
||||
#
|
||||
|
||||
# Disable USB and autostart
|
||||
# disable USB and autostart
|
||||
set USB no
|
||||
set MODE camflyer
|
||||
set MODE custom
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
|
@ -18,6 +21,16 @@ 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
|
||||
|
@ -68,6 +81,10 @@ 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)
|
||||
|
@ -93,15 +110,12 @@ control_demo start
|
|||
#
|
||||
# Start logging
|
||||
#
|
||||
#sdlog start -s 4
|
||||
sdlog2 start -r 50 -a -b 14
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
echo "using BlinkM for state indication"
|
||||
blinkm systemstate
|
||||
else
|
||||
echo "no BlinkM found, OK."
|
||||
fi
|
|
@ -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 @@
|
|||
#!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
|
|
@ -82,3 +82,42 @@ else
|
|||
fi
|
||||
|
||||
fi
|
||||
|
||||
#
|
||||
# Check if auto-setup from one of the standard scripts is wanted
|
||||
# SYS_AUTOSTART = 0 means no autostart (default)
|
||||
#
|
||||
if param compare SYS_AUTOSTART 1
|
||||
then
|
||||
sh /etc/init.d/01_fmu_quad_x
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 2
|
||||
then
|
||||
sh /etc/init.d/02_io_quad_x
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 8
|
||||
then
|
||||
sh /etc/init.d/08_ardrone
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 9
|
||||
then
|
||||
sh /etc/init.d/09_ardrone_flow
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 10
|
||||
then
|
||||
sh /etc/init.d/10_io_f330
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 30
|
||||
then
|
||||
sh /etc/init.d/30_io_camflyer
|
||||
fi
|
||||
|
||||
if param compare SYS_AUTOSTART 31
|
||||
then
|
||||
sh /etc/init.d/31_io_phantom
|
||||
fi
|
||||
|
|
|
@ -41,16 +41,20 @@
|
|||
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
#include <stdarg.h>
|
||||
|
||||
#include <mavlink/mavlink_log.h>
|
||||
|
||||
static FILE* text_recorder_fd = NULL;
|
||||
|
||||
void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size)
|
||||
{
|
||||
lb->size = size;
|
||||
lb->start = 0;
|
||||
lb->count = 0;
|
||||
lb->elems = (struct mavlink_logmessage *)calloc(lb->size, sizeof(struct mavlink_logmessage));
|
||||
text_recorder_fd = fopen("/fs/microsd/text_recorder.txt", "w");
|
||||
}
|
||||
|
||||
int mavlink_logbuffer_is_full(struct mavlink_logbuffer *lb)
|
||||
|
@ -82,6 +86,13 @@ int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessa
|
|||
memcpy(elem, &(lb->elems[lb->start]), sizeof(struct mavlink_logmessage));
|
||||
lb->start = (lb->start + 1) % lb->size;
|
||||
--lb->count;
|
||||
|
||||
if (text_recorder_fd) {
|
||||
fwrite(elem->text, 1, strnlen(elem->text, 50), text_recorder_fd);
|
||||
fputc("\n", text_recorder_fd);
|
||||
fsync(text_recorder_fd);
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
||||
} else {
|
||||
|
|
|
@ -1483,7 +1483,7 @@ int sensors_main(int argc, char *argv[])
|
|||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (sensors::g_sensors != nullptr)
|
||||
errx(1, "sensors task already running");
|
||||
errx(0, "sensors task already running");
|
||||
|
||||
sensors::g_sensors = new Sensors;
|
||||
|
||||
|
|
|
@ -47,4 +47,5 @@ SRCS = err.c \
|
|||
pid/pid.c \
|
||||
geo/geo.c \
|
||||
systemlib.c \
|
||||
airspeed.c
|
||||
airspeed.c \
|
||||
system_params.c
|
||||
|
|
|
@ -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);
|
|
@ -63,6 +63,7 @@ static void do_import(const char* param_file_name);
|
|||
static void do_show(const char* search_string);
|
||||
static void do_show_print(void *arg, param_t param);
|
||||
static void do_set(const char* name, const char* val);
|
||||
static void do_compare(const char* name, const char* val);
|
||||
|
||||
int
|
||||
param_main(int argc, char *argv[])
|
||||
|
@ -117,9 +118,17 @@ param_main(int argc, char *argv[])
|
|||
errx(1, "not enough arguments.\nTry 'param set PARAM_NAME 3'");
|
||||
}
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "compare")) {
|
||||
if (argc >= 4) {
|
||||
do_compare(argv[2], argv[3]);
|
||||
} else {
|
||||
errx(1, "not enough arguments.\nTry 'param compare PARAM_NAME 3'");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
errx(1, "expected a command, try 'load', 'import', 'show', 'set', 'select' or 'save'");
|
||||
errx(1, "expected a command, try 'load', 'import', 'show', 'set', 'compare', 'select' or 'save'");
|
||||
}
|
||||
|
||||
static void
|
||||
|
@ -295,3 +304,65 @@ do_set(const char* name, const char* val)
|
|||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
static void
|
||||
do_compare(const char* name, const char* val)
|
||||
{
|
||||
int32_t i;
|
||||
float f;
|
||||
param_t param = param_find(name);
|
||||
|
||||
/* set nothing if parameter cannot be found */
|
||||
if (param == PARAM_INVALID) {
|
||||
/* param not found */
|
||||
errx(1, "Error: Parameter %s not found.", name);
|
||||
}
|
||||
|
||||
/*
|
||||
* Set parameter if type is known and conversion from string to value turns out fine
|
||||
*/
|
||||
|
||||
int ret = 1;
|
||||
|
||||
switch (param_type(param)) {
|
||||
case PARAM_TYPE_INT32:
|
||||
if (!param_get(param, &i)) {
|
||||
|
||||
/* convert string */
|
||||
char* end;
|
||||
int j = strtol(val,&end,10);
|
||||
if (i == j) {
|
||||
printf(" %d: ", i);
|
||||
ret = 0;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case PARAM_TYPE_FLOAT:
|
||||
if (!param_get(param, &f)) {
|
||||
|
||||
/* convert string */
|
||||
char* end;
|
||||
float g = strtod(val, &end);
|
||||
if (fabsf(f - g) < 1e-7f) {
|
||||
printf(" %4.4f: ", (double)f);
|
||||
ret = 0;
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
errx(1, "<unknown / unsupported type %d>\n", 0 + param_type(param));
|
||||
}
|
||||
|
||||
if (ret == 0) {
|
||||
printf("%c %s: equal\n",
|
||||
param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'),
|
||||
param_name(param));
|
||||
}
|
||||
|
||||
exit(ret);
|
||||
}
|
||||
|
|
|
@ -135,6 +135,7 @@ int preflight_check_main(int argc, char *argv[])
|
|||
|
||||
close(fd);
|
||||
fd = open(BARO_DEVICE_PATH, 0);
|
||||
close(fd);
|
||||
|
||||
/* ---- RC CALIBRATION ---- */
|
||||
|
||||
|
@ -251,6 +252,11 @@ system_eval:
|
|||
int buzzer = open("/dev/tone_alarm", O_WRONLY);
|
||||
int leds = open(LED_DEVICE_PATH, 0);
|
||||
|
||||
if (leds < 0) {
|
||||
close(buzzer);
|
||||
errx(1, "failed to open leds, aborting");
|
||||
}
|
||||
|
||||
/* flip blue led into alternating amber */
|
||||
led_off(leds, LED_BLUE);
|
||||
led_off(leds, LED_AMBER);
|
||||
|
|
Loading…
Reference in New Issue