diff options
-rw-r--r-- | ROMFS/Makefile | 2 | ||||
-rw-r--r-- | ROMFS/scripts/rc.hil | 57 | ||||
-rw-r--r-- | ROMFS/scripts/rc.usb | 14 | ||||
-rw-r--r-- | apps/drivers/boards/px4fmu/px4fmu_spi.c | 14 | ||||
-rw-r--r-- | apps/mavlink/mavlink.c | 3 | ||||
-rw-r--r-- | apps/px4io/controls.c | 2 | ||||
-rw-r--r-- | apps/sensors/sensors.cpp | 2 |
7 files changed, 84 insertions, 10 deletions
diff --git a/ROMFS/Makefile b/ROMFS/Makefile index 15167bf47..ed39ab825 100644 --- a/ROMFS/Makefile +++ b/ROMFS/Makefile @@ -22,6 +22,8 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \ $(SRCROOT)/scripts/rc.PX4IO~init.d/rc.PX4IO \ $(SRCROOT)/scripts/rc.PX4IOAR~init.d/rc.PX4IOAR \ $(SRCROOT)/scripts/rc.FMU_quad_x~init.d/rc.FMU_quad_x \ + $(SRCROOT)/scripts/rc.usb~init.d/rc.usb \ + $(SRCROOT)/scripts/rc.hil~init.d/rc.hil \ $(SRCROOT)/mixers/FMU_pass.mix~mixers/FMU_pass.mix \ $(SRCROOT)/mixers/FMU_Q.mix~mixers/FMU_Q.mix \ $(SRCROOT)/mixers/FMU_X5.mix~mixers/FMU_X5.mix \ diff --git a/ROMFS/scripts/rc.hil b/ROMFS/scripts/rc.hil new file mode 100644 index 000000000..3b37ac26b --- /dev/null +++ b/ROMFS/scripts/rc.hil @@ -0,0 +1,57 @@ +#!nsh +# +# USB HIL start +# + +echo "[HIL] starting.." + +uorb start + +# Tell MAVLink that this link is "fast" +mavlink start -b 230400 -d /dev/console + +# Create a fake HIL /dev/pwm_output interface +hil mode_pwm + +# +# Load microSD params +# +echo "[init] loading microSD params" +param select /fs/microsd/parameters +if [ -f /fs/microsd/parameters ] +then + param load /fs/microsd/parameters +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 + +# +# Start the commander (depends on orb, mavlink) +# +commander start + +# +# Start the sensors (depends on orb, px4io) +# +sh /etc/init.d/rc.sensors + +# +# 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_AET.mix +control_demo start + +echo "[HIL] setup done, running" + +# Exit shell to make it available to MAVLink +exit diff --git a/ROMFS/scripts/rc.usb b/ROMFS/scripts/rc.usb new file mode 100644 index 000000000..31af3991a --- /dev/null +++ b/ROMFS/scripts/rc.usb @@ -0,0 +1,14 @@ +#!nsh +# +# USB MAVLink start +# + +echo "Starting MAVLink on this USB console" + +# Tell MAVLink that this link is "fast" +mavlink start -b 230400 -d /dev/console + +echo "MAVLink started, exiting shell.." + +# Exit shell to make it available to MAVLink +exit diff --git a/apps/drivers/boards/px4fmu/px4fmu_spi.c b/apps/drivers/boards/px4fmu/px4fmu_spi.c index 70245a3ec..7a02eaeb7 100644 --- a/apps/drivers/boards/px4fmu/px4fmu_spi.c +++ b/apps/drivers/boards/px4fmu/px4fmu_spi.c @@ -92,21 +92,21 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, case PX4_SPIDEV_GYRO: /* Making sure the other peripherals are not selected */ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected); - stm32_gpiowrite(GPIO_SPI_CS_MPU, selected); - stm32_gpiowrite(GPIO_SPI_CS_ACCEL, selected); + stm32_gpiowrite(GPIO_SPI_CS_MPU, 1); + stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1); break; case PX4_SPIDEV_ACCEL: /* Making sure the other peripherals are not selected */ stm32_gpiowrite(GPIO_SPI_CS_ACCEL, !selected); - stm32_gpiowrite(GPIO_SPI_CS_MPU, selected); - stm32_gpiowrite(GPIO_SPI_CS_GYRO, selected); + stm32_gpiowrite(GPIO_SPI_CS_MPU, 1); + stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1); break; case PX4_SPIDEV_MPU: /* Making sure the other peripherals are not selected */ - stm32_gpiowrite(GPIO_SPI_CS_ACCEL, selected); - stm32_gpiowrite(GPIO_SPI_CS_GYRO, selected); + stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1); + stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1); stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected); break; @@ -125,7 +125,7 @@ __EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devi __EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) { /* there can only be one device on this bus, so always select it */ - stm32_gpiowrite(GPIO_SPI_CS_SDCARD, 0); + stm32_gpiowrite(GPIO_SPI_CS_SDCARD, !selected); } __EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c index b958d5f96..644b779af 100644 --- a/apps/mavlink/mavlink.c +++ b/apps/mavlink/mavlink.c @@ -442,7 +442,8 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf int termios_state; *is_usb = false; - if (strcmp(uart_name, "/dev/ttyACM0") != OK) { + /* make some wild guesses including that USB serial is indicated by either /dev/ttyACM0 or /dev/console */ + if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/console") != OK) { /* Back up the original uart configuration to restore it after exit */ if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { fprintf(stderr, "[mavlink] ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state); diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c index e80a41f15..dc36f6c93 100644 --- a/apps/px4io/controls.c +++ b/apps/px4io/controls.c @@ -177,7 +177,7 @@ controls_tick() { scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_MAX] - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])); } else if (raw < (conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])) { - scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE] - conf[PX4IO_P_RC_CONFIG_MIN])); + scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE] - conf[PX4IO_P_RC_CONFIG_MIN])); } else { /* in the configured dead zone, output zero */ diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index d725c7727..1f3f7707e 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -1157,7 +1157,7 @@ Sensors::ppm_poll() _rc.chan[i].scaled = (rc_input.values[i] - _parameters.trim[i] - _parameters.dz[i]) / (float)(_parameters.max[i] - _parameters.trim[i] - _parameters.dz[i]); } else if (rc_input.values[i] < (_parameters.trim[i] - _parameters.dz[i])) { - _rc.chan[i].scaled = (rc_input.values[i] - _parameters.trim[i] - _parameters.dz[i]) / (float)(_parameters.trim[i] - _parameters.min[i] - _parameters.dz[i]); + _rc.chan[i].scaled = (rc_input.values[i] - _parameters.trim[i] + _parameters.dz[i]) / (float)(_parameters.trim[i] - _parameters.min[i] - _parameters.dz[i]); } else { /* in the configured dead zone, output zero */ |