diff options
Diffstat (limited to 'ROMFS')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/4009_ardrone_flow | 5 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/4011_dji_f450 | 2 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/40_io_segway | 5 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/800_sdlogger | 2 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rc.hexa | 10 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/rc.octo | 10 |
6 files changed, 6 insertions, 28 deletions
diff --git a/ROMFS/px4fmu_common/init.d/4009_ardrone_flow b/ROMFS/px4fmu_common/init.d/4009_ardrone_flow index 9b739f245..2886bcb75 100644 --- a/ROMFS/px4fmu_common/init.d/4009_ardrone_flow +++ b/ROMFS/px4fmu_common/init.d/4009_ardrone_flow @@ -55,11 +55,6 @@ ardrone_interface start -d /dev/ttyS1 sh /etc/init.d/rc.sensors # -# Start the commander. -# -commander start - -# # Start the attitude estimator # attitude_estimator_ekf start diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450 index 84e48696a..a1d253191 100644 --- a/ROMFS/px4fmu_common/init.d/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450 @@ -41,8 +41,6 @@ then mavlink start usleep 5000 - commander start - sh /etc/init.d/rc.io else # Start MAVLink (on UART1 / ttyS0) diff --git a/ROMFS/px4fmu_common/init.d/40_io_segway b/ROMFS/px4fmu_common/init.d/40_io_segway index fb9dec043..ad455b440 100644 --- a/ROMFS/px4fmu_common/init.d/40_io_segway +++ b/ROMFS/px4fmu_common/init.d/40_io_segway @@ -28,11 +28,6 @@ usleep 5000 # Start and configure PX4IO interface # sh /etc/init.d/rc.io - -# -# Start the commander (depends on orb, mavlink) -# -commander start # # Start the sensors (depends on orb, px4io) diff --git a/ROMFS/px4fmu_common/init.d/800_sdlogger b/ROMFS/px4fmu_common/init.d/800_sdlogger index 1198b42cd..9b90cbdd0 100644 --- a/ROMFS/px4fmu_common/init.d/800_sdlogger +++ b/ROMFS/px4fmu_common/init.d/800_sdlogger @@ -22,8 +22,6 @@ then mavlink start usleep 5000 - commander start - sh /etc/init.d/rc.io # Set PWM values for DJI ESCs else diff --git a/ROMFS/px4fmu_common/init.d/rc.hexa b/ROMFS/px4fmu_common/init.d/rc.hexa index c49de3e0d..097db28e4 100644 --- a/ROMFS/px4fmu_common/init.d/rc.hexa +++ b/ROMFS/px4fmu_common/init.d/rc.hexa @@ -52,7 +52,7 @@ param set MAV_TYPE 13 set EXIT_ON_END no # -# Start and configure PX4IO or FMU interface +# Start and configure PX4IO interface # if px4io detect then @@ -62,12 +62,8 @@ then sh /etc/init.d/rc.io else - # Start MAVLink (on UART1 / ttyS0) - mavlink start -d /dev/ttyS0 - usleep 5000 - fmu mode_pwm - param set BAT_V_SCALING 0.004593 - set EXIT_ON_END yes + # This is not possible on a hexa + tone_alarm error fi # diff --git a/ROMFS/px4fmu_common/init.d/rc.octo b/ROMFS/px4fmu_common/init.d/rc.octo index 6adfa3071..ecb12e96e 100644 --- a/ROMFS/px4fmu_common/init.d/rc.octo +++ b/ROMFS/px4fmu_common/init.d/rc.octo @@ -52,7 +52,7 @@ param set MAV_TYPE 14 set EXIT_ON_END no # -# Start and configure PX4IO or FMU interface +# Start and configure PX4IO interface # if px4io detect then @@ -62,12 +62,8 @@ then sh /etc/init.d/rc.io else - # Start MAVLink (on UART1 / ttyS0) - mavlink start -d /dev/ttyS0 - usleep 5000 - fmu mode_pwm - param set BAT_V_SCALING 0.004593 - set EXIT_ON_END yes + # This is not possible on an octo + tone_alarm error fi # |