From ea70e967565a15ffc06aeb95df87f47440df97c1 Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Tue, 4 Mar 2014 16:16:39 +0100 Subject: [PATCH 1/9] Added ARDrone to autostart --- ROMFS/px4fmu_common/init.d/rc.autostart | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart index 3968af58ea..7aaf7133ef 100644 --- a/ROMFS/px4fmu_common/init.d/rc.autostart +++ b/ROMFS/px4fmu_common/init.d/rc.autostart @@ -106,6 +106,15 @@ then sh /etc/init.d/4001_quad_x fi +# +# ARDrone +# + +if param compare SYS_AUTOSTART 4008 8 +then + sh /etc/init.d/4008_ardrone +fi + if param compare SYS_AUTOSTART 4010 10 then sh /etc/init.d/4010_dji_f330 From 958f7597e7d13f82e41b9c8e0aa4c3ac552cdf1c Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Tue, 4 Mar 2014 16:33:18 +0100 Subject: [PATCH 2/9] Added actual ARDrone start up script. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 40 +++++++++++++++++++++++++ 1 file changed, 40 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d/4008_ardrone diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone new file mode 100644 index 0000000000..fa9b9d18a1 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -0,0 +1,40 @@ +#!nsh +# +# ARDrone +# + +# Just use the default multicopter settings. +sh /etc/init.d/rc.mc_defaults + +# +# Load default params for this platform +# +if param compare SYS_AUTOCONFIG 1 +then + # Set all params here, then disable autoconfig + param set MC_ATTRATE_D 0 + param set MC_ATTRATE_I 0 + param set MC_ATTRATE_P 0.13 + param set MC_ATT_D 0 + param set MC_ATT_I 0.3 + param set MC_ATT_P 5 + param set MC_YAWPOS_D 0.1 + param set MC_YAWPOS_I 0.15 + param set MC_YAWPOS_P 1 + param set MC_YAWRATE_D 0 + param set MC_YAWRATE_I 0 + param set MC_YAWRATE_P 0.15 + + param set SYS_AUTOCONFIG 0 + param save +fi + +set FMU_MODE gpio + +# +# Force some key parameters to sane values +# MAV_TYPE 2 = quadrotor +# +set MAV_TYPE 2 +set VEHICLE_TYPE mc +param set BAT_V_SCALING 0.008381 From 1d9d24f605aeb13b87efe2f6cf82232768b148ac Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Wed, 5 Mar 2014 10:50:16 +0100 Subject: [PATCH 3/9] Added flag for ARDrone interface. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 14 +++++--------- ROMFS/px4fmu_common/init.d/rcS | 12 +++++++++++- src/drivers/px4fmu/fmu.cpp | 2 +- 3 files changed, 17 insertions(+), 11 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index fa9b9d18a1..d6b2319f94 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -3,6 +3,8 @@ # ARDrone # +echo "[init] 4008_ardrone: PX4FMU on PX4IOAR carrier board" + # Just use the default multicopter settings. sh /etc/init.d/rc.mc_defaults @@ -29,12 +31,6 @@ then param save fi -set FMU_MODE gpio - -# -# Force some key parameters to sane values -# MAV_TYPE 2 = quadrotor -# -set MAV_TYPE 2 -set VEHICLE_TYPE mc -param set BAT_V_SCALING 0.008381 +set FMU_MODE gpio_serial +set OUTPUT_MODE fmu +set ARDRONE yes \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 76f021e339..af78162ed5 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -397,8 +397,10 @@ then set EXIT_ON_END yes else # Start MAVLink on default port: ttyS1 - mavlink start + mavlink start -d /dev/ttyS0 usleep 5000 + + set EXIT_ON_END yes fi fi @@ -427,6 +429,14 @@ then gps start fi + # + # Start up ARDrone Motor interface + # + if [ $ARDRONE == yes ] + then + ardrone_interface start -d /dev/ttyS1 + fi + # # Fixed wing setup # diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 0fbd849243..a70ff6c5c5 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -1714,7 +1714,7 @@ fmu_main(int argc, char *argv[]) } - fprintf(stderr, "FMU: unrecognised command, try:\n"); + fprintf(stderr, "FMU: unrecognised command %s, try:\n", verb); #if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n"); #elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) From 9ffa5a665a2ac8b887cbd9383eab1947137f0def Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Wed, 5 Mar 2014 10:56:58 +0100 Subject: [PATCH 4/9] Set the mavlink port settings back to ttyS1 by default. --- ROMFS/px4fmu_common/init.d/rcS | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index af78162ed5..1baac0eb3a 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -387,7 +387,7 @@ then mavlink start -b 230400 -d /dev/ttyACM0 usleep 5000 else - if [ $TTYS1_BUSY == yes ] + if [ $TTYS1_BUSY == yes -o $ARDRONE == yes] then # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else mavlink start -d /dev/ttyS0 @@ -397,10 +397,8 @@ then set EXIT_ON_END yes else # Start MAVLink on default port: ttyS1 - mavlink start -d /dev/ttyS0 + mavlink start usleep 5000 - - set EXIT_ON_END yes fi fi From 5976815f2baff6b17ca41dbb28e3e5698c12a180 Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Wed, 5 Mar 2014 15:07:05 +0100 Subject: [PATCH 5/9] Fixed startup parameters. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 29 ++++++++++++------------- ROMFS/px4fmu_common/init.d/rcS | 2 +- 2 files changed, 15 insertions(+), 16 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index d6b2319f94..d38796cca0 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -11,24 +11,23 @@ sh /etc/init.d/rc.mc_defaults # # Load default params for this platform # -if param compare SYS_AUTOCONFIG 1 +if [ $DO_AUTOCONFIG == yes ] then # Set all params here, then disable autoconfig - param set MC_ATTRATE_D 0 - param set MC_ATTRATE_I 0 - param set MC_ATTRATE_P 0.13 - param set MC_ATT_D 0 - param set MC_ATT_I 0.3 - param set MC_ATT_P 5 - param set MC_YAWPOS_D 0.1 - param set MC_YAWPOS_I 0.15 - param set MC_YAWPOS_P 1 - param set MC_YAWRATE_D 0 - param set MC_YAWRATE_I 0 + param set MC_ROLL_P 5.0 + param set MC_ROLLRATE_P 0.13 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.0 + param set MC_PITCH_P 5.0 + param set MC_PITCHRATE_P 0.13 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.0 + param set MC_YAW_P 1.0 + param set MC_YAW_D 0.1 param set MC_YAWRATE_P 0.15 - - param set SYS_AUTOCONFIG 0 - param save + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_D 0.0 + param set MC_YAW_FF 0.15 fi set FMU_MODE gpio_serial diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 1baac0eb3a..9983aa0e77 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -387,7 +387,7 @@ then mavlink start -b 230400 -d /dev/ttyACM0 usleep 5000 else - if [ $TTYS1_BUSY == yes -o $ARDRONE == yes] + if [ $TTYS1_BUSY == yes -o $ARDRONE == yes ] then # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else mavlink start -d /dev/ttyS0 From 30665816f0005cfb32b048a9ad4db84f78b3eff3 Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Wed, 5 Mar 2014 15:11:41 +0100 Subject: [PATCH 6/9] Added a newline at the end of file. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index d38796cca0..cb8260cccb 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -32,4 +32,4 @@ fi set FMU_MODE gpio_serial set OUTPUT_MODE fmu -set ARDRONE yes \ No newline at end of file +set ARDRONE yes From bcdc8c9e1dcefc2176fd1f853d4bae90e7d196d6 Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Wed, 5 Mar 2014 16:16:10 +0100 Subject: [PATCH 7/9] Get rid of one set of beeps. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 1 + 1 file changed, 1 insertion(+) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index cb8260cccb..512c4cb736 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -33,3 +33,4 @@ fi set FMU_MODE gpio_serial set OUTPUT_MODE fmu set ARDRONE yes +set USE_IO no From a897c97d955de4873aea1f01f65cab11faab2d3a Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Thu, 6 Mar 2014 12:45:10 +0100 Subject: [PATCH 8/9] Changed ARDRONE to an OUTPUT_MODE setting and added a skip option to mixer. Fewer beeps than before. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 5 ++--- ROMFS/px4fmu_common/init.d/rc.interface | 9 ++++++--- ROMFS/px4fmu_common/init.d/rcS | 13 +++++++++---- 3 files changed, 17 insertions(+), 10 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index 512c4cb736..39fe66234b 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -30,7 +30,6 @@ then param set MC_YAW_FF 0.15 fi -set FMU_MODE gpio_serial -set OUTPUT_MODE fmu -set ARDRONE yes +set OUTPUT_MODE ardrone set USE_IO no +set MIXER skip \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index d25f01dde0..afe71460de 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -3,7 +3,7 @@ # Script to configure control interface # -if [ $MIXER != none ] +if [ $MIXER != none -a $MIXER != skip] then # # Load mixer @@ -33,8 +33,11 @@ then tone_alarm $TUNE_OUT_ERROR fi else - echo "[init] Mixer not defined" - tone_alarm $TUNE_OUT_ERROR + if [ $MIXER != skip ] + then + echo "[init] Mixer not defined" + tone_alarm $TUNE_OUT_ERROR + fi fi if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ] diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 9983aa0e77..7b9ae09955 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -240,6 +240,11 @@ then fi fi + if [ $OUTPUT_MODE == ardrone ] + then + set FMU_MODE gpio_serial + fi + if [ $HIL == yes ] then set OUTPUT_MODE hil @@ -277,7 +282,7 @@ then tone_alarm $TUNE_OUT_ERROR fi fi - if [ $OUTPUT_MODE == fmu ] + if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE = ardrone ] then echo "[init] Use FMU PWM as primary output" if fmu mode_$FMU_MODE @@ -351,7 +356,7 @@ then fi fi else - if [ $OUTPUT_MODE != fmu ] + if [ $OUTPUT_MODE != fmu -a $OUTPUT_MODE != ardrone ] then if fmu mode_$FMU_MODE then @@ -387,7 +392,7 @@ then mavlink start -b 230400 -d /dev/ttyACM0 usleep 5000 else - if [ $TTYS1_BUSY == yes -o $ARDRONE == yes ] + if [ $TTYS1_BUSY == yes -o $OUTPUT_MODE == ardrone ] then # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else mavlink start -d /dev/ttyS0 @@ -430,7 +435,7 @@ then # # Start up ARDrone Motor interface # - if [ $ARDRONE == yes ] + if [ $OUTPUT_MODE == ardrone ] then ardrone_interface start -d /dev/ttyS1 fi From 25faf1b8f8716323233d6f966aac65e0c9e8d61a Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 6 Mar 2014 17:44:10 +0400 Subject: [PATCH 9/9] ardrone: minor fixes --- ROMFS/px4fmu_common/init.d/4008_ardrone | 2 +- ROMFS/px4fmu_common/init.d/rcS | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index 39fe66234b..0f98f7b6c2 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -32,4 +32,4 @@ fi set OUTPUT_MODE ardrone set USE_IO no -set MIXER skip \ No newline at end of file +set MIXER skip diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 7b9ae09955..b1cd919f72 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -284,7 +284,7 @@ then fi if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE = ardrone ] then - echo "[init] Use FMU PWM as primary output" + echo "[init] Use FMU as primary output" if fmu mode_$FMU_MODE then echo "[init] FMU mode_$FMU_MODE started" @@ -299,7 +299,7 @@ then then set TTYS1_BUSY yes fi - if [ $FMU_MODE == pwm_gpio ] + if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ] then set TTYS1_BUSY yes fi @@ -372,7 +372,7 @@ then then set TTYS1_BUSY yes fi - if [ $FMU_MODE == pwm_gpio ] + if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ] then set TTYS1_BUSY yes fi @@ -392,7 +392,7 @@ then mavlink start -b 230400 -d /dev/ttyACM0 usleep 5000 else - if [ $TTYS1_BUSY == yes -o $OUTPUT_MODE == ardrone ] + if [ $TTYS1_BUSY == yes ] then # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else mavlink start -d /dev/ttyS0