diff options
author | James Goppert <james.goppert@gmail.com> | 2013-10-22 05:04:13 -0400 |
---|---|---|
committer | James Goppert <james.goppert@gmail.com> | 2013-10-22 05:04:13 -0400 |
commit | 174c86321cad84589f597cfad1e5f7d6dd3c9136 (patch) | |
tree | 631d81a040125e781a88d18eee3d598de83f50da /ROMFS | |
parent | ce68f93867abfd3ea528809144f7c045d9bce544 (diff) | |
download | px4-firmware-174c86321cad84589f597cfad1e5f7d6dd3c9136.tar.gz px4-firmware-174c86321cad84589f597cfad1e5f7d6dd3c9136.tar.bz2 px4-firmware-174c86321cad84589f597cfad1e5f7d6dd3c9136.zip |
Roboclaw encoders/ dutycycledrive complete.
Diffstat (limited to 'ROMFS')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/40_io_segway | 16 | ||||
-rwxr-xr-x | ROMFS/px4fmu_common/init.d/rcS | 6 |
2 files changed, 14 insertions, 8 deletions
diff --git a/ROMFS/px4fmu_common/init.d/40_io_segway b/ROMFS/px4fmu_common/init.d/40_io_segway index 4b7ed5286..ffe7f695b 100644 --- a/ROMFS/px4fmu_common/init.d/40_io_segway +++ b/ROMFS/px4fmu_common/init.d/40_io_segway @@ -21,8 +21,8 @@ param set MAV_TYPE 10 # # Start MAVLink (depends on orb) # -mavlink start -d /dev/ttyS1 -b 57600 -usleep 5000 +#mavlink start -d /dev/ttyS1 -b 57600 +#usleep 5000 # # Start and configure PX4IO interface @@ -32,25 +32,25 @@ sh /etc/init.d/rc.io # # Start the commander (depends on orb, mavlink) # -commander start +#commander start # # Start the sensors (depends on orb, px4io) # -sh /etc/init.d/rc.sensors +#sh /etc/init.d/rc.sensors # # Start GPS interface (depends on orb) # -gps start +#gps start # # Start the attitude estimator (depends on orb) # -attitude_estimator_ekf start +#attitude_estimator_ekf start # # Load mixer and start controllers (depends on px4io) # -md25 start 3 0x58 -segway start +roboclaw test /dev/ttyS2 128 +#segway start diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index fd588017f..3a458286e 100755 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -272,6 +272,12 @@ then sh /etc/init.d/30_io_camflyer set MODE custom fi + + if param compare SYS_AUTOSTART 40 + then + sh /etc/init.d/40_io_segway + set MODE custom + fi if param compare SYS_AUTOSTART 31 then |