diff options
Diffstat (limited to 'ROMFS')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d | 35 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rc.autostart | 5 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rc.fw_defaults | 2 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rc.logging | 2 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rc.usb | 10 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rcS | 20 |
6 files changed, 58 insertions, 16 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d new file mode 100644 index 000000000..6179855f6 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d @@ -0,0 +1,35 @@ +#!nsh +# +# Steadidrone QU4D +# +# Thomas Gubler <thomasgubler@gmail.com> +# Lorenz Meier <lm@inf.ethz.ch> +# + +sh /etc/init.d/rc.mc_defaults + +if [ $DO_AUTOCONFIG == yes ] +then + # TODO tune roll/pitch separately + param set MC_ROLL_P 7.0 + param set MC_ROLLRATE_P 0.13 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.004 + param set MC_PITCH_P 7.0 + param set MC_PITCHRATE_P 0.13 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.004 + param set MC_YAW_P 0.5 + param set MC_YAWRATE_P 0.2 + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_D 0.0 + + param set BAT_N_CELLS 4 +fi + +set MIXER FMU_quad_w + +set PWM_MIN 1210 +set PWM_MAX 2100 + +set PWM_OUTPUTS 1234 diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart index 5ec735d39..b365bd642 100644 --- a/ROMFS/px4fmu_common/init.d/rc.autostart +++ b/ROMFS/px4fmu_common/init.d/rc.autostart @@ -195,6 +195,11 @@ then sh /etc/init.d/10016_3dr_iris fi +if param compare SYS_AUTOSTART 10017 +then + sh /etc/init.d/10017_steadidrone_qu4d +fi + # # Hexa Coaxial # diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 4cd73e23f..3a50fcf56 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -11,6 +11,4 @@ then param set NAV_RTL_ALT 100 param set NAV_RTL_LAND_T -1 param set NAV_ACCEPT_RAD 50 - param set RC_SCALE_ROLL 1 - param set RC_SCALE_PITCH 1 fi
\ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging index 3469d5f5f..009e7431a 100644 --- a/ROMFS/px4fmu_common/init.d/rc.logging +++ b/ROMFS/px4fmu_common/init.d/rc.logging @@ -8,7 +8,7 @@ then if ver hwcmp PX4FMU_V1 then echo "Start sdlog2 at 50Hz" - sdlog2 start -r 50 -a -b 8 -t + sdlog2 start -r 50 -a -b 5 -t else echo "Start sdlog2 at 200Hz" sdlog2 start -r 200 -a -b 16 -t diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index b7b556945..76593881d 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -3,16 +3,20 @@ # USB MAVLink start # -echo "Starting MAVLink on this USB console" - mavlink start -r 10000 -d /dev/ttyACM0 # Enable a number of interesting streams we want via USB mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10 +usleep 100000 mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10 +usleep 100000 mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20 +usleep 100000 mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20 +usleep 100000 mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30 -mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 10 +usleep 100000 +mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20 +usleep 100000 # Exit shell to make it available to MAVLink exit diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 756ee8ef8..8c413e087 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -420,16 +420,6 @@ then mavlink start $MAVLINK_FLAGS # - # Start the datamanager - # - dataman start - - # - # Start the navigator - # - navigator start - - # # Sensors, Logging, GPS # sh /etc/init.d/rc.sensors @@ -551,6 +541,16 @@ then fi # + # Start the datamanager + # + dataman start + + # + # Start the navigator + # + navigator start + + # # Generic setup (autostart ID not found) # if [ $VEHICLE_TYPE == none ] |