aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authormazahner <mazahner@student.ethz.ch>2014-11-10 17:39:04 +0100
committermazahner <mazahner@student.ethz.ch>2014-11-10 17:39:04 +0100
commit6ec08335459457c82158d2df06050bd30fb8cc59 (patch)
tree3d5407b6bc88533eacedb3bebfc9e0c9b23609ea
parentd15203de91cc07530809060f949374bb8918daea (diff)
parent4e8e6e653beb21808f532b83c6c6e827103ea379 (diff)
downloadpx4-firmware-6ec08335459457c82158d2df06050bd30fb8cc59.tar.gz
px4-firmware-6ec08335459457c82158d2df06050bd30fb8cc59.tar.bz2
px4-firmware-6ec08335459457c82158d2df06050bd30fb8cc59.zip
Merge branch 'master' of https://github.com/mazahner/Firmware
-rw-r--r--LICENSE.md41
m---------NuttX0
-rw-r--r--README.md10
-rw-r--r--ROMFS/px4fmu_common/init.d/10015_tbs_discovery1
-rw-r--r--ROMFS/px4fmu_common/init.d/3031_phantom3
-rw-r--r--ROMFS/px4fmu_common/init.d/3035_viper11
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart11
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_apps2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.interface5
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.sensors5
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.uavcan18
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb4
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS34
-rw-r--r--ROMFS/px4fmu_common/mixers/FMU_AERT.mix11
-rwxr-xr-xROMFS/px4fmu_common/mixers/FMU_FX79.mix17
-rwxr-xr-xROMFS/px4fmu_common/mixers/Viper.mix71
-rw-r--r--ROMFS/px4fmu_test/init.d/rcS30
-rw-r--r--ROMFS/px4fmu_test/unit_test_data/mavlink_tests/empty_dir/.gitignore0
-rw-r--r--ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_238.databin0 -> 238 bytes
-rw-r--r--ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_239.databin0 -> 239 bytes
-rw-r--r--ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_240.databin0 -> 240 bytes
-rw-r--r--Tools/px_romfs_pruner.py2
-rwxr-xr-xTools/px_uploader.py6
-rwxr-xr-x[-rw-r--r--]Tools/sdlog2/sdlog2_dump.py4
-rw-r--r--Tools/tests-host/.gitignore2
-rw-r--r--Tools/tests-host/Makefile21
-rw-r--r--Tools/tests-host/sbus2_test.cpp3
-rw-r--r--Tools/tests-host/sf0x_test.cpp65
-rw-r--r--Tools/tests-host/st24_test.cpp76
-rwxr-xr-xTools/upload.sh28
-rw-r--r--Tools/usb_serialload.py55
-rw-r--r--makefiles/config_px4fmu-v1_default.mk16
-rw-r--r--makefiles/config_px4fmu-v2_default.mk6
-rw-r--r--makefiles/config_px4fmu-v2_test.mk4
m---------mavlink/include/mavlink/v1.00
-rw-r--r--nuttx-configs/aerocore/nsh/defconfig2
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/defconfig3
-rw-r--r--nuttx-configs/px4fmu-v2/nsh/defconfig5
-rwxr-xr-xnuttx-configs/px4io-v1/nsh/defconfig3
-rwxr-xr-xnuttx-configs/px4io-v2/nsh/defconfig1
-rw-r--r--src/drivers/airspeed/airspeed.cpp7
-rw-r--r--src/drivers/boards/aerocore/aerocore_init.c13
-rw-r--r--src/drivers/boards/aerocore/board_config.h19
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h21
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h21
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_init.c13
-rw-r--r--src/drivers/boards/px4io-v2/board_config.h1
-rw-r--r--src/drivers/boards/px4io-v2/px4iov2_init.c1
-rw-r--r--src/drivers/device/device.cpp1
-rw-r--r--src/drivers/drv_gps.h3
-rw-r--r--src/drivers/drv_pwm_output.h17
-rw-r--r--src/drivers/drv_px4flow.h31
-rw-r--r--src/drivers/drv_rc_input.h3
-rw-r--r--src/drivers/drv_tone_alarm.h1
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp20
-rw-r--r--src/drivers/gps/ashtech.cpp641
-rw-r--r--src/drivers/gps/ashtech.h96
-rw-r--r--src/drivers/gps/gps.cpp17
-rw-r--r--src/drivers/gps/module.mk1
-rw-r--r--src/drivers/gps/ubx.cpp12
-rw-r--r--src/drivers/gps/ubx.h17
-rw-r--r--src/drivers/hil/hil.cpp3
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp52
-rw-r--r--src/drivers/hott/messages.cpp14
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp9
-rw-r--r--src/drivers/ll40ls/ll40ls.cpp248
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp6
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp39
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp6
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp28
-rw-r--r--src/drivers/ms5611/ms5611.cpp4
-rw-r--r--src/drivers/pca9685/arduino_Adafruit_PWM_Servo_Driver_Library_license.txt29
-rw-r--r--src/drivers/pca9685/module.mk42
-rw-r--r--src/drivers/pca9685/pca9685.cpp651
-rw-r--r--src/drivers/px4flow/px4flow.cpp245
-rw-r--r--src/drivers/px4fmu/fmu.cpp5
-rw-r--r--src/drivers/px4io/px4io.cpp109
-rw-r--r--src/drivers/sf0x/module.mk3
-rw-r--r--src/drivers/sf0x/sf0x.cpp105
-rw-r--r--src/drivers/sf0x/sf0x_parser.cpp155
-rw-r--r--src/drivers/sf0x/sf0x_parser.h51
-rw-r--r--src/drivers/stm32/tone_alarm/tone_alarm.cpp2
-rw-r--r--src/lib/conversion/module.mk2
-rw-r--r--src/lib/conversion/rotation.h4
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp6
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp6
-rw-r--r--src/lib/external_lgpl/tecs/tecs.cpp62
-rw-r--r--src/lib/external_lgpl/tecs/tecs.h93
-rw-r--r--src/lib/geo/geo.c218
-rw-r--r--src/lib/geo/geo.h141
-rw-r--r--src/lib/launchdetection/CatapultLaunchMethod.cpp70
-rw-r--r--src/lib/launchdetection/CatapultLaunchMethod.h15
-rw-r--r--src/lib/launchdetection/LaunchDetector.cpp47
-rw-r--r--src/lib/launchdetection/LaunchDetector.h11
-rw-r--r--src/lib/launchdetection/LaunchMethod.h16
-rw-r--r--src/lib/launchdetection/launchdetection_params.c25
-rw-r--r--src/lib/rc/module.mk40
-rw-r--r--src/lib/rc/st24.c253
-rw-r--r--src/lib/rc/st24.h163
-rw-r--r--src/modules/bottle_drop/bottle_drop.cpp907
-rw-r--r--src/modules/bottle_drop/bottle_drop_params.c131
-rw-r--r--src/modules/bottle_drop/module.mk41
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp44
-rw-r--r--src/modules/commander/airspeed_calibration.cpp39
-rw-r--r--src/modules/commander/commander.cpp488
-rw-r--r--src/modules/commander/commander_params.c66
-rw-r--r--src/modules/commander/commander_tests/commander_tests.cpp4
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp23
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.h2
-rw-r--r--src/modules/commander/gyro_calibration.cpp5
-rw-r--r--src/modules/commander/mag_calibration.cpp2
-rw-r--r--src/modules/commander/state_machine_helper.cpp87
-rw-r--r--src/modules/commander/state_machine_helper.h4
-rw-r--r--src/modules/dataman/dataman.c2
-rw-r--r--src/modules/dataman/module.mk2
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp100
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_23states.cpp858
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_23states.h61
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp69
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp399
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c222
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/mTecs.cpp7
-rw-r--r--src/modules/gpio_led/module.mk2
-rw-r--r--src/modules/mavlink/mavlink.c13
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp734
-rw-r--r--src/modules/mavlink/mavlink_ftp.h294
-rw-r--r--src/modules/mavlink/mavlink_main.cpp130
-rw-r--r--src/modules/mavlink/mavlink_main.h12
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp266
-rw-r--r--src/modules/mavlink/mavlink_mission.cpp25
-rw-r--r--src/modules/mavlink/mavlink_mission.h2
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp482
-rw-r--r--src/modules/mavlink/mavlink_receiver.h13
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp761
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h108
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py7
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_tests.cpp47
-rw-r--r--src/modules/mavlink/mavlink_tests/module.mk50
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp535
-rw-r--r--src/modules/navigator/datalinkloss.cpp227
-rw-r--r--src/modules/navigator/datalinkloss.h98
-rw-r--r--src/modules/navigator/datalinkloss_params.c126
-rw-r--r--src/modules/navigator/enginefailure.cpp149
-rw-r--r--src/modules/navigator/enginefailure.h (renamed from src/modules/navigator/offboard.h)41
-rw-r--r--src/modules/navigator/geofence.cpp66
-rw-r--r--src/modules/navigator/geofence.h63
-rw-r--r--src/modules/navigator/geofence_params.c36
-rw-r--r--src/modules/navigator/gpsfailure.cpp178
-rw-r--r--src/modules/navigator/gpsfailure.h97
-rw-r--r--src/modules/navigator/gpsfailure_params.c97
-rw-r--r--src/modules/navigator/mission.cpp223
-rw-r--r--src/modules/navigator/mission.h50
-rw-r--r--src/modules/navigator/mission_block.cpp13
-rw-r--r--src/modules/navigator/mission_feasibility_checker.cpp22
-rw-r--r--src/modules/navigator/mission_params.c17
-rw-r--r--src/modules/navigator/module.mk12
-rw-r--r--src/modules/navigator/navigator.h63
-rw-r--r--src/modules/navigator/navigator_main.cpp150
-rw-r--r--src/modules/navigator/navigator_mode.cpp5
-rw-r--r--src/modules/navigator/navigator_params.c54
-rw-r--r--src/modules/navigator/offboard.cpp129
-rw-r--r--src/modules/navigator/rcloss.cpp182
-rw-r--r--src/modules/navigator/rcloss.h88
-rw-r--r--src/modules/navigator/rcloss_params.c60
-rw-r--r--src/modules/navigator/rtl.cpp6
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c124
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c57
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h19
-rw-r--r--src/modules/px4iofirmware/controls.c79
-rw-r--r--src/modules/px4iofirmware/dsm.c10
-rw-r--r--src/modules/px4iofirmware/mixer.cpp69
-rw-r--r--src/modules/px4iofirmware/module.mk3
-rw-r--r--src/modules/px4iofirmware/protocol.h7
-rw-r--r--src/modules/px4iofirmware/px4io.c6
-rw-r--r--src/modules/px4iofirmware/px4io.h3
-rw-r--r--src/modules/px4iofirmware/registers.c31
-rw-r--r--src/modules/px4iofirmware/sbus.c95
-rw-r--r--src/modules/sdlog2/sdlog2.c72
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h49
-rw-r--r--src/modules/sensors/sensor_params.c10
-rw-r--r--src/modules/sensors/sensors.cpp67
-rw-r--r--src/modules/systemlib/circuit_breaker.c41
-rw-r--r--src/modules/systemlib/circuit_breaker.h3
-rw-r--r--src/modules/systemlib/mixer/mixer.h6
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp22
-rw-r--r--src/modules/systemlib/param/param.c3
-rw-r--r--src/modules/systemlib/param/param.h2
-rw-r--r--src/modules/uORB/objects_common.cpp9
-rw-r--r--src/modules/uORB/topics/differential_pressure.h1
-rw-r--r--src/modules/uORB/topics/esc_status.h19
-rw-r--r--src/modules/uORB/topics/mission_result.h7
-rw-r--r--src/modules/uORB/topics/multirotor_motor_limits.h69
-rw-r--r--src/modules/uORB/topics/offboard_control_setpoint.h201
-rw-r--r--src/modules/uORB/topics/position_setpoint_triplet.h15
-rw-r--r--src/modules/uORB/topics/rc_channels.h10
-rw-r--r--src/modules/uORB/topics/tecs_status.h12
-rw-r--r--src/modules/uORB/topics/telemetry_status.h2
-rw-r--r--src/modules/uORB/topics/test_motor.h70
-rw-r--r--src/modules/uORB/topics/vehicle_command.h22
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h1
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h2
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h2
-rw-r--r--src/modules/uORB/topics/vehicle_local_position_setpoint.h3
-rw-r--r--src/modules/uORB/topics/vehicle_status.h18
-rw-r--r--src/modules/uORB/topics/vision_position_estimate.h82
-rw-r--r--src/modules/uavcan/actuators/esc.cpp (renamed from src/modules/uavcan/esc_controller.cpp)48
-rw-r--r--src/modules/uavcan/actuators/esc.hpp (renamed from src/modules/uavcan/esc_controller.hpp)19
-rw-r--r--src/modules/uavcan/module.mk21
-rw-r--r--src/modules/uavcan/sensors/baro.cpp117
-rw-r--r--src/modules/uavcan/sensors/baro.hpp68
-rw-r--r--src/modules/uavcan/sensors/gnss.cpp (renamed from src/modules/uavcan/gnss_receiver.cpp)100
-rw-r--r--src/modules/uavcan/sensors/gnss.hpp (renamed from src/modules/uavcan/gnss_receiver.hpp)37
-rw-r--r--src/modules/uavcan/sensors/mag.cpp123
-rw-r--r--src/modules/uavcan/sensors/mag.hpp68
-rw-r--r--src/modules/uavcan/sensors/sensor_bridge.cpp158
-rw-r--r--src/modules/uavcan/sensors/sensor_bridge.hpp131
-rw-r--r--src/modules/uavcan/uavcan_clock.cpp2
-rw-r--r--src/modules/uavcan/uavcan_main.cpp226
-rw-r--r--src/modules/uavcan/uavcan_main.hpp18
-rw-r--r--src/modules/uavcan/uavcan_params.c73
-rw-r--r--src/modules/unit_test/module.mk1
-rw-r--r--src/modules/unit_test/unit_test.cpp27
-rw-r--r--src/modules/unit_test/unit_test.h111
-rw-r--r--src/systemcmds/esc_calib/module.mk2
-rw-r--r--src/systemcmds/motor_test/module.mk41
-rw-r--r--src/systemcmds/motor_test/motor_test.c128
-rw-r--r--src/systemcmds/mtd/24xxxx_mtd.c15
-rw-r--r--src/systemcmds/mtd/module.mk2
-rw-r--r--src/systemcmds/nshterm/module.mk6
-rw-r--r--src/systemcmds/nshterm/nshterm.c4
-rw-r--r--src/systemcmds/pwm/module.mk2
-rw-r--r--src/systemcmds/pwm/pwm.c21
-rw-r--r--src/systemcmds/tests/test_sensors.c2
-rw-r--r--src/systemcmds/tests/tests_main.c2
m---------uavcan0
235 files changed, 13935 insertions, 2767 deletions
diff --git a/LICENSE.md b/LICENSE.md
new file mode 100644
index 000000000..2ad83eba4
--- /dev/null
+++ b/LICENSE.md
@@ -0,0 +1,41 @@
+The PX4 firmware is licensed generally under a permissive 3-clause BSD license. Contributions are required
+to be made under the same license. Any exception to this general rule is listed below.
+
+ /****************************************************************************
+ *
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+
+ - PX4 middleware: BSD 3-clause
+ - PX4 flight control stack: BSD 3-clause
+ - NuttX operating system: BSD 3-clause
+ - Exceptions: Currently only this [400 LOC file](https://github.com/PX4/Firmware/blob/master/src/lib/external_lgpl/tecs/tecs.cpp) remains LGPL, but will be replaced with a BSD implementation. \ No newline at end of file
diff --git a/NuttX b/NuttX
-Subproject 088146b90eee5b614ea6386a64dae343a49a517
+Subproject 5ee4b2b2c26bbc35d1669840f0676e8aa383b98
diff --git a/README.md b/README.md
new file mode 100644
index 000000000..84fb02e3b
--- /dev/null
+++ b/README.md
@@ -0,0 +1,10 @@
+## PX4 Aerial Middleware and Flight Control Stack ##
+
+* Official Website: http://px4.io
+* License: BSD 3-clause (see LICENSE.md)
+* Supported airframes:
+ * Multicopters
+ * Fixed wing
+* Binaries (always up-to-date from master):
+ * [Downloads](https://pixhawk.org/downloads)
+* Mailing list: [Google Groups](http://groups.google.com/group/px4users)
diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
index c4be16943..b1aa8c00b 100644
--- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
@@ -27,3 +27,4 @@ fi
set MIXER FMU_quad_w
set PWM_OUTPUTS 1234
+set PWM_MIN 1200
diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom
index 31dfe7100..53c48d8aa 100644
--- a/ROMFS/px4fmu_common/init.d/3031_phantom
+++ b/ROMFS/px4fmu_common/init.d/3031_phantom
@@ -30,6 +30,9 @@ then
param set FW_RR_P 0.08
param set FW_R_LIM 50
param set FW_R_RMAX 0
+ # Bottom of bay and nominal zero-pitch attitude differ
+ # the payload bay is pitched up about 7 degrees
+ param set SENS_BOARD_Y_OFF 7.0
fi
set MIXER phantom
diff --git a/ROMFS/px4fmu_common/init.d/3035_viper b/ROMFS/px4fmu_common/init.d/3035_viper
new file mode 100644
index 000000000..f3b0e8418
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/3035_viper
@@ -0,0 +1,11 @@
+#!nsh
+#
+# Viper
+#
+# Simon Wilks <sjwilks@gmail.com>
+#
+
+sh /etc/init.d/rc.fw_defaults
+
+set MIXER Viper
+
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index 17541e680..78778d806 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -21,6 +21,12 @@
# Simulation setups
#
+if param compare SYS_AUTOSTART 901
+then
+ sh /etc/init.d/901_bottle_drop_test.hil
+ set MODE custom
+fi
+
if param compare SYS_AUTOSTART 1000
then
sh /etc/init.d/1000_rc_fw_easystar.hil
@@ -103,6 +109,11 @@ then
sh /etc/init.d/3034_fx79
fi
+if param compare SYS_AUTOSTART 3035 35
+then
+ sh /etc/init.d/3035_viper
+fi
+
if param compare SYS_AUTOSTART 3100
then
sh /etc/init.d/3100_tbs_caipirinha
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps
index 9aca3fc5f..c97b3477f 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_apps
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps
@@ -13,3 +13,5 @@ ekf_att_pos_estimator start
#
fw_att_control start
fw_pos_control_l1 start
+
+bottle_drop start
diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface
index 1de0abb58..e44cd0953 100644
--- a/ROMFS/px4fmu_common/init.d/rc.interface
+++ b/ROMFS/px4fmu_common/init.d/rc.interface
@@ -77,4 +77,9 @@ then
pwm max -c $PWM_OUTPUTS -p $PWM_MAX
fi
fi
+
+ if [ $FAILSAFE != none ]
+ then
+ pwm failsafe -d $OUTPUT_DEV $FAILSAFE
+ fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index ecb408a54..739df7ac0 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -68,6 +68,11 @@ else
fi
fi
+# Check for flow sensor
+if px4flow start
+then
+fi
+
#
# Start the sensor collection task.
# IMPORTANT: this also loads param offsets
diff --git a/ROMFS/px4fmu_common/init.d/rc.uavcan b/ROMFS/px4fmu_common/init.d/rc.uavcan
new file mode 100644
index 000000000..9a470a6b8
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.uavcan
@@ -0,0 +1,18 @@
+#!nsh
+#
+# UAVCAN initialization script.
+#
+
+if param compare UAVCAN_ENABLE 1
+then
+ if uavcan start
+ then
+ # First sensor publisher to initialize takes lowest instance ID
+ # This delay ensures that UAVCAN-interfaced sensors would be allocated on lowest instance IDs
+ sleep 1
+ echo "[init] UAVCAN started"
+ else
+ echo "[init] ERROR: Could not start UAVCAN"
+ tone_alarm $TUNE_OUT_ERROR
+ fi
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index eb6039b4c..ee040a706 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -3,7 +3,7 @@
# USB MAVLink start
#
-mavlink start -r 10000 -d /dev/ttyACM0 -x
+mavlink start -r 20000 -d /dev/ttyACM0 -x
# Enable a number of interesting streams we want via USB
mavlink stream -d /dev/ttyACM0 -s PARAM_VALUE -r 200
usleep 100000
@@ -23,7 +23,7 @@ mavlink stream -d /dev/ttyACM0 -s RC_CHANNELS_RAW -r 5
usleep 100000
mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
usleep 100000
-mavlink stream -d /dev/ttyACM0 -s GLOBAL_POSITION_SETPOINT_INT -r 20
+mavlink stream -d /dev/ttyACM0 -s POSITION_TARGET_GLOBAL_INT -r 10
usleep 100000
# Exit shell to make it available to MAVLink
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 24b2a299a..ea04ece34 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -66,6 +66,9 @@ then
#
sercon
+ # Try to get an USB console
+ nshterm /dev/ttyACM0 &
+
#
# Start the ORB (first app to start)
#
@@ -83,9 +86,12 @@ then
param select $PARAM_FILE
if param load
then
- echo "[init] Params loaded: $PARAM_FILE"
+ echo "[param] Loaded: $PARAM_FILE"
else
- echo "[init] ERROR: Params loading failed: $PARAM_FILE"
+ echo "[param] FAILED loading $PARAM_FILE"
+ if param reset
+ then
+ fi
fi
#
@@ -93,11 +99,9 @@ then
#
if rgbled start
then
- echo "[init] RGB Led"
else
if blinkm start
then
- echo "[init] BlinkM"
blinkm systemstate
fi
fi
@@ -126,6 +130,7 @@ then
set LOAD_DEFAULT_APPS yes
set GPS yes
set GPS_FAKE no
+ set FAILSAFE none
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
@@ -276,13 +281,12 @@ then
fi
fi
- # Try to get an USB console
- nshterm /dev/ttyACM0 &
-
#
- # Start the datamanager
+ # Start the datamanager (and do not abort boot if it fails)
#
- dataman start
+ if dataman start
+ then
+ fi
#
# Start the Commander (needs to be this early for in-air-restarts)
@@ -299,11 +303,10 @@ then
then
if [ $OUTPUT_MODE == uavcan_esc ]
then
- if uavcan start 1
+ if param compare UAVCAN_ENABLE 0
then
- echo "CAN UP"
- else
- echo "CAN ERR"
+ echo "[init] OVERRIDING UAVCAN_ENABLE = 1"
+ param set UAVCAN_ENABLE 1
fi
fi
@@ -443,6 +446,11 @@ then
mavlink start $MAVLINK_FLAGS
#
+ # UAVCAN
+ #
+ sh /etc/init.d/rc.uavcan
+
+ #
# Sensors, Logging, GPS
#
sh /etc/init.d/rc.sensors
diff --git a/ROMFS/px4fmu_common/mixers/FMU_AERT.mix b/ROMFS/px4fmu_common/mixers/FMU_AERT.mix
index 0ec663e35..7fed488af 100644
--- a/ROMFS/px4fmu_common/mixers/FMU_AERT.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_AERT.mix
@@ -64,21 +64,22 @@ O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
-Gimbal / flaps / payload mixer for last four channels
+Gimbal / flaps / payload mixer for last four channels,
+using the payload control group
-----------------------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 4 10000 10000 0 -10000 10000
+S: 2 0 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 5 10000 10000 0 -10000 10000
+S: 2 1 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 6 10000 10000 0 -10000 10000
+S: 2 2 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 7 10000 10000 0 -10000 10000
+S: 2 3 10000 10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/FMU_FX79.mix b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix
index 0a1dca98d..b8879af9e 100755
--- a/ROMFS/px4fmu_common/mixers/FMU_FX79.mix
+++ b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix
@@ -27,12 +27,12 @@ for the elevons.
M: 2
O: 10000 10000 0 -10000 10000
-S: 0 0 5000 8000 0 -10000 10000
+S: 0 0 7500 7500 0 -10000 10000
S: 0 1 8000 8000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
-S: 0 0 8000 5000 0 -10000 10000
+S: 0 0 7500 7500 0 -10000 10000
S: 0 1 -8000 -8000 0 -10000 10000
Output 2
@@ -52,21 +52,18 @@ M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
-Gimbal / flaps / payload mixer for last four channels
+Inputs to the mixer come from channel group 2 (payload), channels 0
+(bay servo 1), 1 (bay servo 2) and 3 (drop release).
-----------------------------------------------------
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 4 10000 10000 0 -10000 10000
+S: 2 0 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 5 10000 10000 0 -10000 10000
+S: 2 1 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
-S: 0 6 10000 10000 0 -10000 10000
-
-M: 1
-O: 10000 10000 0 -10000 10000
-S: 0 7 10000 10000 0 -10000 10000
+S: 2 2 -10000 -10000 0 -10000 10000
diff --git a/ROMFS/px4fmu_common/mixers/Viper.mix b/ROMFS/px4fmu_common/mixers/Viper.mix
new file mode 100755
index 000000000..5aa3828f2
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/Viper.mix
@@ -0,0 +1,71 @@
+Viper Delta-wing mixer
+=================================
+
+Designed for Viper.
+
+TODO (sjwilks): Add mixers for flaps.
+
+This file defines mixers suitable for controlling a delta wing aircraft using
+PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
+servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
+assumed to be unused.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+See the README for more information on the scaler format.
+
+Elevon mixers
+-------------
+Three scalers total (output, roll, pitch).
+
+On the assumption that the two elevon servos are physically reversed, the pitch
+input is inverted between the two servos.
+
+The scaling factor for roll inputs is adjusted to implement differential travel
+for the elevons.
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 7500 7500 0 -10000 10000
+S: 0 1 8000 8000 0 -10000 10000
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 7500 7500 0 -10000 10000
+S: 0 1 -8000 -8000 0 -10000 10000
+
+Output 2
+--------
+This mixer is empty.
+
+Z:
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
+
+Inputs to the mixer come from channel group 2 (payload), channels 0
+(bay servo 1), 1 (bay servo 2) and 3 (drop release).
+-----------------------------------------------------
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 2 0 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 2 1 10000 10000 0 -10000 10000
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 2 2 -8000 -8000 0 -10000 10000
+
+
diff --git a/ROMFS/px4fmu_test/init.d/rcS b/ROMFS/px4fmu_test/init.d/rcS
index 56482d140..bc248ac04 100644
--- a/ROMFS/px4fmu_test/init.d/rcS
+++ b/ROMFS/px4fmu_test/init.d/rcS
@@ -75,3 +75,33 @@ if [ -f /fs/microsd/mount_test_cmds.txt ]
then
tests mount
fi
+
+#
+# Run unit tests at board boot, reporting failure as needed.
+# Add new unit tests using the same pattern as below.
+#
+
+set unit_test_failure 0
+
+if mavlink_tests
+then
+else
+ set unit_test_failure 1
+ set unit_test_failure_list "${unit_test_failure_list} mavlink_tests"
+fi
+
+if commander_tests
+then
+else
+ set unit_test_failure 1
+ set unit_test_failure_list "${unit_test_failure_list} commander_tests"
+fi
+
+if [ $unit_test_failure == 0 ]
+then
+ echo
+ echo "All Unit Tests PASSED"
+else
+ echo
+ echo "Some Unit Tests FAILED:${unit_test_failure_list}"
+fi \ No newline at end of file
diff --git a/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/empty_dir/.gitignore b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/empty_dir/.gitignore
new file mode 100644
index 000000000..e69de29bb
--- /dev/null
+++ b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/empty_dir/.gitignore
diff --git a/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_238.data b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_238.data
new file mode 100644
index 000000000..973de16e5
--- /dev/null
+++ b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_238.data
Binary files differ
diff --git a/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_239.data b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_239.data
new file mode 100644
index 000000000..7e8764c03
--- /dev/null
+++ b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_239.data
Binary files differ
diff --git a/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_240.data b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_240.data
new file mode 100644
index 000000000..f3fe31687
--- /dev/null
+++ b/ROMFS/px4fmu_test/unit_test_data/mavlink_tests/test_240.data
Binary files differ
diff --git a/Tools/px_romfs_pruner.py b/Tools/px_romfs_pruner.py
index fcc40b09e..aef1cc7a3 100644
--- a/Tools/px_romfs_pruner.py
+++ b/Tools/px_romfs_pruner.py
@@ -57,7 +57,7 @@ def main():
for (root, dirs, files) in os.walk(args.folder):
for file in files:
# only prune text files
- if ".zip" in file or ".bin" in file or ".swp" in file:
+ if ".zip" in file or ".bin" in file or ".swp" in file or ".data" in file:
continue
file_path = os.path.join(root, file)
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py
index cd7884f6d..d4e461226 100755
--- a/Tools/px_uploader.py
+++ b/Tools/px_uploader.py
@@ -195,7 +195,7 @@ class uploader(object):
def __recv(self, count=1):
c = self.port.read(count)
if len(c) < 1:
- raise RuntimeError("timeout waiting for data")
+ raise RuntimeError("timeout waiting for data (%u bytes)" % count)
# print("recv " + binascii.hexlify(c))
return c
@@ -459,6 +459,7 @@ if os.path.exists("/usr/sbin/ModemManager"):
# Load the firmware file
fw = firmware(args.firmware)
print("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision')))
+print("If the board does not respond within 1-2 seconds, unplug and re-plug the USB connector.")
# Spin waiting for a device to show up
while True:
@@ -508,9 +509,12 @@ while True:
except Exception:
# most probably a timeout talking to the port, no bootloader, try to reboot the board
print("attempting reboot on %s..." % port)
+ print("if the board does not respond, unplug and re-plug the USB connector.")
up.send_reboot()
# wait for the reboot, without we might run into Serial I/O Error 5
time.sleep(0.5)
+ # always close the port
+ up.close()
continue
try:
diff --git a/Tools/sdlog2/sdlog2_dump.py b/Tools/sdlog2/sdlog2_dump.py
index ca2efb021..8b0ccb2d7 100644..100755
--- a/Tools/sdlog2/sdlog2_dump.py
+++ b/Tools/sdlog2/sdlog2_dump.py
@@ -154,8 +154,8 @@ class SDLog2Parser:
first_data_msg = False
self.__parseMsg(msg_descr)
bytes_read += self.__ptr
- if not self.__debug_out and self.__time_msg != None and self.__csv_updated:
- self.__printCSVRow()
+ if not self.__debug_out and self.__time_msg != None and self.__csv_updated:
+ self.__printCSVRow()
f.close()
def __bytesLeft(self):
diff --git a/Tools/tests-host/.gitignore b/Tools/tests-host/.gitignore
index 87b314c61..37e923b5e 100644
--- a/Tools/tests-host/.gitignore
+++ b/Tools/tests-host/.gitignore
@@ -1,4 +1,6 @@
./obj/*
mixer_test
+sf0x_test
sbus2_test
autodeclination_test
+st24_test
diff --git a/Tools/tests-host/Makefile b/Tools/tests-host/Makefile
index f0737ef88..8742e2f7c 100644
--- a/Tools/tests-host/Makefile
+++ b/Tools/tests-host/Makefile
@@ -3,7 +3,7 @@ CC=g++
CFLAGS=-I. -I../../src/modules -I ../../src/include -I../../src/drivers \
-I../../src -I../../src/lib -D__EXPORT="" -Dnullptr="0" -lm
-all: mixer_test sbus2_test autodeclination_test
+all: mixer_test sbus2_test autodeclination_test st24_test sf0x_test
MIXER_FILES=../../src/systemcmds/tests/test_mixer.cpp \
../../src/systemcmds/tests/test_conv.cpp \
@@ -20,7 +20,16 @@ SBUS2_FILES=../../src/modules/px4iofirmware/sbus.c \
hrt.cpp \
sbus2_test.cpp
-AUTODECLINATION_FILES= ../../src/lib/geo/geo_mag_declination.c \
+ST24_FILES=../../src/lib/rc/st24.c \
+ hrt.cpp \
+ st24_test.cpp
+
+SF0X_FILES= \
+ hrt.cpp \
+ sf0x_test.cpp \
+ ../../src/drivers/sf0x/sf0x_parser.cpp
+
+AUTODECLINATION_FILES= ../../src/lib/geo_lookup/geo_mag_declination.c \
hrt.cpp \
autodeclination_test.cpp
@@ -30,10 +39,16 @@ mixer_test: $(MIXER_FILES)
sbus2_test: $(SBUS2_FILES)
$(CC) -o sbus2_test $(SBUS2_FILES) $(CFLAGS)
+sf0x_test: $(SF0X_FILES)
+ $(CC) -o sf0x_test $(SF0X_FILES) $(CFLAGS)
+
autodeclination_test: $(SBUS2_FILES)
$(CC) -o autodeclination_test $(AUTODECLINATION_FILES) $(CFLAGS)
+st24_test: $(ST24_FILES)
+ $(CC) -o st24_test $(ST24_FILES) $(CFLAGS)
+
.PHONY: clean
clean:
- rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~ mixer_test sbus2_test autodeclination_test \ No newline at end of file
+ rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~ mixer_test sbus2_test autodeclination_test st24_test sf0x_test
diff --git a/Tools/tests-host/sbus2_test.cpp b/Tools/tests-host/sbus2_test.cpp
index d8fcb695d..e2c18369c 100644
--- a/Tools/tests-host/sbus2_test.cpp
+++ b/Tools/tests-host/sbus2_test.cpp
@@ -29,7 +29,8 @@ int main(int argc, char *argv[]) {
// Trash the first 20 lines
for (unsigned i = 0; i < 20; i++) {
- (void)fscanf(fp, "%f,%x,,", &f, &x);
+ char buf[200];
+ (void)fgets(buf, sizeof(buf), fp);
}
// Init the parser
diff --git a/Tools/tests-host/sf0x_test.cpp b/Tools/tests-host/sf0x_test.cpp
new file mode 100644
index 000000000..82d19fcbe
--- /dev/null
+++ b/Tools/tests-host/sf0x_test.cpp
@@ -0,0 +1,65 @@
+
+#include <unistd.h>
+#include <string.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+
+#include <drivers/sf0x/sf0x_parser.h>
+
+int main(int argc, char *argv[])
+{
+ warnx("SF0X test started");
+
+ int ret = 0;
+
+ const char LINE_MAX = 20;
+ char _linebuf[LINE_MAX];
+ _linebuf[0] = '\0';
+
+ const char *lines[] = {"0.01\r\n",
+ "0.02\r\n",
+ "0.03\r\n",
+ "0.04\r\n",
+ "0",
+ ".",
+ "0",
+ "5",
+ "\r",
+ "\n",
+ "0",
+ "3\r",
+ "\n"
+ "\r\n",
+ "0.06",
+ "\r\n"
+ };
+
+ enum SF0X_PARSE_STATE state = SF0X_PARSE_STATE0_UNSYNC;
+ float dist_m;
+ char _parserbuf[LINE_MAX];
+ unsigned _parsebuf_index = 0;
+
+ for (unsigned l = 0; l < sizeof(lines) / sizeof(lines[0]); l++) {
+
+ printf("\n%s", _linebuf);
+
+ int parse_ret;
+
+ for (int i = 0; i < strlen(lines[l]); i++) {
+ parse_ret = sf0x_parser(lines[l][i], _parserbuf, &_parsebuf_index, &state, &dist_m);
+
+ if (parse_ret == 0) {
+ printf("\nparsed: %f %s\n", dist_m, (parse_ret == 0) ? "OK" : "");
+ }
+ }
+
+ printf("%s", lines[l]);
+
+ }
+
+ warnx("test finished");
+
+ return ret;
+}
diff --git a/Tools/tests-host/st24_test.cpp b/Tools/tests-host/st24_test.cpp
new file mode 100644
index 000000000..25a9355e2
--- /dev/null
+++ b/Tools/tests-host/st24_test.cpp
@@ -0,0 +1,76 @@
+
+#include <stdio.h>
+#include <unistd.h>
+#include <string.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+#include <rc/st24.h>
+#include "../../src/systemcmds/tests/tests.h"
+
+int main(int argc, char *argv[])
+{
+ warnx("ST24 test started");
+
+ if (argc < 2) {
+ errx(1, "Need a filename for the input file");
+ }
+
+ warnx("loading data from: %s", argv[1]);
+
+ FILE *fp;
+
+ fp = fopen(argv[1], "rt");
+
+ if (!fp) {
+ errx(1, "failed opening file");
+ }
+
+ float f;
+ unsigned x;
+ int ret;
+
+ // Trash the first 20 lines
+ for (unsigned i = 0; i < 20; i++) {
+ char buf[200];
+ (void)fgets(buf, sizeof(buf), fp);
+ }
+
+ float last_time = 0;
+
+ while (EOF != (ret = fscanf(fp, "%f,%x,,", &f, &x))) {
+ if (((f - last_time) * 1000 * 1000) > 3000) {
+ // warnx("FRAME RESET\n\n");
+ }
+
+ uint8_t b = static_cast<uint8_t>(x);
+
+ last_time = f;
+
+ // Pipe the data into the parser
+ hrt_abstime now = hrt_absolute_time();
+
+ uint8_t rssi;
+ uint8_t rx_count;
+ uint16_t channel_count;
+ uint16_t channels[20];
+
+
+ if (!st24_decode(b, &rssi, &rx_count, &channel_count, channels, sizeof(channels) / sizeof(channels[0]))) {
+ warnx("decoded: %u channels (converted to PPM range)", (unsigned)channel_count);
+
+ for (unsigned i = 0; i < channel_count; i++) {
+
+ int16_t val = channels[i];
+ warnx("channel %u: %d 0x%03X", i, static_cast<int>(val), static_cast<int>(val));
+ }
+ }
+ }
+
+ if (ret == EOF) {
+ warnx("Test finished, reached end of file");
+
+ } else {
+ warnx("Test aborted, errno: %d", ret);
+ }
+
+}
diff --git a/Tools/upload.sh b/Tools/upload.sh
new file mode 100755
index 000000000..17d87fe61
--- /dev/null
+++ b/Tools/upload.sh
@@ -0,0 +1,28 @@
+#!/bin/bash
+
+EXEDIR=`pwd`
+BASEDIR=$(dirname $0)
+
+SYSTYPE=`uname -s`
+
+#
+# Serial port defaults.
+#
+# XXX The uploader should be smarter than this.
+#
+if [ $SYSTYPE=Darwin ];
+then
+SERIAL_PORTS="/dev/tty.usbmodemPX*,/dev/tty.usbmodem*"
+fi
+
+if [ $SYSTYPE=Linux ];
+then
+SERIAL_PORTS="/dev/serial/by-id/usb-3D_Robotics*"
+fi
+
+if [ $SYSTYPE="" ];
+then
+SERIAL_PORTS="COM32,COM31,COM30,COM29,COM28,COM27,COM26,COM25,COM24,COM23,COM22,COM21,COM20,COM19,COM18,COM17,COM16,COM15,COM14,COM13,COM12,COM11,COM10,COM9,COM8,COM7,COM6,COM5,COM4,COM3,COM2,COM1,COM0"
+fi
+
+python $BASEDIR/px_uploader.py --port $SERIAL_PORTS $1 \ No newline at end of file
diff --git a/Tools/usb_serialload.py b/Tools/usb_serialload.py
new file mode 100644
index 000000000..5c864532f
--- /dev/null
+++ b/Tools/usb_serialload.py
@@ -0,0 +1,55 @@
+import serial, time
+
+
+port = serial.Serial('/dev/ttyACM0', baudrate=57600, timeout=2)
+
+data = '01234567890123456789012345678901234567890123456789'
+#data = 'hellohello'
+outLine = 'echo %s\n' % data
+
+port.write('\n\n\n')
+port.write('free\n')
+line = port.readline(80)
+while line != '':
+ print(line)
+ line = port.readline(80)
+
+
+i = 0
+bytesOut = 0
+bytesIn = 0
+
+startTime = time.time()
+lastPrint = startTime
+while True:
+ bytesOut += port.write(outLine)
+ line = port.readline(80)
+ bytesIn += len(line)
+ # check command line echo
+ if (data not in line):
+ print('command error %d: %s' % (i,line))
+ #break
+ # read echo output
+ line = port.readline(80)
+ if (data not in line):
+ print('echo output error %d: %s' % (i,line))
+ #break
+ bytesIn += len(line)
+ #print('%d: %s' % (i,line))
+ #print('%d: bytesOut: %d, bytesIn: %d' % (i, bytesOut, bytesIn))
+
+ elapsedT = time.time() - lastPrint
+ if (time.time() - lastPrint >= 5):
+ outRate = bytesOut / elapsedT
+ inRate = bytesIn / elapsedT
+ usbRate = (bytesOut + bytesIn) / elapsedT
+ lastPrint = time.time()
+ print('elapsed time: %f' % (time.time() - startTime))
+ print('data rates (bytes/sec): out: %f, in: %f, total: %f' % (outRate, inRate, usbRate))
+
+ bytesOut = 0
+ bytesIn = 0
+
+ i += 1
+ #if (i > 2): break
+
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index a7c10f52f..9fe16fbb6 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -24,27 +24,22 @@ MODULES += drivers/l3gd20
MODULES += drivers/mpu6000
MODULES += drivers/hmc5883
MODULES += drivers/ms5611
-MODULES += drivers/mb12xx
-MODULES += drivers/ll40ls
+#MODULES += drivers/mb12xx
MODULES += drivers/gps
MODULES += drivers/hil
-MODULES += drivers/hott/hott_telemetry
-MODULES += drivers/hott/hott_sensors
-MODULES += drivers/blinkm
+#MODULES += drivers/blinkm
MODULES += drivers/rgbled
MODULES += drivers/mkblctrl
MODULES += drivers/airspeed
-MODULES += drivers/ets_airspeed
+#MODULES += drivers/ets_airspeed
MODULES += drivers/meas_airspeed
-MODULES += drivers/frsky_telemetry
+#MODULES += drivers/frsky_telemetry
MODULES += modules/sensors
#
# System commands
#
MODULES += systemcmds/mtd
-MODULES += systemcmds/bl_update
-MODULES += systemcmds/i2c
MODULES += systemcmds/mixer
MODULES += systemcmds/param
MODULES += systemcmds/perf
@@ -152,5 +147,4 @@ endef
# command priority stack entrypoint
BUILTIN_COMMANDS := \
$(call _B, sercon, , 2048, sercon_main ) \
- $(call _B, serdis, , 2048, serdis_main ) \
- $(call _B, sysinfo, , 2048, sysinfo_main )
+ $(call _B, serdis, , 2048, serdis_main )
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index d0a40445d..d17dff5bb 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -41,6 +41,7 @@ MODULES += drivers/frsky_telemetry
MODULES += modules/sensors
MODULES += drivers/mkblctrl
MODULES += drivers/pca8574
+MODULES += drivers/px4flow
# Needs to be burned to the ground and re-written; for now,
@@ -128,6 +129,11 @@ MODULES += lib/conversion
MODULES += lib/launchdetection
#
+# OBC challenge
+#
+MODULES += modules/bottle_drop
+
+#
# Demo apps
#
#MODULES += examples/math_demo
diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk
index 932f92261..2f4d9d6a4 100644
--- a/makefiles/config_px4fmu-v2_test.mk
+++ b/makefiles/config_px4fmu-v2_test.mk
@@ -54,6 +54,10 @@ MODULES += lib/conversion
#
LIBRARIES += lib/mathlib/CMSIS
+MODULES += modules/unit_test
+MODULES += modules/mavlink/mavlink_tests
+MODULES += modules/commander/commander_tests
+
#
# Transitional support - add commands from the NuttX export archive.
#
diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0
-Subproject 04b1ad5b284d5e916858ca9f928e93d97bbf6ad
+Subproject ad5e5a645dec152419264ad32221f7c113ea5c3
diff --git a/nuttx-configs/aerocore/nsh/defconfig b/nuttx-configs/aerocore/nsh/defconfig
index 8d0bae7b9..317194f68 100644
--- a/nuttx-configs/aerocore/nsh/defconfig
+++ b/nuttx-configs/aerocore/nsh/defconfig
@@ -314,7 +314,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500
# CONFIG_ARCH_NOINTC is not set
# CONFIG_ARCH_VECNOTIRQ is not set
CONFIG_ARCH_DMA=y
-CONFIG_ARCH_IRQPRIO=y
+# CONFIG_ARCH_IRQPRIO is not set
# CONFIG_CUSTOM_STACK is not set
# CONFIG_ADDRENV is not set
CONFIG_ARCH_HAVE_VFORK=y
diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index a651faffa..edf49b26e 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -288,7 +288,6 @@ CONFIG_STM32_USART_SINGLEWIRE=y
# CONFIG_STM32_I2C_DYNTIMEO is not set
CONFIG_STM32_I2CTIMEOSEC=0
CONFIG_STM32_I2CTIMEOMS=10
-CONFIG_STM32_I2CTIMEOTICKS=500
# CONFIG_STM32_I2C_DUTY16_9 is not set
#
@@ -309,7 +308,7 @@ CONFIG_STM32_I2CTIMEOTICKS=500
# CONFIG_ARCH_NOINTC is not set
# CONFIG_ARCH_VECNOTIRQ is not set
CONFIG_ARCH_DMA=y
-CONFIG_ARCH_IRQPRIO=y
+# CONFIG_ARCH_IRQPRIO is not set
# CONFIG_CUSTOM_STACK is not set
# CONFIG_ADDRENV is not set
CONFIG_ARCH_HAVE_VFORK=y
diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig
index a55c95a29..e31f40cd2 100644
--- a/nuttx-configs/px4fmu-v2/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v2/nsh/defconfig
@@ -323,8 +323,7 @@ CONFIG_STM32_USART_SINGLEWIRE=y
#
# CONFIG_STM32_I2C_DYNTIMEO is not set
CONFIG_STM32_I2CTIMEOSEC=0
-CONFIG_STM32_I2CTIMEOMS=10
-CONFIG_STM32_I2CTIMEOTICKS=500
+CONFIG_STM32_I2CTIMEOMS=1
# CONFIG_STM32_I2C_DUTY16_9 is not set
#
@@ -350,7 +349,7 @@ CONFIG_SDIO_PRI=128
# CONFIG_ARCH_NOINTC is not set
# CONFIG_ARCH_VECNOTIRQ is not set
CONFIG_ARCH_DMA=y
-CONFIG_ARCH_IRQPRIO=y
+# CONFIG_ARCH_IRQPRIO is not set
# CONFIG_CUSTOM_STACK is not set
# CONFIG_ADDRENV is not set
CONFIG_ARCH_HAVE_VFORK=y
diff --git a/nuttx-configs/px4io-v1/nsh/defconfig b/nuttx-configs/px4io-v1/nsh/defconfig
index 3785e0367..7c76be7ec 100755
--- a/nuttx-configs/px4io-v1/nsh/defconfig
+++ b/nuttx-configs/px4io-v1/nsh/defconfig
@@ -83,7 +83,6 @@ CONFIG_ARCH_BOARD="px4io-v1"
CONFIG_BOARD_LOOPSPERMSEC=2000
CONFIG_DRAM_SIZE=0x00002000
CONFIG_DRAM_START=0x20000000
-CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
@@ -134,6 +133,8 @@ CONFIG_STM32_USART2=y
CONFIG_STM32_USART3=y
CONFIG_STM32_I2C1=y
CONFIG_STM32_I2C2=n
+CONFIG_STM32_I2CTIMEOSEC=0
+CONFIG_STM32_I2CTIMEOMS=1
CONFIG_STM32_BKP=n
CONFIG_STM32_PWR=n
CONFIG_STM32_DAC=n
diff --git a/nuttx-configs/px4io-v2/nsh/defconfig b/nuttx-configs/px4io-v2/nsh/defconfig
index e6563e587..02b51e3d7 100755
--- a/nuttx-configs/px4io-v2/nsh/defconfig
+++ b/nuttx-configs/px4io-v2/nsh/defconfig
@@ -79,7 +79,6 @@ CONFIG_ARCH_BOARD_PX4IO_V2=y
CONFIG_BOARD_LOOPSPERMSEC=2000
CONFIG_DRAM_SIZE=0x00002000
CONFIG_DRAM_START=0x20000000
-CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp
index 41942aacd..293690d27 100644
--- a/src/drivers/airspeed/airspeed.cpp
+++ b/src/drivers/airspeed/airspeed.cpp
@@ -165,7 +165,7 @@ Airspeed::probe()
*/
_retries = 4;
int ret = measure();
- _retries = 2;
+ _retries = 0;
return ret;
}
@@ -381,7 +381,10 @@ Airspeed::cycle_trampoline(void *arg)
Airspeed *dev = (Airspeed *)arg;
dev->cycle();
- dev->update_status();
+ // XXX we do not know if this is
+ // really helping - do not update the
+ // subsys state right now
+ //dev->update_status();
}
void
diff --git a/src/drivers/boards/aerocore/aerocore_init.c b/src/drivers/boards/aerocore/aerocore_init.c
index 4e3ba2d7e..1ce235da8 100644
--- a/src/drivers/boards/aerocore/aerocore_init.c
+++ b/src/drivers/boards/aerocore/aerocore_init.c
@@ -93,6 +93,19 @@
# endif
#endif
+/*
+ * Ideally we'd be able to get these from up_internal.h,
+ * but since we want to be able to disable the NuttX use
+ * of leds for system indication at will and there is no
+ * separate switch, we need to build independent of the
+ * CONFIG_ARCH_LEDS configuration switch.
+ */
+__BEGIN_DECLS
+extern void led_init(void);
+extern void led_on(int led);
+extern void led_off(int led);
+__END_DECLS
+
/****************************************************************************
* Protected Functions
****************************************************************************/
diff --git a/src/drivers/boards/aerocore/board_config.h b/src/drivers/boards/aerocore/board_config.h
index 70142a314..776a2071e 100644
--- a/src/drivers/boards/aerocore/board_config.h
+++ b/src/drivers/boards/aerocore/board_config.h
@@ -171,6 +171,25 @@ __BEGIN_DECLS
extern void stm32_spiinitialize(void);
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization for NSH.
+ *
+ * CONFIG_NSH_ARCHINIT=y :
+ * Called from the NSH library
+ *
+ * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
+ * CONFIG_NSH_ARCHINIT=n :
+ * Called from board_initialize().
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_LIBRARY
+int nsh_archinitialize(void);
+#endif
+
#endif /* __ASSEMBLY__ */
__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
index a70a6240c..188885be2 100644
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -209,6 +209,27 @@ __BEGIN_DECLS
extern void stm32_spiinitialize(void);
+extern void stm32_usbinitialize(void);
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization for NSH.
+ *
+ * CONFIG_NSH_ARCHINIT=y :
+ * Called from the NSH library
+ *
+ * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
+ * CONFIG_NSH_ARCHINIT=n :
+ * Called from board_initialize().
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_LIBRARY
+int nsh_archinitialize(void);
+#endif
+
#endif /* __ASSEMBLY__ */
__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index 0190a5b5b..ee365e47c 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -229,6 +229,27 @@ __BEGIN_DECLS
extern void stm32_spiinitialize(void);
+extern void stm32_usbinitialize(void);
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization for NSH.
+ *
+ * CONFIG_NSH_ARCHINIT=y :
+ * Called from the NSH library
+ *
+ * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
+ * CONFIG_NSH_ARCHINIT=n :
+ * Called from board_initialize().
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NSH_LIBRARY
+int nsh_archinitialize(void);
+#endif
+
#endif /* __ASSEMBLY__ */
__END_DECLS
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
index bf41bb1fe..9b25c574a 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
@@ -94,6 +94,19 @@
# endif
#endif
+/*
+ * Ideally we'd be able to get these from up_internal.h,
+ * but since we want to be able to disable the NuttX use
+ * of leds for system indication at will and there is no
+ * separate switch, we need to build independent of the
+ * CONFIG_ARCH_LEDS configuration switch.
+ */
+__BEGIN_DECLS
+extern void led_init(void);
+extern void led_on(int led);
+extern void led_off(int led);
+__END_DECLS
+
/****************************************************************************
* Protected Functions
****************************************************************************/
diff --git a/src/drivers/boards/px4io-v2/board_config.h b/src/drivers/boards/px4io-v2/board_config.h
index ef9bb5cad..10a93be0b 100644
--- a/src/drivers/boards/px4io-v2/board_config.h
+++ b/src/drivers/boards/px4io-v2/board_config.h
@@ -77,6 +77,7 @@
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14)
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_LED4 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN11)
/* Safety switch button *******************************************************/
diff --git a/src/drivers/boards/px4io-v2/px4iov2_init.c b/src/drivers/boards/px4io-v2/px4iov2_init.c
index 9f8c0eeb2..5c3343ccc 100644
--- a/src/drivers/boards/px4io-v2/px4iov2_init.c
+++ b/src/drivers/boards/px4io-v2/px4iov2_init.c
@@ -108,6 +108,7 @@ __EXPORT void stm32_boardinitialize(void)
stm32_configgpio(GPIO_LED1);
stm32_configgpio(GPIO_LED2);
stm32_configgpio(GPIO_LED3);
+ stm32_configgpio(GPIO_LED4);
stm32_configgpio(GPIO_BTN_SAFETY);
diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp
index f1f777dce..d46901683 100644
--- a/src/drivers/device/device.cpp
+++ b/src/drivers/device/device.cpp
@@ -97,6 +97,7 @@ Device::Device(const char *name,
/* setup a default device ID. When bus_type is UNKNOWN the
other fields are invalid */
+ _device_id.devid = 0;
_device_id.devid_s.bus_type = DeviceBusType_UNKNOWN;
_device_id.devid_s.bus = 0;
_device_id.devid_s.address = 0;
diff --git a/src/drivers/drv_gps.h b/src/drivers/drv_gps.h
index e14f4e00d..76a211000 100644
--- a/src/drivers/drv_gps.h
+++ b/src/drivers/drv_gps.h
@@ -57,7 +57,8 @@
typedef enum {
GPS_DRIVER_MODE_NONE = 0,
GPS_DRIVER_MODE_UBX,
- GPS_DRIVER_MODE_MTK
+ GPS_DRIVER_MODE_MTK,
+ GPS_DRIVER_MODE_ASHTECH
} gps_driver_mode_t;
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index 84815fdfb..6873f24b6 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -95,6 +95,11 @@ __BEGIN_DECLS
#define PWM_LOWEST_MAX 1700
/**
+ * Do not output a channel with this value
+ */
+#define PWM_IGNORE_THIS_CHANNEL UINT16_MAX
+
+/**
* Servo output signal type, value is actual servo output pulse
* width in microseconds.
*/
@@ -160,7 +165,7 @@ ORB_DECLARE(output_pwm);
#define DSM2_BIND_PULSES 3 /* DSM_BIND_START ioctl parameter, pulses required to start dsm2 pairing */
#define DSMX_BIND_PULSES 7 /* DSM_BIND_START ioctl parameter, pulses required to start dsmx pairing */
-#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
+#define DSMX8_BIND_PULSES 9 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
/** power up DSM receiver */
#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 11)
@@ -200,10 +205,16 @@ ORB_DECLARE(output_pwm);
#define PWM_SERVO_GET_DISABLE_LOCKDOWN _IOC(_PWM_SERVO_BASE, 22)
/** force safety switch off (to disable use of safety switch) */
-#define PWM_SERVO_SET_FORCE_SAFETY_OFF _IOC(_PWM_SERVO_BASE, 23)
+#define PWM_SERVO_SET_FORCE_SAFETY_OFF _IOC(_PWM_SERVO_BASE, 23)
/** force failsafe mode (failsafe values are set immediately even if failsafe condition not met) */
-#define PWM_SERVO_SET_FORCE_FAILSAFE _IOC(_PWM_SERVO_BASE, 24)
+#define PWM_SERVO_SET_FORCE_FAILSAFE _IOC(_PWM_SERVO_BASE, 24)
+
+/** make failsafe non-recoverable (termination) if it occurs */
+#define PWM_SERVO_SET_TERMINATION_FAILSAFE _IOC(_PWM_SERVO_BASE, 25)
+
+/** force safety switch on (to enable use of safety switch) */
+#define PWM_SERVO_SET_FORCE_SAFETY_ON _IOC(_PWM_SERVO_BASE, 26)
/*
*
diff --git a/src/drivers/drv_px4flow.h b/src/drivers/drv_px4flow.h
index 76ec55c3e..ab640837b 100644
--- a/src/drivers/drv_px4flow.h
+++ b/src/drivers/drv_px4flow.h
@@ -46,37 +46,6 @@
#define PX4FLOW_DEVICE_PATH "/dev/px4flow"
-/**
- * @addtogroup topics
- * @{
- */
-
-/**
- * Optical flow in NED body frame in SI units.
- *
- * @see http://en.wikipedia.org/wiki/International_System_of_Units
- *
- * @warning If possible the usage of the raw flow and performing rotation-compensation
- * using the autopilot angular rate estimate is recommended.
- */
-struct px4flow_report {
-
- uint64_t timestamp; /**< in microseconds since system start */
-
- int16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */
- int16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */
- float flow_comp_x_m; /**< speed over ground in meters per second, rotation-compensated */
- float flow_comp_y_m; /**< speed over ground in meters per second, rotation-compensated */
- float ground_distance_m; /**< Altitude / distance to ground in meters */
- uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */
- uint8_t sensor_id; /**< id of the sensor emitting the flow value */
-
-};
-
-/**
- * @}
- */
-
/*
* ObjDev tag for px4flow data.
*/
diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h
index 47fa8fa59..b249c2a09 100644
--- a/src/drivers/drv_rc_input.h
+++ b/src/drivers/drv_rc_input.h
@@ -83,7 +83,8 @@ enum RC_INPUT_SOURCE {
RC_INPUT_SOURCE_PX4FMU_PPM,
RC_INPUT_SOURCE_PX4IO_PPM,
RC_INPUT_SOURCE_PX4IO_SPEKTRUM,
- RC_INPUT_SOURCE_PX4IO_SBUS
+ RC_INPUT_SOURCE_PX4IO_SBUS,
+ RC_INPUT_SOURCE_PX4IO_ST24
};
/**
diff --git a/src/drivers/drv_tone_alarm.h b/src/drivers/drv_tone_alarm.h
index 19f792d19..307f7dbc7 100644
--- a/src/drivers/drv_tone_alarm.h
+++ b/src/drivers/drv_tone_alarm.h
@@ -150,6 +150,7 @@ enum {
TONE_ARMING_FAILURE_TUNE,
TONE_PARACHUTE_RELEASE_TUNE,
TONE_EKF_WARNING_TUNE,
+ TONE_BARO_WARNING_TUNE,
TONE_NUMBER_OF_TUNES
};
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index f98d615a2..0f77bb805 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -155,7 +155,6 @@ ETSAirspeed::collect()
}
uint16_t diff_pres_pa_raw = val[1] << 8 | val[0];
- uint16_t diff_pres_pa;
if (diff_pres_pa_raw == 0) {
// a zero value means the pressure sensor cannot give us a
// value. We need to return, and not report a value or the
@@ -166,28 +165,21 @@ ETSAirspeed::collect()
return -1;
}
- if (diff_pres_pa_raw < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
- diff_pres_pa = 0;
- } else {
- diff_pres_pa = diff_pres_pa_raw - _diff_pres_offset;
- }
-
// The raw value still should be compensated for the known offset
diff_pres_pa_raw -= _diff_pres_offset;
// Track maximum differential pressure measured (so we can work out top speed).
- if (diff_pres_pa > _max_differential_pressure_pa) {
- _max_differential_pressure_pa = diff_pres_pa;
+ if (diff_pres_pa_raw > _max_differential_pressure_pa) {
+ _max_differential_pressure_pa = diff_pres_pa_raw;
}
differential_pressure_s report;
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
- report.differential_pressure_pa = (float)diff_pres_pa;
// XXX we may want to smooth out the readings to remove noise.
- report.differential_pressure_filtered_pa = (float)diff_pres_pa;
- report.differential_pressure_raw_pa = (float)diff_pres_pa_raw;
+ report.differential_pressure_filtered_pa = diff_pres_pa_raw;
+ report.differential_pressure_raw_pa = diff_pres_pa_raw;
report.temperature = -1000.0f;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
@@ -369,7 +361,7 @@ test()
err(1, "immediate read failed");
warnx("single read");
- warnx("diff pressure: %f pa", (double)report.differential_pressure_pa);
+ warnx("diff pressure: %f pa", (double)report.differential_pressure_filtered_pa);
/* start the sensor polling at 2Hz */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
@@ -394,7 +386,7 @@ test()
err(1, "periodic read failed");
warnx("periodic read %u", i);
- warnx("diff pressure: %f pa", (double)report.differential_pressure_pa);
+ warnx("diff pressure: %f pa", (double)report.differential_pressure_filtered_pa);
}
/* reset the sensor polling to its default rate */
diff --git a/src/drivers/gps/ashtech.cpp b/src/drivers/gps/ashtech.cpp
new file mode 100644
index 000000000..a2e292de2
--- /dev/null
+++ b/src/drivers/gps/ashtech.cpp
@@ -0,0 +1,641 @@
+#include "ashtech.h"
+
+#include <unistd.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <poll.h>
+#include <math.h>
+#include <string.h>
+#include <assert.h>
+#include <systemlib/err.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/satellite_info.h>
+#include <drivers/drv_hrt.h>
+
+#include <fcntl.h>
+#include <math.h>
+
+ASHTECH::ASHTECH(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info):
+ _fd(fd),
+ _satellite_info(satellite_info),
+ _gps_position(gps_position)
+{
+ decode_init();
+ _decode_state = NME_DECODE_UNINIT;
+ _rx_buffer_bytes = 0;
+}
+
+ASHTECH::~ASHTECH()
+{
+}
+
+/*
+ * All NMEA descriptions are taken from
+ * http://www.trimble.com/OEM_ReceiverHelp/V4.44/en/NMEA-0183messages_MessageOverview.html
+ */
+
+int ASHTECH::handle_message(int len)
+{
+ char * endp;
+
+ if (len < 7) { return 0; }
+
+ int uiCalcComma = 0;
+
+ for (int i = 0 ; i < len; i++) {
+ if (_rx_buffer[i] == ',') { uiCalcComma++; }
+ }
+
+ char *bufptr = (char *)(_rx_buffer + 6);
+
+ if ((memcmp(_rx_buffer + 3, "ZDA,", 3) == 0) && (uiCalcComma == 6)) {
+ /*
+ UTC day, month, and year, and local time zone offset
+ An example of the ZDA message string is:
+
+ $GPZDA,172809.456,12,07,1996,00,00*45
+
+ ZDA message fields
+ Field Meaning
+ 0 Message ID $GPZDA
+ 1 UTC
+ 2 Day, ranging between 01 and 31
+ 3 Month, ranging between 01 and 12
+ 4 Year
+ 5 Local time zone offset from GMT, ranging from 00 through 13 hours
+ 6 Local time zone offset from GMT, ranging from 00 through 59 minutes
+ 7 The checksum data, always begins with *
+ Fields 5 and 6 together yield the total offset. For example, if field 5 is -5 and field 6 is +15, local time is 5 hours and 15 minutes earlier than GMT.
+ */
+ double ashtech_time = 0.0;
+ int day = 0, month = 0, year = 0, local_time_off_hour __attribute__((unused)) = 0, local_time_off_min __attribute__((unused)) = 0;
+
+ if (bufptr && *(++bufptr) != ',') { ashtech_time = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { day = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { month = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { year = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { local_time_off_hour = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { local_time_off_min = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+
+ int ashtech_hour = ashtech_time / 10000;
+ int ashtech_minute = (ashtech_time - ashtech_hour * 10000) / 100;
+ double ashtech_sec = ashtech_time - ashtech_hour * 10000 - ashtech_minute * 100;
+ /*
+ * convert to unix timestamp
+ */
+ struct tm timeinfo;
+ timeinfo.tm_year = year - 1900;
+ timeinfo.tm_mon = month - 1;
+ timeinfo.tm_mday = day;
+ timeinfo.tm_hour = ashtech_hour;
+ timeinfo.tm_min = ashtech_minute;
+ timeinfo.tm_sec = int(ashtech_sec);
+ time_t epoch = mktime(&timeinfo);
+
+ _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this
+ _gps_position->time_gps_usec += (uint64_t)((ashtech_sec - int(ashtech_sec)) * 1e6);
+ _gps_position->timestamp_time = hrt_absolute_time();
+ }
+
+ else if ((memcmp(_rx_buffer + 3, "GGA,", 3) == 0) && (uiCalcComma == 14)) {
+ /*
+ Time, position, and fix related data
+ An example of the GBS message string is:
+
+ $GPGGA,172814.0,3723.46587704,N,12202.26957864,W,2,6,1.2,18.893,M,-25.669,M,2.0,0031*4F
+
+ Note - The data string exceeds the ASHTECH standard length.
+ GGA message fields
+ Field Meaning
+ 0 Message ID $GPGGA
+ 1 UTC of position fix
+ 2 Latitude
+ 3 Direction of latitude:
+ N: North
+ S: South
+ 4 Longitude
+ 5 Direction of longitude:
+ E: East
+ W: West
+ 6 GPS Quality indicator:
+ 0: Fix not valid
+ 1: GPS fix
+ 2: Differential GPS fix, OmniSTAR VBS
+ 4: Real-Time Kinematic, fixed integers
+ 5: Real-Time Kinematic, float integers, OmniSTAR XP/HP or Location RTK
+ 7 Number of SVs in use, range from 00 through to 24+
+ 8 HDOP
+ 9 Orthometric height (MSL reference)
+ 10 M: unit of measure for orthometric height is meters
+ 11 Geoid separation
+ 12 M: geoid separation measured in meters
+ 13 Age of differential GPS data record, Type 1 or Type 9. Null field when DGPS is not used.
+ 14 Reference station ID, range 0000-4095. A null field when any reference station ID is selected and no corrections are received1.
+ 15
+ The checksum data, always begins with *
+ Note - If a user-defined geoid model, or an inclined
+ */
+ double ashtech_time __attribute__((unused)) = 0.0, lat = 0.0, lon = 0.0, alt = 0.0;
+ int num_of_sv __attribute__((unused)) = 0, fix_quality = 0;
+ double hdop __attribute__((unused)) = 99.9;
+ char ns = '?', ew = '?';
+
+ if (bufptr && *(++bufptr) != ',') { ashtech_time = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { lat = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { ns = *(bufptr++); }
+
+ if (bufptr && *(++bufptr) != ',') { lon = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { ew = *(bufptr++); }
+
+ if (bufptr && *(++bufptr) != ',') { fix_quality = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { num_of_sv = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { hdop = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { alt = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (ns == 'S') {
+ lat = -lat;
+ }
+
+ if (ew == 'W') {
+ lon = -lon;
+ }
+
+ _gps_position->lat = (int(lat * 0.01) + (lat * 0.01 - int(lat * 0.01)) * 100.0 / 60.0) * 10000000;
+ _gps_position->lon = (int(lon * 0.01) + (lon * 0.01 - int(lon * 0.01)) * 100.0 / 60.0) * 10000000;
+ _gps_position->alt = alt * 1000;
+ _rate_count_lat_lon++;
+
+ if (fix_quality <= 0) {
+ _gps_position->fix_type = 0;
+
+ } else {
+ /*
+ * in this NMEA message float integers (value 5) mode has higher value than fixed integers (value 4), whereas it provides lower quality,
+ * and since value 3 is not being used, I "moved" value 5 to 3 to add it to _gps_position->fix_type
+ */
+ if (fix_quality == 5) { fix_quality = 3; }
+
+ /*
+ * fix quality 1 means just a normal 3D fix, so I'm subtracting 1 here. This way we'll have 3 for auto, 4 for DGPS, 5 for floats, 6 for fixed.
+ */
+ _gps_position->fix_type = 3 + fix_quality - 1;
+ }
+
+ _gps_position->timestamp_position = hrt_absolute_time();
+
+ _gps_position->vel_m_s = 0; /**< GPS ground speed (m/s) */
+ _gps_position->vel_n_m_s = 0; /**< GPS ground speed in m/s */
+ _gps_position->vel_e_m_s = 0; /**< GPS ground speed in m/s */
+ _gps_position->vel_d_m_s = 0; /**< GPS ground speed in m/s */
+ _gps_position->cog_rad =
+ 0; /**< Course over ground (NOT heading, but direction of movement) in rad, -PI..PI */
+ _gps_position->vel_ned_valid = true; /**< Flag to indicate if NED speed is valid */
+ _gps_position->c_variance_rad = 0.1;
+ _gps_position->timestamp_velocity = hrt_absolute_time();
+ return 1;
+
+ } else if ((memcmp(_rx_buffer, "$PASHR,POS,", 11) == 0) && (uiCalcComma == 18)) {
+ /*
+ Example $PASHR,POS,2,10,125410.00,5525.8138702,N,03833.9587380,E,131.555,1.0,0.0,0.007,-0.001,2.0,1.0,1.7,1.0,*34
+
+ $PASHR,POS,d1,d2,m3,m4,c5,m6,c7,f8,f9,f10,f11,f12,f13,f14,f15,f16,s17*cc
+ Parameter Description Range
+ d1 Position mode 0: standalone
+ 1: differential
+ 2: RTK float
+ 3: RTK fixed
+ 5: Dead reckoning
+ 9: SBAS (see NPT setting)
+ d2 Number of satellite used in position fix 0-99
+ m3 Current UTC time of position fix (hhmmss.ss) 000000.00-235959.99
+ m4 Latitude of position (ddmm.mmmmmm) 0-90 degrees 00-59.9999999 minutes
+ c5 Latitude sector N, S
+ m6 Longitude of position (dddmm.mmmmmm) 0-180 degrees 00-59.9999999 minutes
+ c7 Longitude sector E,W
+ f8 Altitude above ellipsoid +9999.000
+ f9 Differential age (data link age), seconds 0.0-600.0
+ f10 True track/course over ground in degrees 0.0-359.9
+ f11 Speed over ground in knots 0.0-999.9
+ f12 Vertical velocity in decimeters per second +999.9
+ f13 PDOP 0-99.9
+ f14 HDOP 0-99.9
+ f15 VDOP 0-99.9
+ f16 TDOP 0-99.9
+ s17 Reserved no data
+ *cc Checksum
+ */
+ bufptr = (char *)(_rx_buffer + 10);
+
+ /*
+ * Ashtech would return empty space as coordinate (lat, lon or alt) if it doesn't have a fix yet
+ */
+ int coordinatesFound = 0;
+ double ashtech_time __attribute__((unused)) = 0.0, lat = 0.0, lon = 0.0, alt = 0.0;
+ int num_of_sv __attribute__((unused)) = 0, fix_quality = 0;
+ double track_true = 0.0, ground_speed = 0.0 , age_of_corr __attribute__((unused)) = 0.0;
+ double hdop __attribute__((unused)) = 99.9, vdop __attribute__((unused)) = 99.9, pdop __attribute__((unused)) = 99.9, tdop __attribute__((unused)) = 99.9, vertic_vel = 0.0;
+ char ns = '?', ew = '?';
+
+ if (bufptr && *(++bufptr) != ',') { fix_quality = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { num_of_sv = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { ashtech_time = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') {
+ /*
+ * if a coordinate is skipped (i.e. no fix), it either won't get into this block (two commas in a row)
+ * or strtod won't find anything and endp will point exactly where bufptr is. The same is for lon and alt.
+ */
+ lat = strtod(bufptr, &endp);
+ if (bufptr != endp) {coordinatesFound++;}
+ bufptr = endp;
+ }
+
+ if (bufptr && *(++bufptr) != ',') { ns = *(bufptr++); }
+
+ if (bufptr && *(++bufptr) != ',') {
+ lon = strtod(bufptr, &endp);
+ if (bufptr != endp) {coordinatesFound++;}
+ bufptr = endp;
+ }
+
+ if (bufptr && *(++bufptr) != ',') { ew = *(bufptr++); }
+
+ if (bufptr && *(++bufptr) != ',') {
+ alt = strtod(bufptr, &endp);
+ if (bufptr != endp) {coordinatesFound++;}
+ bufptr = endp;
+ }
+
+ if (bufptr && *(++bufptr) != ',') { age_of_corr = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { track_true = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { ground_speed = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { vertic_vel = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { pdop = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { hdop = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { vdop = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { tdop = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (ns == 'S') {
+ lat = -lat;
+ }
+
+ if (ew == 'W') {
+ lon = -lon;
+ }
+
+ _gps_position->lat = (int(lat * 0.01) + (lat * 0.01 - int(lat * 0.01)) * 100.0 / 60.0) * 10000000;
+ _gps_position->lon = (int(lon * 0.01) + (lon * 0.01 - int(lon * 0.01)) * 100.0 / 60.0) * 10000000;
+ _gps_position->alt = alt * 1000;
+ _rate_count_lat_lon++;
+
+ if (coordinatesFound < 3) {
+ _gps_position->fix_type = 0;
+
+ } else {
+ _gps_position->fix_type = 3 + fix_quality;
+ }
+
+ _gps_position->timestamp_position = hrt_absolute_time();
+
+ double track_rad = track_true * M_PI / 180.0;
+
+ double velocity_ms = ground_speed / 1.9438445; /** knots to m/s */
+ double velocity_north = velocity_ms * cos(track_rad);
+ double velocity_east = velocity_ms * sin(track_rad);
+
+ _gps_position->vel_m_s = velocity_ms; /**< GPS ground speed (m/s) */
+ _gps_position->vel_n_m_s = velocity_north; /**< GPS ground speed in m/s */
+ _gps_position->vel_e_m_s = velocity_east; /**< GPS ground speed in m/s */
+ _gps_position->vel_d_m_s = -vertic_vel; /**< GPS ground speed in m/s */
+ _gps_position->cog_rad =
+ track_rad; /**< Course over ground (NOT heading, but direction of movement) in rad, -PI..PI */
+ _gps_position->vel_ned_valid = true; /**< Flag to indicate if NED speed is valid */
+ _gps_position->c_variance_rad = 0.1;
+ _gps_position->timestamp_velocity = hrt_absolute_time();
+ return 1;
+
+ } else if ((memcmp(_rx_buffer + 3, "GST,", 3) == 0) && (uiCalcComma == 8)) {
+ /*
+ Position error statistics
+ An example of the GST message string is:
+
+ $GPGST,172814.0,0.006,0.023,0.020,273.6,0.023,0.020,0.031*6A
+
+ The Talker ID ($--) will vary depending on the satellite system used for the position solution:
+
+ $GP - GPS only
+ $GL - GLONASS only
+ $GN - Combined
+ GST message fields
+ Field Meaning
+ 0 Message ID $GPGST
+ 1 UTC of position fix
+ 2 RMS value of the pseudorange residuals; includes carrier phase residuals during periods of RTK (float) and RTK (fixed) processing
+ 3 Error ellipse semi-major axis 1 sigma error, in meters
+ 4 Error ellipse semi-minor axis 1 sigma error, in meters
+ 5 Error ellipse orientation, degrees from true north
+ 6 Latitude 1 sigma error, in meters
+ 7 Longitude 1 sigma error, in meters
+ 8 Height 1 sigma error, in meters
+ 9 The checksum data, always begins with *
+ */
+ double ashtech_time __attribute__((unused)) = 0.0, lat_err = 0.0, lon_err = 0.0, alt_err = 0.0;
+ double min_err __attribute__((unused)) = 0.0, maj_err __attribute__((unused)) = 0.0, deg_from_north __attribute__((unused)) = 0.0, rms_err __attribute__((unused)) = 0.0;
+
+ if (bufptr && *(++bufptr) != ',') { ashtech_time = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { rms_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { maj_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { min_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { deg_from_north = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { lat_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { lon_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { alt_err = strtod(bufptr, &endp); bufptr = endp; }
+
+ _gps_position->eph = sqrt(lat_err * lat_err + lon_err * lon_err);
+ _gps_position->epv = alt_err;
+
+ _gps_position->s_variance_m_s = 0;
+ _gps_position->timestamp_variance = hrt_absolute_time();
+
+ } else if ((memcmp(_rx_buffer + 3, "GSV,", 3) == 0)) {
+ /*
+ The GSV message string identifies the number of SVs in view, the PRN numbers, elevations, azimuths, and SNR values. An example of the GSV message string is:
+
+ $GPGSV,4,1,13,02,02,213,,03,-3,000,,11,00,121,,14,13,172,05*67
+
+ GSV message fields
+ Field Meaning
+ 0 Message ID $GPGSV
+ 1 Total number of messages of this type in this cycle
+ 2 Message number
+ 3 Total number of SVs visible
+ 4 SV PRN number
+ 5 Elevation, in degrees, 90 maximum
+ 6 Azimuth, degrees from True North, 000 through 359
+ 7 SNR, 00 through 99 dB (null when not tracking)
+ 8-11 Information about second SV, same format as fields 4 through 7
+ 12-15 Information about third SV, same format as fields 4 through 7
+ 16-19 Information about fourth SV, same format as fields 4 through 7
+ 20 The checksum data, always begins with *
+ */
+ /*
+ * currently process only gps, because do not know what
+ * Global satellite ID I should use for non GPS sats
+ */
+ bool bGPS = false;
+
+ if (memcmp(_rx_buffer, "$GP", 3) != 0) {
+ return 0;
+
+ } else {
+ bGPS = true;
+ }
+
+ int all_msg_num = 0, this_msg_num = 0, tot_sv_visible = 0;
+ struct gsv_sat {
+ int svid;
+ int elevation;
+ int azimuth;
+ int snr;
+ } sat[4];
+ memset(sat, 0, sizeof(sat));
+
+ if (bufptr && *(++bufptr) != ',') { all_msg_num = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { this_msg_num = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { tot_sv_visible = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if ((this_msg_num < 1) || (this_msg_num > all_msg_num)) {
+ return 0;
+ }
+
+ if ((this_msg_num == 0) && (bGPS == true)) {
+ memset(_satellite_info->svid, 0, sizeof(_satellite_info->svid));
+ memset(_satellite_info->used, 0, sizeof(_satellite_info->used));
+ memset(_satellite_info->snr, 0, sizeof(_satellite_info->snr));
+ memset(_satellite_info->elevation, 0, sizeof(_satellite_info->elevation));
+ memset(_satellite_info->azimuth, 0, sizeof(_satellite_info->azimuth));
+ }
+
+ int end = 4;
+
+ if (this_msg_num == all_msg_num) {
+ end = tot_sv_visible - (this_msg_num - 1) * 4;
+ _gps_position->satellites_used = tot_sv_visible;
+ _satellite_info->count = SAT_INFO_MAX_SATELLITES;
+ _satellite_info->timestamp = hrt_absolute_time();
+ }
+
+ for (int y = 0 ; y < end ; y++) {
+ if (bufptr && *(++bufptr) != ',') { sat[y].svid = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { sat[y].elevation = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { sat[y].azimuth = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ if (bufptr && *(++bufptr) != ',') { sat[y].snr = strtol(bufptr, &endp, 10); bufptr = endp; }
+
+ _satellite_info->svid[y + (this_msg_num - 1) * 4] = sat[y].svid;
+ _satellite_info->used[y + (this_msg_num - 1) * 4] = ((sat[y].snr > 0) ? true : false);
+ _satellite_info->snr[y + (this_msg_num - 1) * 4] = sat[y].snr;
+ _satellite_info->elevation[y + (this_msg_num - 1) * 4] = sat[y].elevation;
+ _satellite_info->azimuth[y + (this_msg_num - 1) * 4] = sat[y].azimuth;
+ }
+ }
+
+ return 0;
+}
+
+
+int ASHTECH::receive(unsigned timeout)
+{
+ {
+ /* poll descriptor */
+ pollfd fds[1];
+ fds[0].fd = _fd;
+ fds[0].events = POLLIN;
+
+ uint8_t buf[32];
+
+ /* timeout additional to poll */
+ uint64_t time_started = hrt_absolute_time();
+
+ int j = 0;
+ ssize_t bytes_count = 0;
+
+ while (true) {
+
+ /* pass received bytes to the packet decoder */
+ while (j < bytes_count) {
+ int l = 0;
+
+ if ((l = parse_char(buf[j])) > 0) {
+ /* return to configure during configuration or to the gps driver during normal work
+ * if a packet has arrived */
+ if (handle_message(l) > 0) {
+ return 1;
+ }
+ }
+
+ /* in case we keep trying but only get crap from GPS */
+ if (time_started + timeout * 1000 * 2 < hrt_absolute_time()) {
+ return -1;
+ }
+
+ j++;
+ }
+
+ /* everything is read */
+ j = bytes_count = 0;
+
+ /* then poll for new data */
+ int ret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), timeout * 2);
+
+ if (ret < 0) {
+ /* something went wrong when polling */
+ return -1;
+
+ } else if (ret == 0) {
+ /* Timeout */
+ return -1;
+
+ } else if (ret > 0) {
+ /* if we have new data from GPS, go handle it */
+ if (fds[0].revents & POLLIN) {
+ /*
+ * We are here because poll says there is some data, so this
+ * won't block even on a blocking device. If more bytes are
+ * available, we'll go back to poll() again...
+ */
+ bytes_count = ::read(_fd, buf, sizeof(buf));
+ }
+ }
+ }
+ }
+
+}
+#define HEXDIGIT_CHAR(d) ((char)((d) + (((d) < 0xA) ? '0' : 'A'-0xA)))
+
+int ASHTECH::parse_char(uint8_t b)
+{
+ int iRet = 0;
+
+ switch (_decode_state) {
+ /* First, look for sync1 */
+ case NME_DECODE_UNINIT:
+ if (b == '$') {
+ _decode_state = NME_DECODE_GOT_SYNC1;
+ _rx_buffer_bytes = 0;
+ _rx_buffer[_rx_buffer_bytes++] = b;
+ }
+
+ break;
+
+ case NME_DECODE_GOT_SYNC1:
+ if (b == '$') {
+ _decode_state = NME_DECODE_GOT_SYNC1;
+ _rx_buffer_bytes = 0;
+
+ } else if (b == '*') {
+ _decode_state = NME_DECODE_GOT_ASTERIKS;
+ }
+
+ if (_rx_buffer_bytes >= (sizeof(_rx_buffer) - 5)) {
+ _decode_state = NME_DECODE_UNINIT;
+ _rx_buffer_bytes = 0;
+
+ } else {
+ _rx_buffer[_rx_buffer_bytes++] = b;
+ }
+
+ break;
+
+ case NME_DECODE_GOT_ASTERIKS:
+ _rx_buffer[_rx_buffer_bytes++] = b;
+ _decode_state = NME_DECODE_GOT_FIRST_CS_BYTE;
+ break;
+
+ case NME_DECODE_GOT_FIRST_CS_BYTE:
+ _rx_buffer[_rx_buffer_bytes++] = b;
+ uint8_t checksum = 0;
+ uint8_t *buffer = _rx_buffer + 1;
+ uint8_t *bufend = _rx_buffer + _rx_buffer_bytes - 3;
+
+ for (; buffer < bufend; buffer++) { checksum ^= *buffer; }
+
+ if ((HEXDIGIT_CHAR(checksum >> 4) == *(_rx_buffer + _rx_buffer_bytes - 2)) &&
+ (HEXDIGIT_CHAR(checksum & 0x0F) == *(_rx_buffer + _rx_buffer_bytes - 1))) {
+ iRet = _rx_buffer_bytes;
+ }
+
+ _decode_state = NME_DECODE_UNINIT;
+ _rx_buffer_bytes = 0;
+ break;
+ }
+
+ return iRet;
+}
+
+void ASHTECH::decode_init(void)
+{
+
+}
+
+/*
+ * ashtech board configuration script
+ */
+
+const char comm[] = "$PASHS,POP,20\r\n"\
+ "$PASHS,NME,ZDA,B,ON,3\r\n"\
+ "$PASHS,NME,GGA,B,OFF\r\n"\
+ "$PASHS,NME,GST,B,ON,3\r\n"\
+ "$PASHS,NME,POS,B,ON,0.05\r\n"\
+ "$PASHS,NME,GSV,B,ON,3\r\n"\
+ "$PASHS,SPD,A,8\r\n"\
+ "$PASHS,SPD,B,9\r\n";
+
+int ASHTECH::configure(unsigned &baudrate)
+{
+ /* try different baudrates */
+ const unsigned baudrates_to_try[] = {9600, 38400, 19200, 57600, 115200};
+
+
+ for (unsigned int baud_i = 0; baud_i < sizeof(baudrates_to_try) / sizeof(baudrates_to_try[0]); baud_i++) {
+ baudrate = baudrates_to_try[baud_i];
+ set_baudrate(_fd, baudrate);
+ write(_fd, (uint8_t *)comm, sizeof(comm));
+ }
+
+ set_baudrate(_fd, 115200);
+ return 0;
+}
diff --git a/src/drivers/gps/ashtech.h b/src/drivers/gps/ashtech.h
new file mode 100644
index 000000000..6ba522b9c
--- /dev/null
+++ b/src/drivers/gps/ashtech.h
@@ -0,0 +1,96 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013. All rights reserved.
+ * Author: Boriskin Aleksey <a.d.boriskin@gmail.com>
+ * Kistanov Alexander <akistanov@gramant.ru>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/* @file ASHTECH protocol definitions */
+
+#ifndef ASHTECH_H_
+#define ASHTECH_H_
+
+#include "gps_helper.h"
+
+#ifndef RECV_BUFFER_SIZE
+#define RECV_BUFFER_SIZE 512
+
+#define SAT_INFO_MAX_SATELLITES 20
+#endif
+
+
+class ASHTECH : public GPS_Helper
+{
+ enum ashtech_decode_state_t {
+ NME_DECODE_UNINIT,
+ NME_DECODE_GOT_SYNC1,
+ NME_DECODE_GOT_ASTERIKS,
+ NME_DECODE_GOT_FIRST_CS_BYTE
+ };
+
+ int _fd;
+ struct satellite_info_s *_satellite_info;
+ struct vehicle_gps_position_s *_gps_position;
+ int ashtechlog_fd;
+
+ ashtech_decode_state_t _decode_state;
+ uint8_t _rx_buffer[RECV_BUFFER_SIZE];
+ uint16_t _rx_buffer_bytes;
+ bool _parse_error; /** parse error flag */
+ char *_parse_pos; /** parse position */
+
+ bool _gsv_in_progress; /**< Indicates that gsv data parsing is in progress */
+ /* int _satellites_count; **< Number of satellites info parsed. */
+ uint8_t count; /**< Number of satellites in satellite info */
+ uint8_t svid[SAT_INFO_MAX_SATELLITES]; /**< Space vehicle ID [1..255], see scheme below */
+ uint8_t used[SAT_INFO_MAX_SATELLITES]; /**< 0: Satellite not used, 1: used for navigation */
+ uint8_t elevation[SAT_INFO_MAX_SATELLITES]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
+ uint8_t azimuth[SAT_INFO_MAX_SATELLITES]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
+ uint8_t snr[SAT_INFO_MAX_SATELLITES]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */
+
+public:
+ ASHTECH(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info);
+ ~ASHTECH();
+ int receive(unsigned timeout);
+ int configure(unsigned &baudrate);
+ void decode_init(void);
+ int handle_message(int len);
+ int parse_char(uint8_t b);
+ /** Read int ASHTECH parameter */
+ int32_t read_int();
+ /** Read float ASHTECH parameter */
+ double read_float();
+ /** Read char ASHTECH parameter */
+ char read_char();
+
+};
+
+#endif /* ASHTECH_H_ */
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index 34dd63086..5fb4b9ff8 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -69,6 +69,7 @@
#include "ubx.h"
#include "mtk.h"
+#include "ashtech.h"
#define TIMEOUT_5HZ 500
@@ -341,6 +342,10 @@ GPS::task_main()
_Helper = new MTK(_serial_fd, &_report_gps_pos);
break;
+ case GPS_DRIVER_MODE_ASHTECH:
+ _Helper = new ASHTECH(_serial_fd, &_report_gps_pos, _p_report_sat_info);
+ break;
+
default:
break;
}
@@ -402,6 +407,10 @@ GPS::task_main()
mode_str = "MTK";
break;
+ case GPS_DRIVER_MODE_ASHTECH:
+ mode_str = "ASHTECH";
+ break;
+
default:
break;
}
@@ -429,6 +438,10 @@ GPS::task_main()
break;
case GPS_DRIVER_MODE_MTK:
+ _mode = GPS_DRIVER_MODE_ASHTECH;
+ break;
+
+ case GPS_DRIVER_MODE_ASHTECH:
_mode = GPS_DRIVER_MODE_UBX;
break;
@@ -475,6 +488,10 @@ GPS::print_info()
warnx("protocol: MTK");
break;
+ case GPS_DRIVER_MODE_ASHTECH:
+ warnx("protocol: ASHTECH");
+ break;
+
default:
break;
}
diff --git a/src/drivers/gps/module.mk b/src/drivers/gps/module.mk
index b00818424..4f99b0d3b 100644
--- a/src/drivers/gps/module.mk
+++ b/src/drivers/gps/module.mk
@@ -40,6 +40,7 @@ MODULE_COMMAND = gps
SRCS = gps.cpp \
gps_helper.cpp \
mtk.cpp \
+ ashtech.cpp \
ubx.cpp
MODULE_STACKSIZE = 1200
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index d0854f5e9..b0eb4ab66 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -189,6 +189,18 @@ UBX::configure(unsigned &baudrate)
return 1;
}
+#ifdef UBX_CONFIGURE_SBAS
+ /* send a SBAS message to set the SBAS options */
+ memset(&_buf.payload_tx_cfg_sbas, 0, sizeof(_buf.payload_tx_cfg_sbas));
+ _buf.payload_tx_cfg_sbas.mode = UBX_TX_CFG_SBAS_MODE;
+
+ send_message(UBX_MSG_CFG_SBAS, _buf.raw, sizeof(_buf.payload_tx_cfg_sbas));
+
+ if (wait_for_ack(UBX_MSG_CFG_SBAS, UBX_CONFIG_TIMEOUT, true) < 0) {
+ return 1;
+ }
+#endif
+
/* configure message rates */
/* the last argument is divisor for measurement rate (set by CFG RATE), i.e. 1 means 5Hz */
diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h
index 219a5762a..c74eb9168 100644
--- a/src/drivers/gps/ubx.h
+++ b/src/drivers/gps/ubx.h
@@ -73,6 +73,7 @@
#define UBX_ID_CFG_MSG 0x01
#define UBX_ID_CFG_RATE 0x08
#define UBX_ID_CFG_NAV5 0x24
+#define UBX_ID_CFG_SBAS 0x16
#define UBX_ID_MON_VER 0x04
#define UBX_ID_MON_HW 0x09
@@ -89,6 +90,7 @@
#define UBX_MSG_CFG_MSG ((UBX_CLASS_CFG) | UBX_ID_CFG_MSG << 8)
#define UBX_MSG_CFG_RATE ((UBX_CLASS_CFG) | UBX_ID_CFG_RATE << 8)
#define UBX_MSG_CFG_NAV5 ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8)
+#define UBX_MSG_CFG_SBAS ((UBX_CLASS_CFG) | UBX_ID_CFG_SBAS << 8)
#define UBX_MSG_MON_HW ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8)
#define UBX_MSG_MON_VER ((UBX_CLASS_MON) | UBX_ID_MON_VER << 8)
@@ -128,6 +130,11 @@
#define UBX_TX_CFG_NAV5_DYNMODEL 7 /**< 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g */
#define UBX_TX_CFG_NAV5_FIXMODE 2 /**< 1 2D only, 2 3D only, 3 Auto 2D/3D */
+/* TX CFG-SBAS message contents */
+#define UBX_TX_CFG_SBAS_MODE_ENABLED 1 /**< SBAS enabled */
+#define UBX_TX_CFG_SBAS_MODE_DISABLED 0 /**< SBAS disabled */
+#define UBX_TX_CFG_SBAS_MODE UBX_TX_CFG_SBAS_MODE_DISABLED /**< SBAS enabled or disabled */
+
/* TX CFG-MSG message contents */
#define UBX_TX_CFG_MSG_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
#define UBX_TX_CFG_MSG_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */
@@ -383,6 +390,15 @@ typedef struct {
uint32_t reserved4;
} ubx_payload_tx_cfg_nav5_t;
+/* tx cfg-sbas */
+typedef struct {
+ uint8_t mode;
+ uint8_t usage;
+ uint8_t maxSBAS;
+ uint8_t scanmode2;
+ uint32_t scanmode1;
+} ubx_payload_tx_cfg_sbas_t;
+
/* Tx CFG-MSG */
typedef struct {
union {
@@ -413,6 +429,7 @@ typedef union {
ubx_payload_tx_cfg_prt_t payload_tx_cfg_prt;
ubx_payload_tx_cfg_rate_t payload_tx_cfg_rate;
ubx_payload_tx_cfg_nav5_t payload_tx_cfg_nav5;
+ ubx_payload_tx_cfg_sbas_t payload_tx_cfg_sbas;
ubx_payload_tx_cfg_msg_t payload_tx_cfg_msg;
uint8_t raw[];
} ubx_buf_t;
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index f17e99e9d..f0dc0c651 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -392,7 +392,8 @@ HIL::task_main()
if (fds[0].revents & POLLIN) {
/* get controls - must always do this to avoid spinning */
- orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _t_actuators, &_controls);
+ orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
+ ORB_ID(actuator_controls_1), _t_actuators, &_controls);
/* can we mix? */
if (_mixers != nullptr) {
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 0e9a961ac..81f767965 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -1049,11 +1049,9 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
* LSM/Ga, giving 1.16 and 1.08 */
float expected_cal[3] = { 1.16f, 1.08f, 1.08f };
- warnx("starting mag scale calibration");
-
/* start the sensor polling at 50 Hz */
if (OK != ioctl(filp, SENSORIOCSPOLLRATE, 50)) {
- warn("failed to set 2Hz poll rate");
+ warn("FAILED: SENSORIOCSPOLLRATE 2Hz");
ret = 1;
goto out;
}
@@ -1061,25 +1059,25 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
/* Set to 2.5 Gauss. We ask for 3 to get the right part of
* the chained if statement above. */
if (OK != ioctl(filp, MAGIOCSRANGE, 3)) {
- warnx("failed to set 2.5 Ga range");
+ warnx("FAILED: MAGIOCSRANGE 3.3 Ga");
ret = 1;
goto out;
}
if (OK != ioctl(filp, MAGIOCEXSTRAP, 1)) {
- warnx("failed to enable sensor calibration mode");
+ warnx("FAILED: MAGIOCEXSTRAP 1");
ret = 1;
goto out;
}
if (OK != ioctl(filp, MAGIOCGSCALE, (long unsigned int)&mscale_previous)) {
- warn("WARNING: failed to get scale / offsets for mag");
+ warn("FAILED: MAGIOCGSCALE 1");
ret = 1;
goto out;
}
if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
- warn("WARNING: failed to set null scale / offsets for mag");
+ warn("FAILED: MAGIOCSSCALE 1");
ret = 1;
goto out;
}
@@ -1094,7 +1092,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
ret = ::poll(&fds, 1, 2000);
if (ret != 1) {
- warn("timed out waiting for sensor data");
+ warn("ERROR: TIMEOUT 1");
goto out;
}
@@ -1102,7 +1100,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
sz = ::read(fd, &report, sizeof(report));
if (sz != sizeof(report)) {
- warn("periodic read failed");
+ warn("ERROR: READ 1");
ret = -EIO;
goto out;
}
@@ -1118,7 +1116,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
ret = ::poll(&fds, 1, 2000);
if (ret != 1) {
- warn("timed out waiting for sensor data");
+ warn("ERROR: TIMEOUT 2");
goto out;
}
@@ -1126,7 +1124,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
sz = ::read(fd, &report, sizeof(report));
if (sz != sizeof(report)) {
- warn("periodic read failed");
+ warn("ERROR: READ 2");
ret = -EIO;
goto out;
}
@@ -1142,33 +1140,19 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
sum_excited[1] += cal[1];
sum_excited[2] += cal[2];
}
-
- //warnx("periodic read %u", i);
- //warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z);
- //warnx("cal: %.6f %.6f %.6f", (double)cal[0], (double)cal[1], (double)cal[2]);
}
if (good_count < 5) {
- warn("failed calibration");
ret = -EIO;
goto out;
}
-#if 0
- warnx("measurement avg: %.6f %.6f %.6f",
- (double)sum_excited[0]/good_count,
- (double)sum_excited[1]/good_count,
- (double)sum_excited[2]/good_count);
-#endif
-
float scaling[3];
scaling[0] = sum_excited[0] / good_count;
scaling[1] = sum_excited[1] / good_count;
scaling[2] = sum_excited[2] / good_count;
- warnx("axes scaling: %.6f %.6f %.6f", (double)scaling[0], (double)scaling[1], (double)scaling[2]);
-
/* set scaling in device */
mscale_previous.x_scale = scaling[0];
mscale_previous.y_scale = scaling[1];
@@ -1179,29 +1163,26 @@ int HMC5883::calibrate(struct file *filp, unsigned enable)
out:
if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_previous)) {
- warn("failed to set new scale / offsets for mag");
+ warn("FAILED: MAGIOCSSCALE 2");
}
/* set back to normal mode */
/* Set to 1.1 Gauss */
if (OK != ::ioctl(fd, MAGIOCSRANGE, 1)) {
- warnx("failed to set 1.1 Ga range");
+ warnx("FAILED: MAGIOCSRANGE 1.1 Ga");
}
if (OK != ::ioctl(fd, MAGIOCEXSTRAP, 0)) {
- warnx("failed to disable sensor calibration mode");
+ warnx("FAILED: MAGIOCEXSTRAP 0");
}
if (ret == OK) {
- if (!check_scale()) {
- warnx("mag scale calibration successfully finished.");
- } else {
- warnx("mag scale calibration finished with invalid results.");
+ if (check_scale()) {
+ /* failed */
+ warnx("FAILED: SCALE");
ret = ERROR;
}
- } else {
- warnx("mag scale calibration failed.");
}
return ret;
@@ -1283,14 +1264,13 @@ int HMC5883::set_excitement(unsigned enable)
if (OK != ret)
perf_count(_comms_errors);
+ _conf_reg &= ~0x03; // reset previous excitement mode
if (((int)enable) < 0) {
_conf_reg |= 0x01;
} else if (enable > 0) {
_conf_reg |= 0x02;
- } else {
- _conf_reg &= ~0x03;
}
// ::printf("set_excitement enable=%d regA=0x%x\n", (int)enable, (unsigned)_conf_reg);
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
index 086132573..f1b12b067 100644
--- a/src/drivers/hott/messages.cpp
+++ b/src/drivers/hott/messages.cpp
@@ -115,9 +115,9 @@ publish_gam_message(const uint8_t *buffer)
esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
- esc.esc[0].esc_temperature = msg.temperature1 - 20;
- esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
- esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
+ esc.esc[0].esc_temperature = static_cast<float>(msg.temperature1) - 20.0F;
+ esc.esc[0].esc_voltage = static_cast<float>((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff)) * 0.1F;
+ esc.esc[0].esc_current = static_cast<float>((msg.current_H << 8) | (msg.current_L & 0xff)) * 0.1F;
/* announce the esc if needed, just publish else */
if (_esc_pub > 0) {
@@ -186,18 +186,18 @@ build_gam_response(uint8_t *buffer, size_t *size)
msg.gam_sensor_id = GAM_SENSOR_ID;
msg.sensor_text_id = GAM_SENSOR_TEXT_ID;
- msg.temperature1 = (uint8_t)(esc.esc[0].esc_temperature + 20);
+ msg.temperature1 = (uint8_t)(esc.esc[0].esc_temperature + 20.0F);
msg.temperature2 = 20; // 0 deg. C.
- uint16_t voltage = (uint16_t)(esc.esc[0].esc_voltage);
+ const uint16_t voltage = (uint16_t)(esc.esc[0].esc_voltage * 10.0F);
msg.main_voltage_L = (uint8_t)voltage & 0xff;
msg.main_voltage_H = (uint8_t)(voltage >> 8) & 0xff;
- uint16_t current = (uint16_t)(esc.esc[0].esc_current);
+ const uint16_t current = (uint16_t)(esc.esc[0].esc_current * 10.0F);
msg.current_L = (uint8_t)current & 0xff;
msg.current_H = (uint8_t)(current >> 8) & 0xff;
- uint16_t rpm = (uint16_t)(esc.esc[0].esc_rpm * 0.1f);
+ const uint16_t rpm = (uint16_t)(esc.esc[0].esc_rpm * 0.1f);
msg.rpm_L = (uint8_t)rpm & 0xff;
msg.rpm_H = (uint8_t)(rpm >> 8) & 0xff;
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index cfae8761c..82fa5cc6e 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -176,6 +176,7 @@ static const int ERROR = -1;
#define L3G4200D_DEFAULT_RATE 800
#define L3GD20_DEFAULT_RANGE_DPS 2000
#define L3GD20_DEFAULT_FILTER_FREQ 30
+#define L3GD20_TEMP_OFFSET_CELSIUS 40
#ifndef SENSOR_BOARD_ROTATION_DEFAULT
#define SENSOR_BOARD_ROTATION_DEFAULT SENSOR_BOARD_ROTATION_270_DEG
@@ -856,7 +857,7 @@ L3GD20::measure()
#pragma pack(push, 1)
struct {
uint8_t cmd;
- uint8_t temp;
+ int8_t temp;
uint8_t status;
int16_t x;
int16_t y;
@@ -930,6 +931,8 @@ L3GD20::measure()
report.z_raw = raw_report.z;
+ report.temperature_raw = raw_report.temp;
+
report.x = ((report.x_raw * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
report.y = ((report.y_raw * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
report.z = ((report.z_raw * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
@@ -938,6 +941,8 @@ L3GD20::measure()
report.y = _gyro_filter_y.apply(report.y);
report.z = _gyro_filter_z.apply(report.z);
+ report.temperature = L3GD20_TEMP_OFFSET_CELSIUS - raw_report.temp;
+
// apply user specified rotation
rotate_3f(_rotation, report.x, report.y, report.z);
@@ -1091,9 +1096,11 @@ test()
warnx("gyro x: \t% 9.5f\trad/s", (double)g_report.x);
warnx("gyro y: \t% 9.5f\trad/s", (double)g_report.y);
warnx("gyro z: \t% 9.5f\trad/s", (double)g_report.z);
+ warnx("temp: \t%d\tC", (int)g_report.temperature);
warnx("gyro x: \t%d\traw", (int)g_report.x_raw);
warnx("gyro y: \t%d\traw", (int)g_report.y_raw);
warnx("gyro z: \t%d\traw", (int)g_report.z_raw);
+ warnx("temp: \t%d\traw", (int)g_report.temperature_raw);
warnx("gyro range: %8.4f rad/s (%d deg/s)", (double)g_report.range_rad_s,
(int)((g_report.range_rad_s / M_PI_F) * 180.0f + 0.5f));
diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp
index a69e6ee55..6793acd81 100644
--- a/src/drivers/ll40ls/ll40ls.cpp
+++ b/src/drivers/ll40ls/ll40ls.cpp
@@ -73,14 +73,19 @@
/* Configuration Constants */
#define LL40LS_BUS PX4_I2C_BUS_EXPANSION
-#define LL40LS_BASEADDR 0x42 /* 7-bit address */
-#define LL40LS_DEVICE_PATH "/dev/ll40ls"
+#define LL40LS_BASEADDR 0x62 /* 7-bit address */
+#define LL40LS_BASEADDR_OLD 0x42 /* previous 7-bit address */
+#define LL40LS_DEVICE_PATH_INT "/dev/ll40ls_int"
+#define LL40LS_DEVICE_PATH_EXT "/dev/ll40ls_ext"
/* LL40LS Registers addresses */
#define LL40LS_MEASURE_REG 0x00 /* Measure range register */
-#define LL40LS_MSRREG_ACQUIRE 0x04 /* Value to initiate a measurement, varies based on sensor revision */
+#define LL40LS_MSRREG_ACQUIRE 0x04 /* Value to initiate a measurement, varies based on sensor revision */
#define LL40LS_DISTHIGH_REG 0x8F /* High byte of distance register, auto increment */
+#define LL40LS_WHO_AM_I_REG 0x11
+#define LL40LS_WHO_AM_I_REG_VAL 0xCA
+#define LL40LS_SIGNAL_STRENGTH_REG 0x5b
/* Device limits */
#define LL40LS_MIN_DISTANCE (0.00f)
@@ -101,7 +106,7 @@ static const int ERROR = -1;
class LL40LS : public device::I2C
{
public:
- LL40LS(int bus = LL40LS_BUS, int address = LL40LS_BASEADDR);
+ LL40LS(int bus, const char *path, int address = LL40LS_BASEADDR);
virtual ~LL40LS();
virtual int init();
@@ -116,6 +121,7 @@ public:
protected:
virtual int probe();
+ virtual int read_reg(uint8_t reg, uint8_t &val);
private:
float _min_distance;
@@ -132,6 +138,10 @@ private:
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
+ uint16_t _last_distance;
+
+ /**< the bus the device is connected to */
+ int _bus;
/**
* Test whether the device supported by the driver is present at a
@@ -188,8 +198,8 @@ private:
*/
extern "C" __EXPORT int ll40ls_main(int argc, char *argv[]);
-LL40LS::LL40LS(int bus, int address) :
- I2C("LL40LS", LL40LS_DEVICE_PATH, bus, address, 100000),
+LL40LS::LL40LS(int bus, const char *path, int address) :
+ I2C("LL40LS", path, bus, address, 100000),
_min_distance(LL40LS_MIN_DISTANCE),
_max_distance(LL40LS_MAX_DISTANCE),
_reports(nullptr),
@@ -200,10 +210,12 @@ LL40LS::LL40LS(int bus, int address) :
_range_finder_topic(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "ll40ls_read")),
_comms_errors(perf_alloc(PC_COUNT, "ll40ls_comms_errors")),
- _buffer_overflows(perf_alloc(PC_COUNT, "ll40ls_buffer_overflows"))
+ _buffer_overflows(perf_alloc(PC_COUNT, "ll40ls_buffer_overflows")),
+ _last_distance(0),
+ _bus(bus)
{
// up the retries since the device misses the first measure attempts
- I2C::_retries = 3;
+ _retries = 3;
// enable debug() calls
_debug_enabled = false;
@@ -271,8 +283,50 @@ out:
}
int
+LL40LS::read_reg(uint8_t reg, uint8_t &val)
+{
+ return transfer(&reg, 1, &val, 1);
+}
+
+int
LL40LS::probe()
{
+ // cope with both old and new I2C bus address
+ const uint8_t addresses[2] = {LL40LS_BASEADDR, LL40LS_BASEADDR_OLD};
+
+ // more retries for detection
+ _retries = 10;
+
+ for (uint8_t i=0; i<sizeof(addresses); i++) {
+ uint8_t val=0, who_am_i=0;
+
+ // set the I2C bus address
+ set_address(addresses[i]);
+
+ if (read_reg(LL40LS_WHO_AM_I_REG, who_am_i) == OK && who_am_i == LL40LS_WHO_AM_I_REG_VAL) {
+ // it is responding correctly to a WHO_AM_I
+ goto ok;
+ }
+
+ if (read_reg(LL40LS_SIGNAL_STRENGTH_REG, val) == OK && val != 0) {
+ // very likely to be a ll40ls. px4flow does not
+ // respond to this
+ goto ok;
+ }
+
+ debug("WHO_AM_I byte mismatch 0x%02x should be 0x%02x val=0x%02x\n",
+ (unsigned)who_am_i,
+ LL40LS_WHO_AM_I_REG_VAL,
+ (unsigned)val);
+ }
+
+ // not found on any address
+ return -EIO;
+
+ok:
+ _retries = 3;
+
+ // start a measurement
return measure();
}
@@ -521,6 +575,8 @@ LL40LS::collect()
float si_units = distance * 0.01f; /* cm to m */
struct range_finder_report report;
+ _last_distance = distance;
+
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
@@ -648,6 +704,8 @@ LL40LS::print_info()
perf_print_counter(_buffer_overflows);
printf("poll interval: %u ticks\n", _measure_ticks);
_reports->print_info("report queue");
+ printf("distance: %ucm (0x%04x)\n",
+ (unsigned)_last_distance, (unsigned)_last_distance);
}
/**
@@ -662,55 +720,89 @@ namespace ll40ls
#endif
const int ERROR = -1;
-LL40LS *g_dev;
+LL40LS *g_dev_int;
+LL40LS *g_dev_ext;
-void start();
-void stop();
-void test();
-void reset();
-void info();
+void start(int bus);
+void stop(int bus);
+void test(int bus);
+void reset(int bus);
+void info(int bus);
+void usage();
/**
* Start the driver.
*/
void
-start()
+start(int bus)
{
- int fd;
-
- if (g_dev != nullptr) {
- errx(1, "already started");
+ /* create the driver, attempt expansion bus first */
+ if (bus == -1 || bus == PX4_I2C_BUS_EXPANSION) {
+ if (g_dev_ext != nullptr)
+ errx(0, "already started external");
+ g_dev_ext = new LL40LS(PX4_I2C_BUS_EXPANSION, LL40LS_DEVICE_PATH_EXT);
+ if (g_dev_ext != nullptr && OK != g_dev_ext->init()) {
+ delete g_dev_ext;
+ g_dev_ext = nullptr;
+ }
}
- /* create the driver */
- g_dev = new LL40LS(LL40LS_BUS);
-
- if (g_dev == nullptr) {
- goto fail;
- }
+#ifdef PX4_I2C_BUS_ONBOARD
+ /* if this failed, attempt onboard sensor */
+ if (bus == -1 || bus == PX4_I2C_BUS_ONBOARD) {
+ if (g_dev_int != nullptr)
+ errx(0, "already started internal");
+ g_dev_int = new LL40LS(PX4_I2C_BUS_ONBOARD, LL40LS_DEVICE_PATH_INT);
+ if (g_dev_int != nullptr && OK != g_dev_int->init()) {
+ /* tear down the failing onboard instance */
+ delete g_dev_int;
+ g_dev_int = nullptr;
- if (OK != g_dev->init()) {
- goto fail;
+ if (bus == PX4_I2C_BUS_ONBOARD) {
+ goto fail;
+ }
+ }
+ if (g_dev_int == nullptr && bus == PX4_I2C_BUS_ONBOARD) {
+ goto fail;
+ }
}
+#endif
/* set the poll rate to default, starts automatic data collection */
- fd = open(LL40LS_DEVICE_PATH, O_RDONLY);
-
- if (fd < 0) {
- goto fail;
- }
-
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
- goto fail;
- }
+ if (g_dev_int != nullptr) {
+ int fd = open(LL40LS_DEVICE_PATH_INT, O_RDONLY);
+ if (fd == -1) {
+ goto fail;
+ }
+ int ret = ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT);
+ close(fd);
+ if (ret < 0) {
+ goto fail;
+ }
+ }
+
+ if (g_dev_ext != nullptr) {
+ int fd = open(LL40LS_DEVICE_PATH_EXT, O_RDONLY);
+ if (fd == -1) {
+ goto fail;
+ }
+ int ret = ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT);
+ close(fd);
+ if (ret < 0) {
+ goto fail;
+ }
+ }
exit(0);
fail:
-
- if (g_dev != nullptr) {
- delete g_dev;
- g_dev = nullptr;
+ if (g_dev_int != nullptr && (bus == -1 || bus == PX4_I2C_BUS_ONBOARD)) {
+ delete g_dev_int;
+ g_dev_int = nullptr;
+ }
+ if (g_dev_ext != nullptr && (bus == -1 || bus == PX4_I2C_BUS_EXPANSION)) {
+ delete g_dev_ext;
+ g_dev_ext = nullptr;
}
errx(1, "driver start failed");
@@ -719,11 +811,12 @@ fail:
/**
* Stop the driver
*/
-void stop()
+void stop(int bus)
{
- if (g_dev != nullptr) {
- delete g_dev;
- g_dev = nullptr;
+ LL40LS **g_dev = (bus == PX4_I2C_BUS_ONBOARD?&g_dev_int:&g_dev_ext);
+ if (*g_dev != nullptr) {
+ delete *g_dev;
+ *g_dev = nullptr;
} else {
errx(1, "driver not running");
@@ -738,16 +831,17 @@ void stop()
* and automatic modes.
*/
void
-test()
+test(int bus)
{
struct range_finder_report report;
ssize_t sz;
int ret;
+ const char *path = (bus==PX4_I2C_BUS_ONBOARD?LL40LS_DEVICE_PATH_INT:LL40LS_DEVICE_PATH_EXT);
- int fd = open(LL40LS_DEVICE_PATH, O_RDONLY);
+ int fd = open(path, O_RDONLY);
if (fd < 0) {
- err(1, "%s open failed (try 'll40ls start' if the driver is not running", LL40LS_DEVICE_PATH);
+ err(1, "%s open failed (try 'll40ls start' if the driver is not running", path);
}
/* do a simple demand read */
@@ -803,9 +897,10 @@ test()
* Reset the driver.
*/
void
-reset()
+reset(int bus)
{
- int fd = open(LL40LS_DEVICE_PATH, O_RDONLY);
+ const char *path = (bus==PX4_I2C_BUS_ONBOARD?LL40LS_DEVICE_PATH_INT:LL40LS_DEVICE_PATH_EXT);
+ int fd = open(path, O_RDONLY);
if (fd < 0) {
err(1, "failed ");
@@ -826,8 +921,9 @@ reset()
* Print a little info about the driver.
*/
void
-info()
+info(int bus)
{
+ LL40LS *g_dev = (bus == PX4_I2C_BUS_ONBOARD?g_dev_int:g_dev_ext);
if (g_dev == nullptr) {
errx(1, "driver not running");
}
@@ -838,44 +934,76 @@ info()
exit(0);
}
+void
+usage()
+{
+ warnx("missing command: try 'start', 'stop', 'info', 'test', 'reset', 'info'");
+ warnx("options:");
+ warnx(" -X only external bus");
+#ifdef PX4_I2C_BUS_ONBOARD
+ warnx(" -I only internal bus");
+#endif
+}
+
} // namespace
int
ll40ls_main(int argc, char *argv[])
{
+ int ch;
+ int bus = -1;
+
+ while ((ch = getopt(argc, argv, "XI")) != EOF) {
+ switch (ch) {
+#ifdef PX4_I2C_BUS_ONBOARD
+ case 'I':
+ bus = PX4_I2C_BUS_ONBOARD;
+ break;
+#endif
+ case 'X':
+ bus = PX4_I2C_BUS_EXPANSION;
+ break;
+ default:
+ ll40ls::usage();
+ exit(0);
+ }
+ }
+
+ const char *verb = argv[optind];
+
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start")) {
- ll40ls::start();
+ if (!strcmp(verb, "start")) {
+ ll40ls::start(bus);
}
/*
* Stop the driver
*/
- if (!strcmp(argv[1], "stop")) {
- ll40ls::stop();
+ if (!strcmp(verb, "stop")) {
+ ll40ls::stop(bus);
}
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test")) {
- ll40ls::test();
+ if (!strcmp(verb, "test")) {
+ ll40ls::test(bus);
}
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset")) {
- ll40ls::reset();
+ if (!strcmp(verb, "reset")) {
+ ll40ls::reset(bus);
}
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
- ll40ls::info();
+ if (!strcmp(verb, "info") || !strcmp(verb, "status")) {
+ ll40ls::info(bus);
}
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 6880cf0f8..01c89192a 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -1519,8 +1519,10 @@ LSM303D::measure()
{
// if the accel doesn't have any data ready then re-schedule
// for 100 microseconds later. This ensures we don't double
- // read a value and then miss the next value
- if (stm32_gpioread(GPIO_EXTI_ACCEL_DRDY) == 0) {
+ // read a value and then miss the next value.
+ // Note that DRDY is not available when the lsm303d is
+ // connected on the external bus
+ if (_bus == PX4_SPI_BUS_SENSORS && stm32_gpioread(GPIO_EXTI_ACCEL_DRDY) == 0) {
perf_count(_accel_reschedules);
hrt_call_delay(&_accel_call, 100);
return;
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
index 9cfa7f383..1d9a463ad 100644
--- a/src/drivers/meas_airspeed/meas_airspeed.cpp
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -103,7 +103,7 @@
/* Measurement rate is 100Hz */
#define MEAS_RATE 100
-#define MEAS_DRIVER_FILTER_FREQ 1.5f
+#define MEAS_DRIVER_FILTER_FREQ 1.2f
#define CONVERSION_INTERVAL (1000000 / MEAS_RATE) /* microseconds */
class MEASAirspeed : public Airspeed
@@ -228,44 +228,23 @@ MEASAirspeed::collect()
// the raw value still should be compensated for the known offset
diff_press_pa_raw -= _diff_pres_offset;
- float diff_press_pa = fabsf(diff_press_pa_raw);
-
/*
- note that we return both the absolute value with offset
- applied and a raw value without the offset applied. This
- makes it possible for higher level code to detect if the
- user has the tubes connected backwards, and also makes it
- possible to correctly use offsets calculated by a higher
- level airspeed driver.
-
With the above calculation the MS4525 sensor will produce a
positive number when the top port is used as a dynamic port
and bottom port is used as the static port
-
- Also note that the _diff_pres_offset is applied before the
- fabsf() not afterwards. It needs to be done this way to
- prevent a bias at low speeds, but this also means that when
- setting a offset you must set it based on the raw value, not
- the offset value
*/
-
+
struct differential_pressure_s report;
/* track maximum differential pressure measured (so we can work out top speed). */
- if (diff_press_pa > _max_differential_pressure_pa) {
- _max_differential_pressure_pa = diff_press_pa;
+ if (diff_press_pa_raw > _max_differential_pressure_pa) {
+ _max_differential_pressure_pa = diff_press_pa_raw;
}
report.timestamp = hrt_absolute_time();
report.error_count = perf_event_count(_comms_errors);
report.temperature = temperature;
- report.differential_pressure_pa = diff_press_pa;
- report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa);
-
- /* the dynamics of the filter can make it overshoot into the negative range */
- if (report.differential_pressure_filtered_pa < 0.0f) {
- report.differential_pressure_filtered_pa = _filter.reset(diff_press_pa);
- }
+ report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa_raw);
report.differential_pressure_raw_pa = diff_press_pa_raw;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
@@ -345,7 +324,7 @@ MEASAirspeed::cycle()
/**
correct for 5V rail voltage if the system_power ORB topic is
available
-
+
See http://uav.tridgell.net/MS4525/MS4525-offset.png for a graph of
offset versus voltage for 3 sensors
*/
@@ -394,7 +373,7 @@ MEASAirspeed::voltage_correction(float &diff_press_pa, float &temperature)
if (voltage_diff < -1.0f) {
voltage_diff = -1.0f;
}
- temperature -= voltage_diff * temp_slope;
+ temperature -= voltage_diff * temp_slope;
#endif // CONFIG_ARCH_BOARD_PX4FMU_V2
}
@@ -523,7 +502,7 @@ test()
}
warnx("single read");
- warnx("diff pressure: %d pa", (int)report.differential_pressure_pa);
+ warnx("diff pressure: %d pa", (int)report.differential_pressure_filtered_pa);
/* start the sensor polling at 2Hz */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
@@ -551,7 +530,7 @@ test()
}
warnx("periodic read %u", i);
- warnx("diff pressure: %d pa", (int)report.differential_pressure_pa);
+ warnx("diff pressure: %d pa", (int)report.differential_pressure_filtered_pa);
warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature);
}
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index 3996b76a6..1055487cb 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -600,8 +600,8 @@ MK::task_main()
esc.esc[i].esc_address = (uint8_t) BLCTRL_BASE_ADDR + i;
esc.esc[i].esc_vendor = ESC_VENDOR_MIKROKOPTER;
esc.esc[i].esc_version = (uint16_t) Motor[i].Version;
- esc.esc[i].esc_voltage = (uint16_t) 0;
- esc.esc[i].esc_current = (uint16_t) Motor[i].Current;
+ esc.esc[i].esc_voltage = 0.0F;
+ esc.esc[i].esc_current = static_cast<float>(Motor[i].Current) * 0.1F;
esc.esc[i].esc_rpm = (uint16_t) 0;
esc.esc[i].esc_setpoint = (float) Motor[i].SetPoint_PX4;
@@ -614,7 +614,7 @@ MK::task_main()
esc.esc[i].esc_setpoint_raw = (uint16_t) Motor[i].SetPoint;
}
- esc.esc[i].esc_temperature = (uint16_t) Motor[i].Temperature;
+ esc.esc[i].esc_temperature = static_cast<float>(Motor[i].Temperature);
esc.esc[i].esc_state = (uint16_t) Motor[i].State;
esc.esc[i].esc_errorcount = (uint16_t) 0;
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 6f5dae7ad..a95e041a1 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -229,6 +229,7 @@ private:
perf_counter_t _gyro_reads;
perf_counter_t _sample_perf;
perf_counter_t _bad_transfers;
+ perf_counter_t _good_transfers;
math::LowPassFilter2p _accel_filter_x;
math::LowPassFilter2p _accel_filter_y;
@@ -404,6 +405,7 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev
_gyro_reads(perf_alloc(PC_COUNT, "mpu6000_gyro_read")),
_sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")),
_bad_transfers(perf_alloc(PC_COUNT, "mpu6000_bad_transfers")),
+ _good_transfers(perf_alloc(PC_COUNT, "mpu6000_good_transfers")),
_accel_filter_x(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
_accel_filter_y(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
_accel_filter_z(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ),
@@ -456,6 +458,7 @@ MPU6000::~MPU6000()
perf_free(_accel_reads);
perf_free(_gyro_reads);
perf_free(_bad_transfers);
+ perf_free(_good_transfers);
}
int
@@ -910,12 +913,14 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
// adjust filters
float cutoff_freq_hz = _accel_filter_x.get_cutoff_freq();
float sample_rate = 1.0e6f/ticks;
+ _set_dlpf_filter(cutoff_freq_hz);
_accel_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
_accel_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
_accel_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
float cutoff_freq_hz_gyro = _gyro_filter_x.get_cutoff_freq();
+ _set_dlpf_filter(cutoff_freq_hz_gyro);
_gyro_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
_gyro_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
_gyro_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
@@ -968,11 +973,9 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
return _accel_filter_x.get_cutoff_freq();
case ACCELIOCSLOWPASS:
- if (arg == 0) {
- // allow disabling of on-chip filter using
- // zero as desired filter frequency
- _set_dlpf_filter(0);
- }
+ // set hardware filtering
+ _set_dlpf_filter(arg);
+ // set software filtering
_accel_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_accel_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_accel_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
@@ -1053,14 +1056,11 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
case GYROIOCGLOWPASS:
return _gyro_filter_x.get_cutoff_freq();
case GYROIOCSLOWPASS:
+ // set hardware filtering
+ _set_dlpf_filter(arg);
_gyro_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_gyro_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
_gyro_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
- if (arg == 0) {
- // allow disabling of on-chip filter using 0
- // as desired frequency
- _set_dlpf_filter(0);
- }
return OK;
case GYROIOCSSCALE:
@@ -1282,8 +1282,14 @@ MPU6000::measure()
// all zero data - probably a SPI bus error
perf_count(_bad_transfers);
perf_end(_sample_perf);
+ // note that we don't call reset() here as a reset()
+ // costs 20ms with interrupts disabled. That means if
+ // the mpu6k does go bad it would cause a FMU failure,
+ // regardless of whether another sensor is available,
return;
}
+
+ perf_count(_good_transfers);
/*
@@ -1402,6 +1408,8 @@ MPU6000::print_info()
perf_print_counter(_sample_perf);
perf_print_counter(_accel_reads);
perf_print_counter(_gyro_reads);
+ perf_print_counter(_bad_transfers);
+ perf_print_counter(_good_transfers);
_accel_reports->print_info("accel queue");
_gyro_reports->print_info("gyro queue");
}
diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 873fa62c4..889643d0d 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -130,7 +130,7 @@ protected:
float _T;
/* altitude conversion calibration */
- unsigned _msl_pressure; /* in kPa */
+ unsigned _msl_pressure; /* in Pa */
orb_advert_t _baro_topic;
@@ -466,7 +466,7 @@ MS5611::ioctl(struct file *filp, int cmd, unsigned long arg)
irqrestore(flags);
return -ENOMEM;
}
- irqrestore(flags);
+ irqrestore(flags);
return OK;
}
diff --git a/src/drivers/pca9685/arduino_Adafruit_PWM_Servo_Driver_Library_license.txt b/src/drivers/pca9685/arduino_Adafruit_PWM_Servo_Driver_Library_license.txt
new file mode 100644
index 000000000..9c5eb42eb
--- /dev/null
+++ b/src/drivers/pca9685/arduino_Adafruit_PWM_Servo_Driver_Library_license.txt
@@ -0,0 +1,29 @@
+The following license agreement covers re-used code from the arduino driver
+for the Adafruit I2C to PWM converter.
+
+Software License Agreement (BSD License)
+
+Copyright (c) 2012, Adafruit Industries
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+1. Redistributions of source code must retain the above copyright
+notice, this list of conditions and the following disclaimer.
+2. Redistributions in binary form must reproduce the above copyright
+notice, this list of conditions and the following disclaimer in the
+documentation and/or other materials provided with the distribution.
+3. Neither the name of the copyright holders nor the
+names of its contributors may be used to endorse or promote products
+derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
+EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
diff --git a/src/drivers/pca9685/module.mk b/src/drivers/pca9685/module.mk
new file mode 100644
index 000000000..7a5c7996e
--- /dev/null
+++ b/src/drivers/pca9685/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Driver for the PCA9685 I2C PWM controller
+# The chip is used on the adafruit I2C PWM converter,
+# which allows to control servos via I2C.
+# https://www.adafruit.com/product/815
+
+MODULE_COMMAND = pca9685
+
+SRCS = pca9685.cpp
diff --git a/src/drivers/pca9685/pca9685.cpp b/src/drivers/pca9685/pca9685.cpp
new file mode 100644
index 000000000..6f69ce8a1
--- /dev/null
+++ b/src/drivers/pca9685/pca9685.cpp
@@ -0,0 +1,651 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file pca9685.cpp
+ *
+ * Driver for the PCA9685 I2C PWM module
+ * The chip is used on the Adafruit I2C/PWM converter https://www.adafruit.com/product/815
+ *
+ * Parts of the code are adapted from the arduino library for the board
+ * https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Library
+ * for the license of these parts see the
+ * arduino_Adafruit_PWM_Servo_Driver_Library_license.txt file
+ * see https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Library for contributors
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <ctype.h>
+#include <math.h>
+
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/actuator_controls.h>
+
+#include <board_config.h>
+#include <drivers/drv_io_expander.h>
+
+#define PCA9685_SUBADR1 0x2
+#define PCA9685_SUBADR2 0x3
+#define PCA9685_SUBADR3 0x4
+
+#define PCA9685_MODE1 0x0
+#define PCA9685_PRESCALE 0xFE
+
+#define LED0_ON_L 0x6
+#define LED0_ON_H 0x7
+#define LED0_OFF_L 0x8
+#define LED0_OFF_H 0x9
+
+#define ALLLED_ON_L 0xFA
+#define ALLLED_ON_H 0xFB
+#define ALLLED_OFF_L 0xFC
+#define ALLLED_OF
+
+#define ADDR 0x40 // I2C adress
+
+#define PCA9685_DEVICE_PATH "/dev/pca9685"
+#define PCA9685_BUS PX4_I2C_BUS_EXPANSION
+#define PCA9685_PWMFREQ 60.0f
+#define PCA9685_NCHANS 16 // total amount of pwm outputs
+
+#define PCA9685_PWMMIN 150 // this is the 'minimum' pulse length count (out of 4096)
+#define PCA9685_PWMMAX 600 // this is the 'maximum' pulse length count (out of 4096)_PWMFREQ 60.0f
+
+#define PCA9685_PWMCENTER ((PCA9685_PWMMAX + PCA9685_PWMMIN)/2)
+#define PCA9685_MAXSERVODEG 90.0f /* maximal servo deflection in degrees
+ PCA9685_PWMMIN <--> -PCA9685_MAXSERVODEG
+ PCA9685_PWMMAX <--> PCA9685_MAXSERVODEG
+ */
+#define PCA9685_SCALE ((PCA9685_PWMMAX - PCA9685_PWMCENTER)/(M_DEG_TO_RAD_F * PCA9685_MAXSERVODEG)) // scales from rad to PWM
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+class PCA9685 : public device::I2C
+{
+public:
+ PCA9685(int bus=PCA9685_BUS, uint8_t address=ADDR);
+ virtual ~PCA9685();
+
+
+ virtual int init();
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+ virtual int info();
+ virtual int reset();
+ bool is_running() { return _running; }
+
+private:
+ work_s _work;
+
+
+ enum IOX_MODE _mode;
+ bool _running;
+ int _i2cpwm_interval;
+ bool _should_run;
+ perf_counter_t _comms_errors;
+
+ uint8_t _msg[6];
+
+ int _actuator_controls_sub;
+ struct actuator_controls_s _actuator_controls;
+ uint16_t _current_values[NUM_ACTUATOR_CONTROLS]; /**< stores the current pwm output
+ values as sent to the setPin() */
+
+ bool _mode_on_initialized; /** Set to true after the first call of i2cpwm in mode IOX_MODE_ON */
+
+ static void i2cpwm_trampoline(void *arg);
+ void i2cpwm();
+
+ /**
+ * Helper function to set the pwm frequency
+ */
+ int setPWMFreq(float freq);
+
+ /**
+ * Helper function to set the demanded pwm value
+ * @param num pwm output number
+ */
+ int setPWM(uint8_t num, uint16_t on, uint16_t off);
+
+ /**
+ * Sets pin without having to deal with on/off tick placement and properly handles
+ * a zero value as completely off. Optional invert parameter supports inverting
+ * the pulse for sinking to ground.
+ * @param num pwm output number
+ * @param val should be a value from 0 to 4095 inclusive.
+ */
+ int setPin(uint8_t num, uint16_t val, bool invert = false);
+
+
+ /* Wrapper to read a byte from addr */
+ int read8(uint8_t addr, uint8_t &value);
+
+ /* Wrapper to wite a byte to addr */
+ int write8(uint8_t addr, uint8_t value);
+
+};
+
+/* for now, we only support one board */
+namespace
+{
+PCA9685 *g_pca9685;
+}
+
+void pca9685_usage();
+
+extern "C" __EXPORT int pca9685_main(int argc, char *argv[]);
+
+PCA9685::PCA9685(int bus, uint8_t address) :
+ I2C("pca9685", PCA9685_DEVICE_PATH, bus, address, 100000),
+ _mode(IOX_MODE_OFF),
+ _running(false),
+ _i2cpwm_interval(SEC2TICK(1.0f/60.0f)),
+ _should_run(false),
+ _comms_errors(perf_alloc(PC_COUNT, "actuator_controls_2_comms_errors")),
+ _actuator_controls_sub(-1),
+ _actuator_controls(),
+ _mode_on_initialized(false)
+{
+ memset(&_work, 0, sizeof(_work));
+ memset(_msg, 0, sizeof(_msg));
+ memset(_current_values, 0, sizeof(_current_values));
+}
+
+PCA9685::~PCA9685()
+{
+}
+
+int
+PCA9685::init()
+{
+ int ret;
+ ret = I2C::init();
+ if (ret != OK) {
+ return ret;
+ }
+
+ ret = reset();
+ if (ret != OK) {
+ return ret;
+ }
+
+ ret = setPWMFreq(PCA9685_PWMFREQ);
+
+ return ret;
+}
+
+int
+PCA9685::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int ret = -EINVAL;
+ switch (cmd) {
+
+ case IOX_SET_MODE:
+
+ if (_mode != (IOX_MODE)arg) {
+
+ switch ((IOX_MODE)arg) {
+ case IOX_MODE_OFF:
+ warnx("shutting down");
+ break;
+ case IOX_MODE_ON:
+ warnx("starting");
+ break;
+ case IOX_MODE_TEST_OUT:
+ warnx("test starting");
+ break;
+
+ default:
+ return -1;
+ }
+
+ _mode = (IOX_MODE)arg;
+ }
+
+ // if not active, kick it
+ if (!_running) {
+ _running = true;
+ work_queue(LPWORK, &_work, (worker_t)&PCA9685::i2cpwm_trampoline, this, 1);
+ }
+
+
+ return OK;
+
+ default:
+ // see if the parent class can make any use of it
+ ret = CDev::ioctl(filp, cmd, arg);
+ break;
+ }
+
+ return ret;
+}
+
+int
+PCA9685::info()
+{
+ int ret = OK;
+
+ if (is_running()) {
+ warnx("Driver is running, mode: %u", _mode);
+ } else {
+ warnx("Driver started but not running");
+ }
+
+ return ret;
+}
+
+void
+PCA9685::i2cpwm_trampoline(void *arg)
+{
+ PCA9685 *i2cpwm = reinterpret_cast<PCA9685 *>(arg);
+
+ i2cpwm->i2cpwm();
+}
+
+/**
+ * Main loop function
+ */
+void
+PCA9685::i2cpwm()
+{
+ if (_mode == IOX_MODE_TEST_OUT) {
+ setPin(0, PCA9685_PWMCENTER);
+ _should_run = true;
+ } else if (_mode == IOX_MODE_OFF) {
+ _should_run = false;
+ } else {
+ if (!_mode_on_initialized) {
+ /* Subscribe to actuator control 2 (payload group for gimbal) */
+ _actuator_controls_sub = orb_subscribe(ORB_ID(actuator_controls_2));
+ /* set the uorb update interval lower than the driver pwm interval */
+ orb_set_interval(_actuator_controls_sub, 1000.0f / PCA9685_PWMFREQ - 5);
+
+ _mode_on_initialized = true;
+ }
+
+ /* Read the servo setpoints from the actuator control topics (gimbal) */
+ bool updated;
+ orb_check(_actuator_controls_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(actuator_controls_2), _actuator_controls_sub, &_actuator_controls);
+ for (int i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
+ /* Scale the controls to PWM, first multiply by pi to get rad,
+ * the control[i] values are on the range -1 ... 1 */
+ uint16_t new_value = PCA9685_PWMCENTER +
+ (_actuator_controls.control[i] * M_PI_F * PCA9685_SCALE);
+ debug("%d: current: %u, new %u, control %.2f", i, _current_values[i], new_value,
+ (double)_actuator_controls.control[i]);
+ if (new_value != _current_values[i] &&
+ isfinite(new_value) &&
+ new_value >= PCA9685_PWMMIN &&
+ new_value <= PCA9685_PWMMAX) {
+ /* This value was updated, send the command to adjust the PWM value */
+ setPin(i, new_value);
+ _current_values[i] = new_value;
+ }
+ }
+ }
+ _should_run = true;
+ }
+
+ // check if any activity remains, else stop
+ if (!_should_run) {
+ _running = false;
+ return;
+ }
+
+ // re-queue ourselves to run again later
+ _running = true;
+ work_queue(LPWORK, &_work, (worker_t)&PCA9685::i2cpwm_trampoline, this, _i2cpwm_interval);
+}
+
+int
+PCA9685::setPWM(uint8_t num, uint16_t on, uint16_t off)
+{
+ int ret;
+ /* convert to correct message */
+ _msg[0] = LED0_ON_L + 4 * num;
+ _msg[1] = on;
+ _msg[2] = on >> 8;
+ _msg[3] = off;
+ _msg[4] = off >> 8;
+
+ /* try i2c transfer */
+ ret = transfer(_msg, 5, nullptr, 0);
+
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+ }
+
+ return ret;
+}
+
+int
+PCA9685::setPin(uint8_t num, uint16_t val, bool invert)
+{
+ // Clamp value between 0 and 4095 inclusive.
+ if (val > 4095) {
+ val = 4095;
+ }
+ if (invert) {
+ if (val == 0) {
+ // Special value for signal fully on.
+ return setPWM(num, 4096, 0);
+ } else if (val == 4095) {
+ // Special value for signal fully off.
+ return setPWM(num, 0, 4096);
+ } else {
+ return setPWM(num, 0, 4095-val);
+ }
+ } else {
+ if (val == 4095) {
+ // Special value for signal fully on.
+ return setPWM(num, 4096, 0);
+ } else if (val == 0) {
+ // Special value for signal fully off.
+ return setPWM(num, 0, 4096);
+ } else {
+ return setPWM(num, 0, val);
+ }
+ }
+
+ return ERROR;
+}
+
+int
+PCA9685::setPWMFreq(float freq)
+{
+ int ret = OK;
+ freq *= 0.9f; /* Correct for overshoot in the frequency setting (see issue
+ https://github.com/adafruit/Adafruit-PWM-Servo-Driver-Library/issues/11). */
+ float prescaleval = 25000000;
+ prescaleval /= 4096;
+ prescaleval /= freq;
+ prescaleval -= 1;
+ uint8_t prescale = uint8_t(prescaleval + 0.5f); //implicit floor()
+ uint8_t oldmode;
+ ret = read8(PCA9685_MODE1, oldmode);
+ if (ret != OK) {
+ return ret;
+ }
+ uint8_t newmode = (oldmode&0x7F) | 0x10; // sleep
+
+ ret = write8(PCA9685_MODE1, newmode); // go to sleep
+ if (ret != OK) {
+ return ret;
+ }
+ ret = write8(PCA9685_PRESCALE, prescale); // set the prescaler
+ if (ret != OK) {
+ return ret;
+ }
+ ret = write8(PCA9685_MODE1, oldmode);
+ if (ret != OK) {
+ return ret;
+ }
+
+ usleep(5000); //5ms delay (from arduino driver)
+
+ ret = write8(PCA9685_MODE1, oldmode | 0xa1); // This sets the MODE1 register to turn on auto increment.
+ if (ret != OK) {
+ return ret;
+ }
+
+ return ret;
+}
+
+/* Wrapper to read a byte from addr */
+int
+PCA9685::read8(uint8_t addr, uint8_t &value)
+{
+ int ret = OK;
+
+ /* send addr */
+ ret = transfer(&addr, sizeof(addr), nullptr, 0);
+ if (ret != OK) {
+ goto fail_read;
+ }
+
+ /* get value */
+ ret = transfer(nullptr, 0, &value, 1);
+ if (ret != OK) {
+ goto fail_read;
+ }
+
+ return ret;
+
+fail_read:
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+
+ return ret;
+}
+
+int PCA9685::reset(void) {
+ warnx("resetting");
+ return write8(PCA9685_MODE1, 0x0);
+}
+
+/* Wrapper to wite a byte to addr */
+int
+PCA9685::write8(uint8_t addr, uint8_t value) {
+ int ret = OK;
+ _msg[0] = addr;
+ _msg[1] = value;
+ /* send addr and value */
+ ret = transfer(_msg, 2, nullptr, 0);
+ if (ret != OK) {
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+ }
+ return ret;
+}
+
+void
+pca9685_usage()
+{
+ warnx("missing command: try 'start', 'test', 'stop', 'info'");
+ warnx("options:");
+ warnx(" -b i2cbus (%d)", PX4_I2C_BUS_EXPANSION);
+ warnx(" -a addr (0x%x)", ADDR);
+}
+
+int
+pca9685_main(int argc, char *argv[])
+{
+ int i2cdevice = -1;
+ int i2caddr = ADDR; // 7bit
+
+ int ch;
+
+ // jump over start/off/etc and look at options first
+ while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
+ switch (ch) {
+ case 'a':
+ i2caddr = strtol(optarg, NULL, 0);
+ break;
+
+ case 'b':
+ i2cdevice = strtol(optarg, NULL, 0);
+ break;
+
+ default:
+ pca9685_usage();
+ exit(0);
+ }
+ }
+
+ if (optind >= argc) {
+ pca9685_usage();
+ exit(1);
+ }
+
+ const char *verb = argv[optind];
+
+ int fd;
+ int ret;
+
+ if (!strcmp(verb, "start")) {
+ if (g_pca9685 != nullptr) {
+ errx(1, "already started");
+ }
+
+ if (i2cdevice == -1) {
+ // try the external bus first
+ i2cdevice = PX4_I2C_BUS_EXPANSION;
+ g_pca9685 = new PCA9685(PX4_I2C_BUS_EXPANSION, i2caddr);
+
+ if (g_pca9685 != nullptr && OK != g_pca9685->init()) {
+ delete g_pca9685;
+ g_pca9685 = nullptr;
+ }
+
+ if (g_pca9685 == nullptr) {
+ errx(1, "init failed");
+ }
+ }
+
+ if (g_pca9685 == nullptr) {
+ g_pca9685 = new PCA9685(i2cdevice, i2caddr);
+
+ if (g_pca9685 == nullptr) {
+ errx(1, "new failed");
+ }
+
+ if (OK != g_pca9685->init()) {
+ delete g_pca9685;
+ g_pca9685 = nullptr;
+ errx(1, "init failed");
+ }
+ }
+ fd = open(PCA9685_DEVICE_PATH, 0);
+ if (fd == -1) {
+ errx(1, "Unable to open " PCA9685_DEVICE_PATH);
+ }
+ ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_ON);
+ close(fd);
+
+
+ exit(0);
+ }
+
+ // need the driver past this point
+ if (g_pca9685 == nullptr) {
+ warnx("not started, run pca9685 start");
+ exit(1);
+ }
+
+ if (!strcmp(verb, "info")) {
+ g_pca9685->info();
+ exit(0);
+ }
+
+ if (!strcmp(verb, "reset")) {
+ g_pca9685->reset();
+ exit(0);
+ }
+
+
+ if (!strcmp(verb, "test")) {
+ fd = open(PCA9685_DEVICE_PATH, 0);
+
+ if (fd == -1) {
+ errx(1, "Unable to open " PCA9685_DEVICE_PATH);
+ }
+
+ ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_TEST_OUT);
+
+ close(fd);
+ exit(ret);
+ }
+
+ if (!strcmp(verb, "stop")) {
+ fd = open(PCA9685_DEVICE_PATH, 0);
+
+ if (fd == -1) {
+ errx(1, "Unable to open " PCA9685_DEVICE_PATH);
+ }
+
+ ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_OFF);
+ close(fd);
+
+ // wait until we're not running any more
+ for (unsigned i = 0; i < 15; i++) {
+ if (!g_pca9685->is_running()) {
+ break;
+ }
+
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+ }
+ printf("\n");
+ fflush(stdout);
+
+ if (!g_pca9685->is_running()) {
+ delete g_pca9685;
+ g_pca9685= nullptr;
+ warnx("stopped, exiting");
+ exit(0);
+ } else {
+ warnx("stop failed.");
+ exit(1);
+ }
+ }
+
+ pca9685_usage();
+ exit(0);
+}
diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp
index f214b5964..6c68636c6 100644
--- a/src/drivers/px4flow/px4flow.cpp
+++ b/src/drivers/px4flow/px4flow.cpp
@@ -37,7 +37,7 @@
*
* Driver for the PX4FLOW module connected via I2C.
*/
-
+
#include <nuttx/config.h>
#include <drivers/device/i2c.h>
@@ -68,7 +68,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/subsystem_info.h>
-//#include <uORB/topics/optical_flow.h>
+#include <uORB/topics/optical_flow.h>
#include <board_config.h>
@@ -76,11 +76,11 @@
#define PX4FLOW_BUS PX4_I2C_BUS_EXPANSION
#define I2C_FLOW_ADDRESS 0x42 //* 7-bit address. 8-bit address is 0x84
//range 0x42 - 0x49
-
+
/* PX4FLOW Registers addresses */
#define PX4FLOW_REG 0x00 /* Measure Register */
-#define PX4FLOW_CONVERSION_INTERVAL 8000 /* 8ms 125Hz
+#define PX4FLOW_CONVERSION_INTERVAL 8000 /* 8ms 125Hz */
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -115,17 +115,17 @@ class PX4FLOW : public device::I2C
public:
PX4FLOW(int bus = PX4FLOW_BUS, int address = I2C_FLOW_ADDRESS);
virtual ~PX4FLOW();
-
+
virtual int init();
-
+
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
-
+
/**
* Diagnostics - print some basic information about the driver.
*/
void print_info();
-
+
protected:
virtual int probe();
@@ -136,13 +136,13 @@ private:
bool _sensor_ok;
int _measure_ticks;
bool _collect_phase;
-
+
orb_advert_t _px4flow_topic;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
-
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -151,7 +151,7 @@ private:
* @return True if the device is present.
*/
int probe_address(uint8_t address);
-
+
/**
* Initialise the automatic measurement state machine and start it.
*
@@ -159,12 +159,12 @@ private:
* to make it more aggressive about resetting the bus in case of errors.
*/
void start();
-
+
/**
* Stop the automatic measurement state machine.
*/
void stop();
-
+
/**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
@@ -179,8 +179,8 @@ private:
* @param arg Instance pointer for the driver that is polling.
*/
static void cycle_trampoline(void *arg);
-
-
+
+
};
/*
@@ -201,7 +201,7 @@ PX4FLOW::PX4FLOW(int bus, int address) :
{
// enable debug() calls
_debug_enabled = true;
-
+
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
}
@@ -212,8 +212,9 @@ PX4FLOW::~PX4FLOW()
stop();
/* free any existing reports */
- if (_reports != nullptr)
+ if (_reports != nullptr) {
delete _reports;
+ }
}
int
@@ -222,22 +223,25 @@ PX4FLOW::init()
int ret = ERROR;
/* do I2C init (and probe) first */
- if (I2C::init() != OK)
+ if (I2C::init() != OK) {
goto out;
+ }
/* allocate basic report buffers */
- _reports = new RingBuffer(2, sizeof(px4flow_report));
+ _reports = new RingBuffer(2, sizeof(struct optical_flow_s));
- if (_reports == nullptr)
+ if (_reports == nullptr) {
goto out;
+ }
/* get a publish handle on the px4flow topic */
- struct px4flow_report zero_report;
+ struct optical_flow_s zero_report;
memset(&zero_report, 0, sizeof(zero_report));
_px4flow_topic = orb_advertise(ORB_ID(optical_flow), &zero_report);
- if (_px4flow_topic < 0)
+ if (_px4flow_topic < 0) {
debug("failed to create px4flow object. Did you start uOrb?");
+ }
ret = OK;
/* sensor is ok, but we don't really know if it is within range */
@@ -249,6 +253,17 @@ out:
int
PX4FLOW::probe()
{
+ uint8_t val[22];
+
+ // to be sure this is not a ll40ls Lidar (which can also be on
+ // 0x42) we check if a 22 byte transfer works from address
+ // 0. The ll40ls gives an error for that, whereas the flow
+ // happily returns some data
+ if (transfer(nullptr, 0, &val[0], 22) != OK) {
+ return -EIO;
+ }
+
+ // that worked, so start a measurement cycle
return measure();
}
@@ -260,20 +275,20 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSORIOCSPOLLRATE: {
switch (arg) {
- /* switching to manual polling */
+ /* switching to manual polling */
case SENSOR_POLLRATE_MANUAL:
stop();
_measure_ticks = 0;
return OK;
- /* external signalling (DRDY) not supported */
+ /* external signalling (DRDY) not supported */
case SENSOR_POLLRATE_EXTERNAL:
- /* zero would be bad */
+ /* zero would be bad */
case 0:
return -EINVAL;
- /* set default/max polling rate */
+ /* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT: {
/* do we need to start internal polling? */
@@ -283,13 +298,14 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
_measure_ticks = USEC2TICK(PX4FLOW_CONVERSION_INTERVAL);
/* if we need to start the poll state machine, do it */
- if (want_start)
+ if (want_start) {
start();
+ }
return OK;
}
- /* adjust to a legal polling interval in Hz */
+ /* adjust to a legal polling interval in Hz */
default: {
/* do we need to start internal polling? */
bool want_start = (_measure_ticks == 0);
@@ -298,15 +314,17 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
unsigned ticks = USEC2TICK(1000000 / arg);
/* check against maximum rate */
- if (ticks < USEC2TICK(PX4FLOW_CONVERSION_INTERVAL))
+ if (ticks < USEC2TICK(PX4FLOW_CONVERSION_INTERVAL)) {
return -EINVAL;
+ }
/* update interval for next measurement */
_measure_ticks = ticks;
/* if we need to start the poll state machine, do it */
- if (want_start)
+ if (want_start) {
start();
+ }
return OK;
}
@@ -314,33 +332,37 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
}
case SENSORIOCGPOLLRATE:
- if (_measure_ticks == 0)
+ if (_measure_ticks == 0) {
return SENSOR_POLLRATE_MANUAL;
+ }
return (1000 / _measure_ticks);
case SENSORIOCSQUEUEDEPTH: {
- /* lower bound is mandatory, upper bound is a sanity check */
- if ((arg < 1) || (arg > 100))
- return -EINVAL;
-
- irqstate_t flags = irqsave();
- if (!_reports->resize(arg)) {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100)) {
+ return -EINVAL;
+ }
+
+ irqstate_t flags = irqsave();
+
+ if (!_reports->resize(arg)) {
+ irqrestore(flags);
+ return -ENOMEM;
+ }
+
irqrestore(flags);
- return -ENOMEM;
+
+ return OK;
}
- irqrestore(flags);
-
- return OK;
- }
case SENSORIOCGQUEUEDEPTH:
return _reports->size();
-
+
case SENSORIOCRESET:
/* XXX implement this */
return -EINVAL;
-
+
default:
/* give it to the superclass */
return I2C::ioctl(filp, cmd, arg);
@@ -350,13 +372,14 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg)
ssize_t
PX4FLOW::read(struct file *filp, char *buffer, size_t buflen)
{
- unsigned count = buflen / sizeof(struct px4flow_report);
- struct px4flow_report *rbuf = reinterpret_cast<struct px4flow_report *>(buffer);
+ unsigned count = buflen / sizeof(struct optical_flow_s);
+ struct optical_flow_s *rbuf = reinterpret_cast<struct optical_flow_s *>(buffer);
int ret = 0;
/* buffer must be large enough */
- if (count < 1)
+ if (count < 1) {
return -ENOSPC;
+ }
/* if automatic measurement is enabled */
if (_measure_ticks > 0) {
@@ -417,15 +440,15 @@ PX4FLOW::measure()
uint8_t cmd = PX4FLOW_REG;
ret = transfer(&cmd, 1, nullptr, 0);
- if (OK != ret)
- {
+ if (OK != ret) {
perf_count(_comms_errors);
log("i2c::transfer returned %d", ret);
- printf("i2c::transfer flow returned %d");
+ printf("i2c::transfer flow returned %d");
return ret;
}
+
ret = OK;
-
+
return ret;
}
@@ -433,22 +456,21 @@ int
PX4FLOW::collect()
{
int ret = -EIO;
-
+
/* read from the sensor */
- uint8_t val[22] = {0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0};
-
+ uint8_t val[22] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
+
perf_begin(_sample_perf);
-
+
ret = transfer(nullptr, 0, &val[0], 22);
-
- if (ret < 0)
- {
+
+ if (ret < 0) {
log("error reading from sensor: %d", ret);
perf_count(_comms_errors);
perf_end(_sample_perf);
return ret;
}
-
+
// f.frame_count = val[1] << 8 | val[0];
// f.pixel_flow_x_sum= val[3] << 8 | val[2];
// f.pixel_flow_y_sum= val[5] << 8 | val[4];
@@ -466,13 +488,13 @@ PX4FLOW::collect()
int16_t flowcy = val[9] << 8 | val[8];
int16_t gdist = val[21] << 8 | val[20];
- struct px4flow_report report;
- report.flow_comp_x_m = float(flowcx)/1000.0f;
- report.flow_comp_y_m = float(flowcy)/1000.0f;
- report.flow_raw_x= val[3] << 8 | val[2];
- report.flow_raw_y= val[5] << 8 | val[4];
- report.ground_distance_m =float(gdist)/1000.0f;
- report.quality= val[10];
+ struct optical_flow_s report;
+ report.flow_comp_x_m = float(flowcx) / 1000.0f;
+ report.flow_comp_y_m = float(flowcy) / 1000.0f;
+ report.flow_raw_x = val[3] << 8 | val[2];
+ report.flow_raw_y = val[5] << 8 | val[4];
+ report.ground_distance_m = float(gdist) / 1000.0f;
+ report.quality = val[10];
report.sensor_id = 0;
report.timestamp = hrt_absolute_time();
@@ -503,17 +525,19 @@ PX4FLOW::start()
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&PX4FLOW::cycle_trampoline, this, 1);
-
+
/* notify about state change */
struct subsystem_info_s info = {
true,
true,
true,
- SUBSYSTEM_TYPE_OPTICALFLOW};
+ SUBSYSTEM_TYPE_OPTICALFLOW
+ };
static orb_advert_t pub = -1;
if (pub > 0) {
orb_publish(ORB_ID(subsystem_info), pub, &info);
+
} else {
pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
@@ -567,8 +591,9 @@ PX4FLOW::cycle()
}
/* measurement phase */
- if (OK != measure())
+ if (OK != measure()) {
log("measure error");
+ }
/* next phase is collection */
_collect_phase = true;
@@ -619,33 +644,37 @@ start()
{
int fd;
- if (g_dev != nullptr)
+ if (g_dev != nullptr) {
errx(1, "already started");
+ }
/* create the driver */
g_dev = new PX4FLOW(PX4FLOW_BUS);
- if (g_dev == nullptr)
+ if (g_dev == nullptr) {
goto fail;
+ }
- if (OK != g_dev->init())
+ if (OK != g_dev->init()) {
goto fail;
+ }
/* set the poll rate to default, starts automatic data collection */
fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
goto fail;
+ }
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX) < 0)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX) < 0) {
goto fail;
+ }
exit(0);
fail:
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
}
@@ -658,15 +687,14 @@ fail:
*/
void stop()
{
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
- }
- else
- {
+
+ } else {
errx(1, "driver not running");
}
+
exit(0);
}
@@ -678,20 +706,23 @@ void stop()
void
test()
{
- struct px4flow_report report;
+ struct optical_flow_s report;
ssize_t sz;
int ret;
int fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
err(1, "%s open failed (try 'px4flow start' if the driver is not running", PX4FLOW_DEVICE_PATH);
+ }
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
if (sz != sizeof(report))
- // err(1, "immediate read failed");
+ {
+ warnx("immediate read failed");
+ }
warnx("single read");
warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
@@ -700,8 +731,9 @@ test()
/* start the sensor polling at 2Hz */
- if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
errx(1, "failed to set 2Hz poll rate");
+ }
/* read the sensor 5x and report each value */
for (unsigned i = 0; i < 5; i++) {
@@ -712,14 +744,16 @@ test()
fds.events = POLLIN;
ret = poll(&fds, 1, 2000);
- if (ret != 1)
+ if (ret != 1) {
errx(1, "timed out waiting for sensor data");
+ }
/* now go get it */
sz = read(fd, &report, sizeof(report));
- if (sz != sizeof(report))
+ if (sz != sizeof(report)) {
err(1, "periodic read failed");
+ }
warnx("periodic read %u", i);
warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
@@ -740,14 +774,17 @@ reset()
{
int fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY);
- if (fd < 0)
+ if (fd < 0) {
err(1, "failed ");
+ }
- if (ioctl(fd, SENSORIOCRESET, 0) < 0)
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
err(1, "driver reset failed");
+ }
- if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
err(1, "driver poll restart failed");
+ }
exit(0);
}
@@ -758,8 +795,9 @@ reset()
void
info()
{
- if (g_dev == nullptr)
+ if (g_dev == nullptr) {
errx(1, "driver not running");
+ }
printf("state @ %p\n", g_dev);
g_dev->print_info();
@@ -775,32 +813,37 @@ px4flow_main(int argc, char *argv[])
/*
* Start/load the driver.
*/
- if (!strcmp(argv[1], "start"))
+ if (!strcmp(argv[1], "start")) {
px4flow::start();
-
- /*
- * Stop the driver
- */
- if (!strcmp(argv[1], "stop"))
- px4flow::stop();
+ }
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop")) {
+ px4flow::stop();
+ }
/*
* Test the driver/device.
*/
- if (!strcmp(argv[1], "test"))
+ if (!strcmp(argv[1], "test")) {
px4flow::test();
+ }
/*
* Reset the driver.
*/
- if (!strcmp(argv[1], "reset"))
+ if (!strcmp(argv[1], "reset")) {
px4flow::reset();
+ }
/*
* Print driver information.
*/
- if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
+ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
px4flow::info();
+ }
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
}
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 82977a032..3d3e1b0eb 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -829,6 +829,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_SET_ARM_OK:
case PWM_SERVO_CLEAR_ARM_OK:
case PWM_SERVO_SET_FORCE_SAFETY_OFF:
+ case PWM_SERVO_SET_FORCE_SAFETY_ON:
// these are no-ops, as no safety switch
break;
@@ -1272,7 +1273,9 @@ PX4FMU::write(file *filp, const char *buffer, size_t len)
memcpy(values, buffer, count * 2);
for (uint8_t i = 0; i < count; i++) {
- up_pwm_servo_set(i, values[i]);
+ if (values[i] != PWM_IGNORE_THIS_CHANNEL) {
+ up_pwm_servo_set(i, values[i]);
+ }
}
return count * 2;
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index d93009c47..6d68d9f60 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -136,6 +136,15 @@ public:
virtual int init();
/**
+ * Initialize the PX4IO class.
+ *
+ * Retrieve relevant initial system parameters. Initialize PX4IO registers.
+ *
+ * @param disable_rc_handling set to true to forbid override / RC handling on IO
+ */
+ int init(bool disable_rc_handling);
+
+ /**
* Detect if a PX4IO is connected.
*
* Only validate if there is a PX4IO to talk to.
@@ -286,6 +295,7 @@ private:
float _battery_amp_bias; ///< current sensor bias
float _battery_mamphour_total;///< amp hours consumed so far
uint64_t _battery_last_timestamp;///< last amp hour calculation timestamp
+ bool _cb_flighttermination; ///< true if the flight termination circuit breaker is enabled
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
bool _dsm_vcc_ctl; ///< true if relay 1 controls DSM satellite RX power
@@ -506,7 +516,8 @@ PX4IO::PX4IO(device::Device *interface) :
_battery_amp_per_volt(90.0f / 5.0f), // this matches the 3DR current sensor
_battery_amp_bias(0),
_battery_mamphour_total(0),
- _battery_last_timestamp(0)
+ _battery_last_timestamp(0),
+ _cb_flighttermination(true)
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
, _dsm_vcc_ctl(false)
#endif
@@ -580,6 +591,12 @@ PX4IO::detect()
}
int
+PX4IO::init(bool rc_handling_disabled) {
+ _rc_handling_disabled = rc_handling_disabled;
+ return init();
+}
+
+int
PX4IO::init()
{
int ret;
@@ -778,6 +795,11 @@ PX4IO::init()
if (_rc_handling_disabled) {
ret = io_disable_rc_handling();
+ if (ret != OK) {
+ log("failed disabling RC handling");
+ return ret;
+ }
+
} else {
/* publish RC config to IO */
ret = io_set_rc_config();
@@ -1031,6 +1053,9 @@ PX4IO::task_main()
}
}
+ /* Update Circuit breakers */
+ _cb_flighttermination = circuit_breaker_enabled("CBRK_FLIGHTTERM", CBRK_FLIGHTTERM_KEY);
+
}
}
@@ -1149,12 +1174,21 @@ PX4IO::io_set_arming_state()
clear |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
}
- if (armed.force_failsafe) {
+ /* Do not set failsafe if circuit breaker is enabled */
+ if (armed.force_failsafe && !_cb_flighttermination) {
set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
} else {
clear |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
}
+ // XXX this is for future support in the commander
+ // but can be removed if unneeded
+ // if (armed.termination_failsafe) {
+ // set |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
+ // } else {
+ // clear |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
+ // }
+
if (armed.ready_to_arm) {
set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
@@ -1175,6 +1209,7 @@ PX4IO::io_set_arming_state()
int
PX4IO::disable_rc_handling()
{
+ _rc_handling_disabled = true;
return io_disable_rc_handling();
}
@@ -1212,28 +1247,40 @@ PX4IO::io_set_rc_config()
*/
param_get(param_find("RC_MAP_ROLL"), &ichan);
+ /* subtract one from 1-based index - this might be
+ * a negative number now
+ */
+ ichan -= 1;
+
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
- input_map[ichan - 1] = 0;
+ input_map[ichan] = 0;
param_get(param_find("RC_MAP_PITCH"), &ichan);
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
- input_map[ichan - 1] = 1;
+ input_map[ichan] = 1;
param_get(param_find("RC_MAP_YAW"), &ichan);
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
- input_map[ichan - 1] = 2;
+ input_map[ichan] = 2;
param_get(param_find("RC_MAP_THROTTLE"), &ichan);
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
- input_map[ichan - 1] = 3;
+ input_map[ichan] = 3;
- param_get(param_find("RC_MAP_MODE_SW"), &ichan);
+ param_get(param_find("RC_MAP_FLAPS"), &ichan);
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
- input_map[ichan - 1] = 4;
+ input_map[ichan] = 4;
+
+ param_get(param_find("RC_MAP_MODE_SW"), &ichan);
+
+ if ((ichan >= 0) && (ichan < (int)_max_rc_input)) {
+ /* use out of normal bounds index to indicate special channel */
+ input_map[ichan] = PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH;
+ }
/*
* Iterate all possible RC inputs.
@@ -1582,6 +1629,9 @@ PX4IO::io_publish_raw_rc()
} else if (_status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
rc_val.input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
+ } else if (_status & PX4IO_P_STATUS_FLAGS_RC_ST24) {
+ rc_val.input_source = RC_INPUT_SOURCE_PX4IO_ST24;
+
} else {
rc_val.input_source = RC_INPUT_SOURCE_UNKNOWN;
@@ -1899,13 +1949,15 @@ PX4IO::print_status(bool extended_status)
io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FREEMEM));
uint16_t flags = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS);
uint16_t io_status_flags = flags;
- printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s\n",
+ printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s%s%s\n",
flags,
((flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED) ? " OUTPUTS_ARMED" : ""),
((flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ? " SAFETY_OFF" : " SAFETY_SAFE"),
((flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ? " OVERRIDE" : ""),
((flags & PX4IO_P_STATUS_FLAGS_RC_OK) ? " RC_OK" : " RC_FAIL"),
((flags & PX4IO_P_STATUS_FLAGS_RC_PPM) ? " PPM" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) ? " DSM" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_RC_ST24) ? " ST24" : ""),
((flags & PX4IO_P_STATUS_FLAGS_RC_SBUS) ? " SBUS" : ""),
((flags & PX4IO_P_STATUS_FLAGS_FMU_OK) ? " FMU_OK" : " FMU_FAIL"),
((flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ? " RAW_PWM_PASSTHROUGH" : ""),
@@ -1947,7 +1999,7 @@ PX4IO::print_status(bool extended_status)
printf("actuators");
for (unsigned i = 0; i < _max_actuators; i++)
- printf(" %u", io_reg_get(PX4IO_PAGE_ACTUATORS, i));
+ printf(" %hi", int16_t(io_reg_get(PX4IO_PAGE_ACTUATORS, i)));
printf("\n");
printf("servos");
@@ -2017,7 +2069,8 @@ PX4IO::print_status(bool extended_status)
((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""),
((arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE) ? " ALWAYS_PWM_ENABLE" : ""),
((arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) ? " LOCKDOWN" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) ? " FORCE_FAILSAFE" : "")
+ ((arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) ? " FORCE_FAILSAFE" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) ? " TERM_FAILSAFE" : "")
);
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
printf("rates 0x%04x default %u alt %u relays 0x%04x\n",
@@ -2230,6 +2283,11 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC);
break;
+ case PWM_SERVO_SET_FORCE_SAFETY_ON:
+ /* force safety switch on */
+ ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_ON, PX4IO_FORCE_SAFETY_MAGIC);
+ break;
+
case PWM_SERVO_SET_FORCE_FAILSAFE:
/* force failsafe mode instantly */
if (arg == 0) {
@@ -2241,6 +2299,17 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
}
break;
+ case PWM_SERVO_SET_TERMINATION_FAILSAFE:
+ /* if failsafe occurs, do not allow the system to recover */
+ if (arg == 0) {
+ /* clear termination failsafe flag */
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE, 0);
+ } else {
+ /* set termination failsafe flag */
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE);
+ }
+ break;
+
case DSM_BIND_START:
/* only allow DSM2, DSM-X and DSM-X with more than 7 channels */
@@ -2418,6 +2487,9 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
} else if (status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
+ } else if (status & PX4IO_P_STATUS_FLAGS_RC_ST24) {
+ rc_val->input_source = RC_INPUT_SOURCE_PX4IO_ST24;
+
} else {
rc_val->input_source = RC_INPUT_SOURCE_UNKNOWN;
}
@@ -2613,24 +2685,25 @@ start(int argc, char *argv[])
errx(1, "driver alloc failed");
}
- if (OK != g_dev->init()) {
- delete g_dev;
- g_dev = nullptr;
- errx(1, "driver init failed");
- }
+ bool rc_handling_disabled = false;
/* disable RC handling on request */
if (argc > 1) {
if (!strcmp(argv[1], "norc")) {
- if (g_dev->disable_rc_handling())
- warnx("Failed disabling RC handling");
+ rc_handling_disabled = true;
} else {
warnx("unknown argument: %s", argv[1]);
}
}
+ if (OK != g_dev->init(rc_handling_disabled)) {
+ delete g_dev;
+ g_dev = nullptr;
+ errx(1, "driver init failed");
+ }
+
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
int dsm_vcc_ctl;
diff --git a/src/drivers/sf0x/module.mk b/src/drivers/sf0x/module.mk
index dc2c66d56..26e77d1cc 100644
--- a/src/drivers/sf0x/module.mk
+++ b/src/drivers/sf0x/module.mk
@@ -37,6 +37,7 @@
MODULE_COMMAND = sf0x
-SRCS = sf0x.cpp
+SRCS = sf0x.cpp \
+ sf0x_parser.cpp
MAXOPTIMIZATION = -Os
diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp
index bca1715fa..fdd524189 100644
--- a/src/drivers/sf0x/sf0x.cpp
+++ b/src/drivers/sf0x/sf0x.cpp
@@ -72,6 +72,8 @@
#include <board_config.h>
+#include "sf0x_parser.h"
+
/* Configuration Constants */
/* oddly, ERROR is not defined for c++ */
@@ -120,6 +122,7 @@ private:
int _fd;
char _linebuf[10];
unsigned _linebuf_index;
+ enum SF0X_PARSE_STATE _parse_state;
hrt_abstime _last_read;
orb_advert_t _range_finder_topic;
@@ -186,6 +189,7 @@ SF0X::SF0X(const char *port) :
_collect_phase(false),
_fd(-1),
_linebuf_index(0),
+ _parse_state(SF0X_PARSE_STATE0_UNSYNC),
_last_read(0),
_range_finder_topic(-1),
_consecutive_fail_count(0),
@@ -200,12 +204,6 @@ SF0X::SF0X(const char *port) :
warnx("FAIL: laser fd");
}
- /* tell it to stop auto-triggering */
- char stop_auto = ' ';
- (void)::write(_fd, &stop_auto, 1);
- usleep(100);
- (void)::write(_fd, &stop_auto, 1);
-
struct termios uart_config;
int termios_state;
@@ -520,22 +518,15 @@ SF0X::collect()
/* clear buffer if last read was too long ago */
uint64_t read_elapsed = hrt_elapsed_time(&_last_read);
- if (read_elapsed > (SF0X_CONVERSION_INTERVAL * 2)) {
- _linebuf_index = 0;
- } else if (_linebuf_index > 0) {
- /* increment to next read position */
- _linebuf_index++;
- }
-
/* the buffer for read chars is buflen minus null termination */
- unsigned readlen = sizeof(_linebuf) - 1;
+ char readbuf[sizeof(_linebuf)];
+ unsigned readlen = sizeof(readbuf) - 1;
/* read from the sensor (uart buffer) */
- ret = ::read(_fd, &_linebuf[_linebuf_index], readlen - _linebuf_index);
+ ret = ::read(_fd, &readbuf[0], readlen);
if (ret < 0) {
- _linebuf[sizeof(_linebuf) - 1] = '\0';
- debug("read err: %d lbi: %d buf: %s", ret, (int)_linebuf_index, _linebuf);
+ debug("read err: %d", ret);
perf_count(_comms_errors);
perf_end(_sample_perf);
@@ -550,83 +541,23 @@ SF0X::collect()
return -EAGAIN;
}
- /* we did increment the index to the next position already, so just add the additional fields */
- _linebuf_index += (ret - 1);
-
_last_read = hrt_absolute_time();
- if (_linebuf_index < 1) {
- /* we need at least the two end bytes to make sense of this string */
- return -EAGAIN;
-
- } else if (_linebuf[_linebuf_index - 1] != '\r' || _linebuf[_linebuf_index] != '\n') {
-
- if (_linebuf_index >= readlen - 1) {
- /* we have a full buffer, but no line ending - abort */
- _linebuf_index = 0;
- perf_count(_comms_errors);
- return -ENOMEM;
- } else {
- /* incomplete read, reschedule ourselves */
- return -EAGAIN;
- }
- }
-
- char *end;
float si_units;
- bool valid;
-
- /* enforce line ending */
- unsigned lend = (_linebuf_index < (sizeof(_linebuf) - 1)) ? _linebuf_index : (sizeof(_linebuf) - 1);
-
- _linebuf[lend] = '\0';
-
- if (_linebuf[0] == '-' && _linebuf[1] == '-' && _linebuf[2] == '.') {
- si_units = -1.0f;
- valid = false;
-
- } else {
-
- /* we need to find a dot in the string, as we're missing the meters part else */
- valid = false;
-
- /* wipe out partially read content from last cycle(s), check for dot */
- for (unsigned i = 0; i < (lend - 2); i++) {
- if (_linebuf[i] == '\n') {
- char buf[sizeof(_linebuf)];
- memcpy(buf, &_linebuf[i+1], (lend + 1) - (i + 1));
- memcpy(_linebuf, buf, (lend + 1) - (i + 1));
- }
-
- if (_linebuf[i] == '.') {
- valid = true;
- }
- }
-
- if (valid) {
- si_units = strtod(_linebuf, &end);
-
- /* we require at least 3 characters for a valid number */
- if (end > _linebuf + 3) {
- valid = true;
- } else {
- si_units = -1.0f;
- valid = false;
- }
+ bool valid = false;
+
+ for (int i = 0; i < ret; i++) {
+ if (OK == sf0x_parser(readbuf[i], _linebuf, &_linebuf_index, &_parse_state, &si_units)) {
+ valid = true;
}
}
- debug("val (float): %8.4f, raw: %s, valid: %s\n", (double)si_units, _linebuf, ((valid) ? "OK" : "NO"));
-
- /* done with this chunk, resetting - even if invalid */
- _linebuf_index = 0;
-
- /* if its invalid, there is no reason to forward the value */
if (!valid) {
- perf_count(_comms_errors);
- return -EINVAL;
+ return -EAGAIN;
}
+ debug("val (float): %8.4f, raw: %s, valid: %s", (double)si_units, _linebuf, ((valid) ? "OK" : "NO"));
+
struct range_finder_report report;
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
@@ -708,12 +639,12 @@ SF0X::cycle()
int collect_ret = collect();
if (collect_ret == -EAGAIN) {
- /* reschedule to grab the missing bits, time to transmit 10 bytes @9600 bps */
+ /* reschedule to grab the missing bits, time to transmit 8 bytes @ 9600 bps */
work_queue(HPWORK,
&_work,
(worker_t)&SF0X::cycle_trampoline,
this,
- USEC2TICK(1100));
+ USEC2TICK(1042 * 8));
return;
}
diff --git a/src/drivers/sf0x/sf0x_parser.cpp b/src/drivers/sf0x/sf0x_parser.cpp
new file mode 100644
index 000000000..8e73b0ad3
--- /dev/null
+++ b/src/drivers/sf0x/sf0x_parser.cpp
@@ -0,0 +1,155 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file sf0x_parser.cpp
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Driver for the Lightware SF0x laser rangefinder series
+ */
+
+#include "sf0x_parser.h"
+#include <string.h>
+#include <stdlib.h>
+
+//#define SF0X_DEBUG
+
+#ifdef SF0X_DEBUG
+#include <stdio.h>
+
+const char *parser_state[] = {
+ "0_UNSYNC",
+ "1_SYNC",
+ "2_GOT_DIGIT0",
+ "3_GOT_DOT",
+ "4_GOT_DIGIT1",
+ "5_GOT_DIGIT2",
+ "6_GOT_CARRIAGE_RETURN"
+};
+#endif
+
+int sf0x_parser(char c, char *parserbuf, unsigned *parserbuf_index, enum SF0X_PARSE_STATE *state, float *dist)
+{
+ int ret = -1;
+ char *end;
+
+ switch (*state) {
+ case SF0X_PARSE_STATE0_UNSYNC:
+ if (c == '\n') {
+ *state = SF0X_PARSE_STATE1_SYNC;
+ (*parserbuf_index) = 0;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE1_SYNC:
+ if (c >= '0' && c <= '9') {
+ *state = SF0X_PARSE_STATE2_GOT_DIGIT0;
+ parserbuf[*parserbuf_index] = c;
+ (*parserbuf_index)++;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE2_GOT_DIGIT0:
+ if (c >= '0' && c <= '9') {
+ *state = SF0X_PARSE_STATE2_GOT_DIGIT0;
+ parserbuf[*parserbuf_index] = c;
+ (*parserbuf_index)++;
+
+ } else if (c == '.') {
+ *state = SF0X_PARSE_STATE3_GOT_DOT;
+ parserbuf[*parserbuf_index] = c;
+ (*parserbuf_index)++;
+
+ } else {
+ *state = SF0X_PARSE_STATE0_UNSYNC;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE3_GOT_DOT:
+ if (c >= '0' && c <= '9') {
+ *state = SF0X_PARSE_STATE4_GOT_DIGIT1;
+ parserbuf[*parserbuf_index] = c;
+ (*parserbuf_index)++;
+
+ } else {
+ *state = SF0X_PARSE_STATE0_UNSYNC;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE4_GOT_DIGIT1:
+ if (c >= '0' && c <= '9') {
+ *state = SF0X_PARSE_STATE5_GOT_DIGIT2;
+ parserbuf[*parserbuf_index] = c;
+ (*parserbuf_index)++;
+
+ } else {
+ *state = SF0X_PARSE_STATE0_UNSYNC;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE5_GOT_DIGIT2:
+ if (c == '\r') {
+ *state = SF0X_PARSE_STATE6_GOT_CARRIAGE_RETURN;
+
+ } else {
+ *state = SF0X_PARSE_STATE0_UNSYNC;
+ }
+
+ break;
+
+ case SF0X_PARSE_STATE6_GOT_CARRIAGE_RETURN:
+ if (c == '\n') {
+ parserbuf[*parserbuf_index] = '\0';
+ *dist = strtod(parserbuf, &end);
+ *state = SF0X_PARSE_STATE1_SYNC;
+ *parserbuf_index = 0;
+ ret = 0;
+
+ } else {
+ *state = SF0X_PARSE_STATE0_UNSYNC;
+ }
+
+ break;
+ }
+
+#ifdef SF0X_DEBUG
+ printf("state: SF0X_PARSE_STATE%s\n", parser_state[*state]);
+#endif
+
+ return ret;
+} \ No newline at end of file
diff --git a/src/drivers/sf0x/sf0x_parser.h b/src/drivers/sf0x/sf0x_parser.h
new file mode 100644
index 000000000..20892d50e
--- /dev/null
+++ b/src/drivers/sf0x/sf0x_parser.h
@@ -0,0 +1,51 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file sf0x_parser.cpp
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Declarations of parser for the Lightware SF0x laser rangefinder series
+ */
+
+enum SF0X_PARSE_STATE {
+ SF0X_PARSE_STATE0_UNSYNC = 0,
+ SF0X_PARSE_STATE1_SYNC,
+ SF0X_PARSE_STATE2_GOT_DIGIT0,
+ SF0X_PARSE_STATE3_GOT_DOT,
+ SF0X_PARSE_STATE4_GOT_DIGIT1,
+ SF0X_PARSE_STATE5_GOT_DIGIT2,
+ SF0X_PARSE_STATE6_GOT_CARRIAGE_RETURN
+};
+
+int sf0x_parser(char c, char *parserbuf, unsigned *parserbuf_index, enum SF0X_PARSE_STATE *state, float *dist); \ No newline at end of file
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index 03c7bd399..8f523b390 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -337,6 +337,7 @@ ToneAlarm::ToneAlarm() :
_default_tunes[TONE_ARMING_FAILURE_TUNE] = "MFT255L4<<<BAP";
_default_tunes[TONE_PARACHUTE_RELEASE_TUNE] = "MFT255L16agagagag"; // parachute release
_default_tunes[TONE_EKF_WARNING_TUNE] = "MFT255L8ddd#d#eeff"; // ekf warning
+ _default_tunes[TONE_BARO_WARNING_TUNE] = "MFT255L4gf#fed#d"; // baro warning
_tune_names[TONE_STARTUP_TUNE] = "startup"; // startup tune
_tune_names[TONE_ERROR_TUNE] = "error"; // ERROR tone
@@ -350,6 +351,7 @@ ToneAlarm::ToneAlarm() :
_tune_names[TONE_ARMING_FAILURE_TUNE] = "arming_failure"; //fail to arm
_tune_names[TONE_PARACHUTE_RELEASE_TUNE] = "parachute_release"; // parachute release
_tune_names[TONE_EKF_WARNING_TUNE] = "ekf_warning"; // ekf warning
+ _tune_names[TONE_BARO_WARNING_TUNE] = "baro_warning"; // baro warning
}
ToneAlarm::~ToneAlarm()
diff --git a/src/lib/conversion/module.mk b/src/lib/conversion/module.mk
index f5f59a2dc..4593c4887 100644
--- a/src/lib/conversion/module.mk
+++ b/src/lib/conversion/module.mk
@@ -36,3 +36,5 @@
#
SRCS = rotation.cpp
+
+MAXOPTIMIZATION = -Os
diff --git a/src/lib/conversion/rotation.h b/src/lib/conversion/rotation.h
index 5187b448f..917c7f830 100644
--- a/src/lib/conversion/rotation.h
+++ b/src/lib/conversion/rotation.h
@@ -74,6 +74,7 @@ enum Rotation {
ROTATION_ROLL_270_YAW_135 = 23,
ROTATION_PITCH_90 = 24,
ROTATION_PITCH_270 = 25,
+ ROTATION_ROLL_270_YAW_270 = 26,
ROTATION_MAX
};
@@ -109,7 +110,8 @@ const rot_lookup_t rot_lookup[] = {
{270, 0, 90 },
{270, 0, 135 },
{ 0, 90, 0 },
- { 0, 270, 0 }
+ { 0, 270, 0 },
+ {270, 0, 270 }
};
/**
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
index 46db788a6..926a8db2a 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -169,7 +169,7 @@ float ECL_PitchController::control_bodyrate(float roll, float pitch,
if (!lock_integrator && _k_i > 0.0f && airspeed > 0.5f * airspeed_min) {
- float id = _rate_error * dt;
+ float id = _rate_error * dt * scaler;
/*
* anti-windup: do not allow integrator to increase if actuator is at limit
@@ -190,7 +190,9 @@ float ECL_PitchController::control_bodyrate(float roll, float pitch,
float integrator_constrained = math::constrain(_integrator * _k_i, -_integrator_max, _integrator_max);
/* Apply PI rate controller and store non-limited output */
- _last_output = (_bodyrate_setpoint * _k_ff +_rate_error * _k_p + integrator_constrained) * scaler * scaler; //scaler is proportional to 1/airspeed
+ _last_output = _bodyrate_setpoint * _k_ff * scaler +
+ _rate_error * _k_p * scaler * scaler
+ + integrator_constrained; //scaler is proportional to 1/airspeed
// warnx("pitch: _integrator: %.4f, _integrator_max: %.4f, airspeed %.4f, _k_i %.4f, _k_p: %.4f", (double)_integrator, (double)_integrator_max, (double)airspeed, (double)_k_i, (double)_k_p);
// warnx("roll: _last_output %.4f", (double)_last_output);
return math::constrain(_last_output, -1.0f, 1.0f);
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
index 9894a34d7..94bd26f03 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -135,7 +135,7 @@ float ECL_RollController::control_bodyrate(float pitch,
if (!lock_integrator && _k_i > 0.0f && airspeed > 0.5f * airspeed_min) {
- float id = _rate_error * dt;
+ float id = _rate_error * dt * scaler;
/*
* anti-windup: do not allow integrator to increase if actuator is at limit
@@ -157,7 +157,9 @@ float ECL_RollController::control_bodyrate(float pitch,
//warnx("roll: _integrator: %.4f, _integrator_max: %.4f", (double)_integrator, (double)_integrator_max);
/* Apply PI rate controller and store non-limited output */
- _last_output = (_bodyrate_setpoint * _k_ff + _rate_error * _k_p + integrator_constrained) * scaler * scaler; //scaler is proportional to 1/airspeed
+ _last_output = _bodyrate_setpoint * _k_ff * scaler +
+ _rate_error * _k_p * scaler * scaler
+ + integrator_constrained; //scaler is proportional to 1/airspeed
return math::constrain(_last_output, -1.0f, 1.0f);
}
diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp
index 6386e37a0..0ed210cf4 100644
--- a/src/lib/external_lgpl/tecs/tecs.cpp
+++ b/src/lib/external_lgpl/tecs/tecs.cpp
@@ -236,9 +236,9 @@ void TECS::_update_height_demand(float demand, float state)
// // _hgt_rate_dem);
_hgt_dem_adj = demand;//0.025f * demand + 0.975f * _hgt_dem_adj_last;
+ _hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p + _heightrate_ff * (_hgt_dem_adj - _hgt_dem_adj_last)/_DT;
_hgt_dem_adj_last = _hgt_dem_adj;
- _hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p;
// Limit height rate of change
if (_hgt_rate_dem > _maxClimbRate) {
_hgt_rate_dem = _maxClimbRate;
@@ -252,6 +252,11 @@ void TECS::_update_height_demand(float demand, float state)
void TECS::_detect_underspeed(void)
{
+ if (!_detect_underspeed_enabled) {
+ _underspeed = false;
+ return;
+ }
+
if (((_integ5_state < _TASmin * 0.9f) && (_throttle_dem >= _THRmaxf * 0.95f)) || ((_integ3_state < _hgt_dem_adj) && _underspeed)) {
_underspeed = true;
@@ -294,11 +299,11 @@ void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotM
// Calculate throttle demand
// If underspeed condition is set, then demand full throttle
if (_underspeed) {
- _throttle_dem_unc = 1.0f;
+ _throttle_dem = 1.0f;
} else {
// Calculate gain scaler from specific energy error to throttle
- float K_STE2Thr = 1 / (_timeConst * (_STEdot_max - _STEdot_min));
+ float K_STE2Thr = 1 / (_timeConstThrot * (_STEdot_max - _STEdot_min));
// Calculate feed-forward throttle
float ff_throttle = 0;
@@ -327,9 +332,12 @@ void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotM
_throttle_dem = constrain(_throttle_dem,
_last_throttle_dem - thrRateIncr,
_last_throttle_dem + thrRateIncr);
- _last_throttle_dem = _throttle_dem;
}
+ // Ensure _last_throttle_dem is always initialized properly
+ // Also: The throttle_slewrate limit is only applied to throttle_dem, but does not limit the integrator!!
+ _last_throttle_dem = _throttle_dem;
+
// Calculate integrator state upper and lower limits
// Set to a value thqat will allow 0.1 (10%) throttle saturation to allow for noise on the demand
@@ -355,10 +363,10 @@ void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotM
} else {
_throttle_dem = ff_throttle;
}
- }
- // Constrain throttle demand
- _throttle_dem = constrain(_throttle_dem, _THRminf, _THRmaxf);
+ // Constrain throttle demand
+ _throttle_dem = constrain(_throttle_dem, _THRminf, _THRmaxf);
+ }
}
void TECS::_detect_bad_descent(void)
@@ -551,18 +559,30 @@ void TECS::update_pitch_throttle(const math::Matrix<3,3> &rotMat, float pitch, f
// Calculate pitch demand
_update_pitch();
-// // Write internal variables to the log_tuning structure. This
-// // structure will be logged in dataflash at 10Hz
- // log_tuning.hgt_dem = _hgt_dem_adj;
- // log_tuning.hgt = _integ3_state;
- // log_tuning.dhgt_dem = _hgt_rate_dem;
- // log_tuning.dhgt = _integ2_state;
- // log_tuning.spd_dem = _TAS_dem_adj;
- // log_tuning.spd = _integ5_state;
- // log_tuning.dspd = _vel_dot;
- // log_tuning.ithr = _integ6_state;
- // log_tuning.iptch = _integ7_state;
- // log_tuning.thr = _throttle_dem;
- // log_tuning.ptch = _pitch_dem;
- // log_tuning.dspd_dem = _TAS_rate_dem;
+ _tecs_state.timestamp = now;
+
+ if (_underspeed) {
+ _tecs_state.mode = ECL_TECS_MODE_UNDERSPEED;
+ } else if (_badDescent) {
+ _tecs_state.mode = ECL_TECS_MODE_BAD_DESCENT;
+ } else if (_climbOutDem) {
+ _tecs_state.mode = ECL_TECS_MODE_CLIMBOUT;
+ } else {
+ // If no error flag applies, conclude normal
+ _tecs_state.mode = ECL_TECS_MODE_NORMAL;
+ }
+
+ _tecs_state.hgt_dem = _hgt_dem_adj;
+ _tecs_state.hgt = _integ3_state;
+ _tecs_state.dhgt_dem = _hgt_rate_dem;
+ _tecs_state.dhgt = _integ2_state;
+ _tecs_state.spd_dem = _TAS_dem_adj;
+ _tecs_state.spd = _integ5_state;
+ _tecs_state.dspd = _vel_dot;
+ _tecs_state.ithr = _integ6_state;
+ _tecs_state.iptch = _integ7_state;
+ _tecs_state.thr = _throttle_dem;
+ _tecs_state.ptch = _pitch_dem;
+ _tecs_state.dspd_dem = _TAS_rate_dem;
+
}
diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h
index 5cafb1c79..eb45237b7 100644
--- a/src/lib/external_lgpl/tecs/tecs.h
+++ b/src/lib/external_lgpl/tecs/tecs.h
@@ -28,6 +28,28 @@ class __EXPORT TECS
{
public:
TECS() :
+ _tecs_state {},
+ _update_50hz_last_usec(0),
+ _update_speed_last_usec(0),
+ _update_pitch_throttle_last_usec(0),
+ // TECS tuning parameters
+ _hgtCompFiltOmega(0.0f),
+ _spdCompFiltOmega(0.0f),
+ _maxClimbRate(2.0f),
+ _minSinkRate(1.0f),
+ _maxSinkRate(2.0f),
+ _timeConst(5.0f),
+ _timeConstThrot(8.0f),
+ _ptchDamp(0.0f),
+ _thrDamp(0.0f),
+ _integGain(0.0f),
+ _vertAccLim(0.0f),
+ _rollComp(0.0f),
+ _spdWeight(0.5f),
+ _heightrate_p(0.0f),
+ _heightrate_ff(0.0f),
+ _speedrate_p(0.0f),
+ _throttle_dem(0.0f),
_pitch_dem(0.0f),
_integ1_state(0.0f),
_integ2_state(0.0f),
@@ -45,6 +67,9 @@ public:
_hgt_dem_prev(0.0f),
_TAS_dem_adj(0.0f),
_STEdotErrLast(0.0f),
+ _underspeed(false),
+ _detect_underspeed_enabled(true),
+ _badDescent(false),
_climbOutDem(false),
_SPE_dem(0.0f),
_SKE_dem(0.0f),
@@ -100,29 +125,42 @@ public:
return _spdWeight;
}
- // log data on internal state of the controller. Called at 10Hz
- // void log_data(DataFlash_Class &dataflash, uint8_t msgid);
-
- // struct PACKED log_TECS_Tuning {
- // LOG_PACKET_HEADER;
- // float hgt;
- // float dhgt;
- // float hgt_dem;
- // float dhgt_dem;
- // float spd_dem;
- // float spd;
- // float dspd;
- // float ithr;
- // float iptch;
- // float thr;
- // float ptch;
- // float dspd_dem;
- // } log_tuning;
+ enum ECL_TECS_MODE {
+ ECL_TECS_MODE_NORMAL = 0,
+ ECL_TECS_MODE_UNDERSPEED,
+ ECL_TECS_MODE_BAD_DESCENT,
+ ECL_TECS_MODE_CLIMBOUT
+ };
+
+ struct tecs_state {
+ uint64_t timestamp;
+ float hgt;
+ float dhgt;
+ float hgt_dem;
+ float dhgt_dem;
+ float spd_dem;
+ float spd;
+ float dspd;
+ float ithr;
+ float iptch;
+ float thr;
+ float ptch;
+ float dspd_dem;
+ enum ECL_TECS_MODE mode;
+ };
+
+ void get_tecs_state(struct tecs_state& state) {
+ state = _tecs_state;
+ }
void set_time_const(float time_const) {
_timeConst = time_const;
}
+ void set_time_const_throt(float time_const_throt) {
+ _timeConstThrot = time_const_throt;
+ }
+
void set_min_sink_rate(float rate) {
_minSinkRate = rate;
}
@@ -183,11 +221,22 @@ public:
_heightrate_p = heightrate_p;
}
+ void set_heightrate_ff(float heightrate_ff) {
+ _heightrate_ff = heightrate_ff;
+ }
+
void set_speedrate_p(float speedrate_p) {
_speedrate_p = speedrate_p;
}
+ void set_detect_underspeed_enabled(bool enabled) {
+ _detect_underspeed_enabled = enabled;
+ }
+
private:
+
+ struct tecs_state _tecs_state;
+
// Last time update_50Hz was called
uint64_t _update_50hz_last_usec;
@@ -204,6 +253,7 @@ private:
float _minSinkRate;
float _maxSinkRate;
float _timeConst;
+ float _timeConstThrot;
float _ptchDamp;
float _thrDamp;
float _integGain;
@@ -211,6 +261,7 @@ private:
float _rollComp;
float _spdWeight;
float _heightrate_p;
+ float _heightrate_ff;
float _speedrate_p;
// throttle demand in the range from 0.0 to 1.0
@@ -285,15 +336,15 @@ private:
// Underspeed condition
bool _underspeed;
+ // Underspeed detection enabled
+ bool _detect_underspeed_enabled;
+
// Bad descent condition caused by unachievable airspeed demand
bool _badDescent;
// climbout mode
bool _climbOutDem;
- // throttle demand before limiting
- float _throttle_dem_unc;
-
// pitch demand before limiting
float _pitch_dem_unc;
diff --git a/src/lib/geo/geo.c b/src/lib/geo/geo.c
index e600976ce..f595467b3 100644
--- a/src/lib/geo/geo.c
+++ b/src/lib/geo/geo.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012, 2014 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -49,39 +49,124 @@
#include <stdio.h>
#include <math.h>
#include <stdbool.h>
+#include <string.h>
+#include <float.h>
+
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
/*
* Azimuthal Equidistant Projection
* formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html
*/
-__EXPORT void map_projection_init(struct map_projection_reference_s *ref, double lat_0, double lon_0) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
+static struct map_projection_reference_s mp_ref = {0.0, 0.0, 0.0, 0.0, false, 0};
+static struct globallocal_converter_reference_s gl_ref = {0.0f, false};
+
+__EXPORT bool map_projection_global_initialized()
+{
+ return map_projection_initialized(&mp_ref);
+}
+
+__EXPORT bool map_projection_initialized(const struct map_projection_reference_s *ref)
{
- ref->lat = lat_0 / 180.0 * M_PI;
- ref->lon = lon_0 / 180.0 * M_PI;
+ return ref->init_done;
+}
- ref->sin_lat = sin(ref->lat);
- ref->cos_lat = cos(ref->lat);
+__EXPORT uint64_t map_projection_global_timestamp()
+{
+ return map_projection_timestamp(&mp_ref);
}
-__EXPORT void map_projection_project(struct map_projection_reference_s *ref, double lat, double lon, float *x, float *y)
+__EXPORT uint64_t map_projection_timestamp(const struct map_projection_reference_s *ref)
{
- double lat_rad = lat / 180.0 * M_PI;
- double lon_rad = lon / 180.0 * M_PI;
+ return ref->timestamp;
+}
+
+__EXPORT int map_projection_global_init(double lat_0, double lon_0, uint64_t timestamp) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
+{
+ if (strcmp("commander", getprogname()) == 0) {
+ return map_projection_init_timestamped(&mp_ref, lat_0, lon_0, timestamp);
+ } else {
+ return -1;
+ }
+}
+
+__EXPORT int map_projection_init_timestamped(struct map_projection_reference_s *ref, double lat_0, double lon_0, uint64_t timestamp) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
+{
+
+ ref->lat_rad = lat_0 * M_DEG_TO_RAD;
+ ref->lon_rad = lon_0 * M_DEG_TO_RAD;
+ ref->sin_lat = sin(ref->lat_rad);
+ ref->cos_lat = cos(ref->lat_rad);
+
+ ref->timestamp = timestamp;
+ ref->init_done = true;
+
+ return 0;
+}
+
+__EXPORT int map_projection_init(struct map_projection_reference_s *ref, double lat_0, double lon_0) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
+{
+ return map_projection_init_timestamped(ref, lat_0, lon_0, hrt_absolute_time());
+}
+
+__EXPORT int map_projection_global_reference(double *ref_lat_rad, double *ref_lon_rad)
+{
+ return map_projection_reference(&mp_ref, ref_lat_rad, ref_lon_rad);
+}
+
+__EXPORT int map_projection_reference(const struct map_projection_reference_s *ref, double *ref_lat_rad, double *ref_lon_rad)
+{
+ if (!map_projection_initialized(ref)) {
+ return -1;
+ }
+
+ *ref_lat_rad = ref->lat_rad;
+ *ref_lon_rad = ref->lon_rad;
+
+ return 0;
+}
+
+__EXPORT int map_projection_global_project(double lat, double lon, float *x, float *y)
+{
+ return map_projection_project(&mp_ref, lat, lon, x, y);
+
+}
+
+__EXPORT int map_projection_project(const struct map_projection_reference_s *ref, double lat, double lon, float *x, float *y)
+{
+ if (!map_projection_initialized(ref)) {
+ return -1;
+ }
+
+ double lat_rad = lat * M_DEG_TO_RAD;
+ double lon_rad = lon * M_DEG_TO_RAD;
double sin_lat = sin(lat_rad);
double cos_lat = cos(lat_rad);
- double cos_d_lon = cos(lon_rad - ref->lon);
+ double cos_d_lon = cos(lon_rad - ref->lon_rad);
double c = acos(ref->sin_lat * sin_lat + ref->cos_lat * cos_lat * cos_d_lon);
- double k = (c == 0.0) ? 1.0 : (c / sin(c));
+ double k = (fabs(c) < DBL_EPSILON) ? 1.0 : (c / sin(c));
*x = k * (ref->cos_lat * sin_lat - ref->sin_lat * cos_lat * cos_d_lon) * CONSTANTS_RADIUS_OF_EARTH;
- *y = k * cos_lat * sin(lon_rad - ref->lon) * CONSTANTS_RADIUS_OF_EARTH;
+ *y = k * cos_lat * sin(lon_rad - ref->lon_rad) * CONSTANTS_RADIUS_OF_EARTH;
+
+ return 0;
}
-__EXPORT void map_projection_reproject(struct map_projection_reference_s *ref, float x, float y, double *lat, double *lon)
+__EXPORT int map_projection_global_reproject(float x, float y, double *lat, double *lon)
{
+ return map_projection_reproject(&mp_ref, x, y, lat, lon);
+}
+
+__EXPORT int map_projection_reproject(const struct map_projection_reference_s *ref, float x, float y, double *lat, double *lon)
+{
+ if (!map_projection_initialized(ref)) {
+ return -1;
+ }
+
double x_rad = x / CONSTANTS_RADIUS_OF_EARTH;
double y_rad = y / CONSTANTS_RADIUS_OF_EARTH;
double c = sqrtf(x_rad * x_rad + y_rad * y_rad);
@@ -91,19 +176,101 @@ __EXPORT void map_projection_reproject(struct map_projection_reference_s *ref, f
double lat_rad;
double lon_rad;
- if (c != 0.0) {
+ if (fabs(c) > DBL_EPSILON) {
lat_rad = asin(cos_c * ref->sin_lat + (x_rad * sin_c * ref->cos_lat) / c);
- lon_rad = (ref->lon + atan2(y_rad * sin_c, c * ref->cos_lat * cos_c - x_rad * ref->sin_lat * sin_c));
+ lon_rad = (ref->lon_rad + atan2(y_rad * sin_c, c * ref->cos_lat * cos_c - x_rad * ref->sin_lat * sin_c));
} else {
- lat_rad = ref->lat;
- lon_rad = ref->lon;
+ lat_rad = ref->lat_rad;
+ lon_rad = ref->lon_rad;
}
*lat = lat_rad * 180.0 / M_PI;
*lon = lon_rad * 180.0 / M_PI;
+
+ return 0;
+}
+
+__EXPORT int map_projection_global_getref(double *lat_0, double *lon_0)
+{
+ if (!map_projection_global_initialized()) {
+ return -1;
+ }
+
+ if (lat_0 != NULL) {
+ *lat_0 = M_RAD_TO_DEG * mp_ref.lat_rad;
+ }
+
+ if (lon_0 != NULL) {
+ *lon_0 = M_RAD_TO_DEG * mp_ref.lon_rad;
+ }
+
+ return 0;
+
+}
+__EXPORT int globallocalconverter_init(double lat_0, double lon_0, float alt_0, uint64_t timestamp)
+{
+ if (strcmp("commander", getprogname()) == 0) {
+ gl_ref.alt = alt_0;
+ if (!map_projection_global_init(lat_0, lon_0, timestamp))
+ {
+ gl_ref.init_done = true;
+ return 0;
+ } else {
+ gl_ref.init_done = false;
+ return -1;
+ }
+ } else {
+ return -1;
+ }
+}
+
+__EXPORT bool globallocalconverter_initialized()
+{
+ return gl_ref.init_done && map_projection_global_initialized();
+}
+
+__EXPORT int globallocalconverter_tolocal(double lat, double lon, float alt, float *x, float *y, float *z)
+{
+ if (!map_projection_global_initialized()) {
+ return -1;
+ }
+
+ map_projection_global_project(lat, lon, x, y);
+ *z = gl_ref.alt - alt;
+
+ return 0;
}
+__EXPORT int globallocalconverter_toglobal(float x, float y, float z, double *lat, double *lon, float *alt)
+{
+ if (!map_projection_global_initialized()) {
+ return -1;
+ }
+
+ map_projection_global_reproject(x, y, lat, lon);
+ *alt = gl_ref.alt - z;
+
+ return 0;
+}
+
+__EXPORT int globallocalconverter_getref(double *lat_0, double *lon_0, float *alt_0)
+{
+ if (!map_projection_global_initialized()) {
+ return -1;
+ }
+
+ if (map_projection_global_getref(lat_0, lon_0))
+ {
+ return -1;
+ }
+
+ if (alt_0 != NULL) {
+ *alt_0 = gl_ref.alt;
+ }
+
+ return 0;
+}
__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next)
{
@@ -195,8 +362,12 @@ __EXPORT int get_distance_to_line(struct crosstrack_error_s *crosstrack_error, d
crosstrack_error->distance = 0.0f;
crosstrack_error->bearing = 0.0f;
+ dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
+
// Return error if arguments are bad
- if (lat_now == 0.0 || lon_now == 0.0 || lat_start == 0.0 || lon_start == 0.0 || lat_end == 0.0d || lon_end == 0.0d) { return return_value; }
+ if (dist_to_end < 0.1f) {
+ return ERROR;
+ }
bearing_end = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
bearing_track = get_bearing_to_next_waypoint(lat_start, lon_start, lat_end, lon_end);
@@ -210,7 +381,6 @@ __EXPORT int get_distance_to_line(struct crosstrack_error_s *crosstrack_error, d
return return_value;
}
- dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
crosstrack_error->distance = (dist_to_end) * sinf(bearing_diff);
if (sin(bearing_diff) >= 0) {
@@ -247,10 +417,10 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, do
crosstrack_error->bearing = 0.0f;
// Return error if arguments are bad
- if (lat_now == 0.0 || lon_now == 0.0 || lat_center == 0.0 || lon_center == 0.0 || radius == 0.0f) { return return_value; }
+ if (radius < 0.1f) { return return_value; }
- if (arc_sweep >= 0) {
+ if (arc_sweep >= 0.0f) {
bearing_sector_start = arc_start_bearing;
bearing_sector_end = arc_start_bearing + arc_sweep;
@@ -296,8 +466,8 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, do
double start_disp_x = (double)radius * sin(arc_start_bearing);
double start_disp_y = (double)radius * cos(arc_start_bearing);
- double end_disp_x = (double)radius * sin(_wrapPI((double)(arc_start_bearing + arc_sweep)));
- double end_disp_y = (double)radius * cos(_wrapPI((double)(arc_start_bearing + arc_sweep)));
+ double end_disp_x = (double)radius * sin(_wrap_pi((double)(arc_start_bearing + arc_sweep)));
+ double end_disp_y = (double)radius * cos(_wrap_pi((double)(arc_start_bearing + arc_sweep)));
double lon_start = lon_now + start_disp_x / 111111.0;
double lat_start = lat_now + start_disp_y * cos(lat_now) / 111111.0;
double lon_end = lon_now + end_disp_x / 111111.0;
@@ -317,7 +487,7 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, do
}
- crosstrack_error->bearing = _wrapPI((double)crosstrack_error->bearing);
+ crosstrack_error->bearing = _wrap_pi((double)crosstrack_error->bearing);
return_value = OK;
return return_value;
}
diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h
index 8b286af36..2311e0a7c 100644
--- a/src/lib/geo/geo.h
+++ b/src/lib/geo/geo.h
@@ -69,39 +69,162 @@ struct crosstrack_error_s {
/* lat/lon are in radians */
struct map_projection_reference_s {
- double lat;
- double lon;
+ double lat_rad;
+ double lon_rad;
double sin_lat;
double cos_lat;
+ bool init_done;
+ uint64_t timestamp;
};
+struct globallocal_converter_reference_s {
+ float alt;
+ bool init_done;
+};
+
+/**
+ * Checks if global projection was initialized
+ * @return true if map was initialized before, false else
+ */
+__EXPORT bool map_projection_global_initialized(void);
+
+/**
+ * Checks if projection given as argument was initialized
+ * @return true if map was initialized before, false else
+ */
+__EXPORT bool map_projection_initialized(const struct map_projection_reference_s *ref);
+
+/**
+ * Get the timestamp of the global map projection
+ * @return the timestamp of the map_projection
+ */
+__EXPORT uint64_t map_projection_global_timestamp(void);
+
+/**
+ * Get the timestamp of the map projection given by the argument
+ * @return the timestamp of the map_projection
+ */
+__EXPORT uint64_t map_projection_timestamp(const struct map_projection_reference_s *ref);
+
+/**
+ * Writes the reference values of the global projection to ref_lat and ref_lon
+ * @return 0 if map_projection_init was called before, -1 else
+ */
+__EXPORT int map_projection_global_reference(double *ref_lat_rad, double *ref_lon_rad);
+
/**
- * Initializes the map transformation.
+ * Writes the reference values of the projection given by the argument to ref_lat and ref_lon
+ * @return 0 if map_projection_init was called before, -1 else
+ */
+__EXPORT int map_projection_reference(const struct map_projection_reference_s *ref, double *ref_lat_rad, double *ref_lon_rad);
+
+/**
+ * Initializes the global map transformation.
+ *
+ * Initializes the transformation between the geographic coordinate system and
+ * the azimuthal equidistant plane
+ * @param lat in degrees (47.1234567°, not 471234567°)
+ * @param lon in degrees (8.1234567°, not 81234567°)
+ */
+__EXPORT int map_projection_global_init(double lat_0, double lon_0, uint64_t timestamp);
+
+/**
+ * Initializes the map transformation given by the argument.
+ *
+ * Initializes the transformation between the geographic coordinate system and
+ * the azimuthal equidistant plane
+ * @param lat in degrees (47.1234567°, not 471234567°)
+ * @param lon in degrees (8.1234567°, not 81234567°)
+ */
+__EXPORT int map_projection_init_timestamped(struct map_projection_reference_s *ref,
+ double lat_0, double lon_0, uint64_t timestamp);
+
+/**
+ * Initializes the map transformation given by the argument and sets the timestamp to now.
*
- * Initializes the transformation between the geographic coordinate system and the azimuthal equidistant plane
+ * Initializes the transformation between the geographic coordinate system and
+ * the azimuthal equidistant plane
* @param lat in degrees (47.1234567°, not 471234567°)
* @param lon in degrees (8.1234567°, not 81234567°)
*/
-__EXPORT void map_projection_init(struct map_projection_reference_s *ref, double lat_0, double lon_0);
+__EXPORT int map_projection_init(struct map_projection_reference_s *ref, double lat_0, double lon_0);
/**
- * Transforms a point in the geographic coordinate system to the local azimuthal equidistant plane
+ * Transforms a point in the geographic coordinate system to the local
+ * azimuthal equidistant plane using the global projection
* @param x north
* @param y east
* @param lat in degrees (47.1234567°, not 471234567°)
* @param lon in degrees (8.1234567°, not 81234567°)
+ * @return 0 if map_projection_init was called before, -1 else
*/
-__EXPORT void map_projection_project(struct map_projection_reference_s *ref, double lat, double lon, float *x, float *y);
+__EXPORT int map_projection_global_project(double lat, double lon, float *x, float *y);
+
+
+ /* Transforms a point in the geographic coordinate system to the local
+ * azimuthal equidistant plane using the projection given by the argument
+ * @param x north
+ * @param y east
+ * @param lat in degrees (47.1234567°, not 471234567°)
+ * @param lon in degrees (8.1234567°, not 81234567°)
+ * @return 0 if map_projection_init was called before, -1 else
+ */
+__EXPORT int map_projection_project(const struct map_projection_reference_s *ref, double lat, double lon, float *x, float *y);
+
+/**
+ * Transforms a point in the local azimuthal equidistant plane to the
+ * geographic coordinate system using the global projection
+ *
+ * @param x north
+ * @param y east
+ * @param lat in degrees (47.1234567°, not 471234567°)
+ * @param lon in degrees (8.1234567°, not 81234567°)
+ * @return 0 if map_projection_init was called before, -1 else
+ */
+__EXPORT int map_projection_global_reproject(float x, float y, double *lat, double *lon);
/**
- * Transforms a point in the local azimuthal equidistant plane to the geographic coordinate system
+ * Transforms a point in the local azimuthal equidistant plane to the
+ * geographic coordinate system using the projection given by the argument
*
* @param x north
* @param y east
* @param lat in degrees (47.1234567°, not 471234567°)
* @param lon in degrees (8.1234567°, not 81234567°)
+ * @return 0 if map_projection_init was called before, -1 else
+ */
+__EXPORT int map_projection_reproject(const struct map_projection_reference_s *ref, float x, float y, double *lat, double *lon);
+
+/**
+ * Get reference position of the global map projection
+ */
+__EXPORT int map_projection_global_getref(double *lat_0, double *lon_0);
+
+/**
+ * Initialize the global mapping between global position (spherical) and local position (NED).
+ */
+__EXPORT int globallocalconverter_init(double lat_0, double lon_0, float alt_0, uint64_t timestamp);
+
+/**
+ * Checks if globallocalconverter was initialized
+ * @return true if map was initialized before, false else
+ */
+__EXPORT bool globallocalconverter_initialized(void);
+
+/**
+ * Convert from global position coordinates to local position coordinates using the global reference
+ */
+__EXPORT int globallocalconverter_tolocal(double lat, double lon, float alt, float *x, float *y, float *z);
+
+/**
+ * Convert from local position coordinates to global position coordinates using the global reference
+ */
+__EXPORT int globallocalconverter_toglobal(float x, float y, float z, double *lat, double *lon, float *alt);
+
+/**
+ * Get reference position of the global to local converter
*/
-__EXPORT void map_projection_reproject(struct map_projection_reference_s *ref, float x, float y, double *lat, double *lon);
+__EXPORT int globallocalconverter_getref(double *lat_0, double *lon_0, float *alt_0);
/**
* Returns the distance to the next waypoint in meters.
diff --git a/src/lib/launchdetection/CatapultLaunchMethod.cpp b/src/lib/launchdetection/CatapultLaunchMethod.cpp
index c555a0a69..2ea1c414b 100644
--- a/src/lib/launchdetection/CatapultLaunchMethod.cpp
+++ b/src/lib/launchdetection/CatapultLaunchMethod.cpp
@@ -49,9 +49,11 @@ CatapultLaunchMethod::CatapultLaunchMethod(SuperBlock *parent) :
SuperBlock(parent, "CAT"),
last_timestamp(hrt_absolute_time()),
integrator(0.0f),
- launchDetected(false),
- threshold_accel(this, "A"),
- threshold_time(this, "T")
+ state(LAUNCHDETECTION_RES_NONE),
+ thresholdAccel(this, "A"),
+ thresholdTime(this, "T"),
+ motorDelay(this, "MDEL"),
+ pitchMaxPreThrottle(this, "PMAX")
{
}
@@ -65,34 +67,66 @@ void CatapultLaunchMethod::update(float accel_x)
float dt = (float)hrt_elapsed_time(&last_timestamp) * 1e-6f;
last_timestamp = hrt_absolute_time();
- if (accel_x > threshold_accel.get()) {
- integrator += accel_x * dt;
-// warnx("*** integrator %.3f, threshold_accel %.3f, threshold_time %.3f, accel_x %.3f, dt %.3f",
-// (double)integrator, (double)threshold_accel.get(), (double)threshold_time.get(), (double)accel_x, (double)dt);
- if (integrator > threshold_accel.get() * threshold_time.get()) {
- launchDetected = true;
+ switch (state) {
+ case LAUNCHDETECTION_RES_NONE:
+ /* Detect a acceleration that is longer and stronger as the minimum given by the params */
+ if (accel_x > thresholdAccel.get()) {
+ integrator += dt;
+ if (integrator > thresholdTime.get()) {
+ if (motorDelay.get() > 0.0f) {
+ state = LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL;
+ warnx("Launch detected: state: enablecontrol, waiting %.2fs until using full"
+ " throttle", (double)motorDelay.get());
+ } else {
+ /* No motor delay set: go directly to enablemotors state */
+ state = LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS;
+ warnx("Launch detected: state: enablemotors (delay not activated)");
+ }
+ }
+ } else {
+ /* reset */
+ reset();
}
+ break;
+
+ case LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL:
+ /* Vehicle is currently controlling attitude but not with full throttle. Waiting undtil delay is
+ * over to allow full throttle */
+ motorDelayCounter += dt;
+ if (motorDelayCounter > motorDelay.get()) {
+ warnx("Launch detected: state enablemotors");
+ state = LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS;
+ }
+ break;
+
+ default:
+ break;
- } else {
-// warnx("integrator %.3f, threshold_accel %.3f, threshold_time %.3f, accel_x %.3f, dt %.3f",
-// (double)integrator, (double)threshold_accel.get(), (double)threshold_time.get(), (double)accel_x, (double)dt);
- /* reset integrator */
- integrator = 0.0f;
- launchDetected = false;
}
}
-bool CatapultLaunchMethod::getLaunchDetected()
+LaunchDetectionResult CatapultLaunchMethod::getLaunchDetected() const
{
- return launchDetected;
+ return state;
}
void CatapultLaunchMethod::reset()
{
integrator = 0.0f;
- launchDetected = false;
+ motorDelayCounter = 0.0f;
+ state = LAUNCHDETECTION_RES_NONE;
+}
+
+float CatapultLaunchMethod::getPitchMax(float pitchMaxDefault) {
+ /* If motor is turned on do not impose the extra limit on maximum pitch */
+ if (state == LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) {
+ return pitchMaxDefault;
+ } else {
+ return pitchMaxPreThrottle.get();
+ }
+
}
}
diff --git a/src/lib/launchdetection/CatapultLaunchMethod.h b/src/lib/launchdetection/CatapultLaunchMethod.h
index 23757f6f3..321dfb1de 100644
--- a/src/lib/launchdetection/CatapultLaunchMethod.h
+++ b/src/lib/launchdetection/CatapultLaunchMethod.h
@@ -57,16 +57,23 @@ public:
~CatapultLaunchMethod();
void update(float accel_x);
- bool getLaunchDetected();
+ LaunchDetectionResult getLaunchDetected() const;
void reset();
+ float getPitchMax(float pitchMaxDefault);
private:
hrt_abstime last_timestamp;
float integrator;
- bool launchDetected;
+ float motorDelayCounter;
- control::BlockParamFloat threshold_accel;
- control::BlockParamFloat threshold_time;
+ LaunchDetectionResult state;
+
+ control::BlockParamFloat thresholdAccel;
+ control::BlockParamFloat thresholdTime;
+ control::BlockParamFloat motorDelay;
+ control::BlockParamFloat pitchMaxPreThrottle; /**< Upper pitch limit before throttle is turned on.
+ Can be used to make sure that the AC does not climb
+ too much while attached to a bungee */
};
diff --git a/src/lib/launchdetection/LaunchDetector.cpp b/src/lib/launchdetection/LaunchDetector.cpp
index 3bf47bbb0..52f5c3257 100644
--- a/src/lib/launchdetection/LaunchDetector.cpp
+++ b/src/lib/launchdetection/LaunchDetector.cpp
@@ -46,6 +46,7 @@ namespace launchdetection
LaunchDetector::LaunchDetector() :
SuperBlock(NULL, "LAUN"),
+ activeLaunchDetectionMethodIndex(-1),
launchdetection_on(this, "ALL_ON"),
throttlePreTakeoff(this, "THR_PRE")
{
@@ -65,7 +66,14 @@ LaunchDetector::~LaunchDetector()
void LaunchDetector::reset()
{
/* Reset all detectors */
- launchMethods[0]->reset();
+ for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
+ launchMethods[i]->reset();
+ }
+
+ /* Reset active launchdetector */
+ activeLaunchDetectionMethodIndex = -1;
+
+
}
void LaunchDetector::update(float accel_x)
@@ -77,17 +85,44 @@ void LaunchDetector::update(float accel_x)
}
}
-bool LaunchDetector::getLaunchDetected()
+LaunchDetectionResult LaunchDetector::getLaunchDetected()
{
if (launchdetection_on.get() == 1) {
- for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
- if(launchMethods[i]->getLaunchDetected()) {
- return true;
+ if (activeLaunchDetectionMethodIndex < 0) {
+ /* None of the active launchmethods has detected a launch, check all launchmethods */
+ for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) {
+ if(launchMethods[i]->getLaunchDetected() != LAUNCHDETECTION_RES_NONE) {
+ warnx("selecting launchmethod %d", i);
+ activeLaunchDetectionMethodIndex = i; // from now on only check this method
+ return launchMethods[i]->getLaunchDetected();
+ }
}
+ } else {
+ return launchMethods[activeLaunchDetectionMethodIndex]->getLaunchDetected();
}
}
- return false;
+ return LAUNCHDETECTION_RES_NONE;
}
+float LaunchDetector::getPitchMax(float pitchMaxDefault) {
+ if (!launchdetection_on.get()) {
+ return pitchMaxDefault;
+ }
+
+ /* if a lauchdetectionmethod is active or only one exists return the pitch limit from this method,
+ * otherwise use the default limit */
+ if (activeLaunchDetectionMethodIndex < 0) {
+ if (sizeof(launchMethods)/sizeof(LaunchMethod) > 1) {
+ return pitchMaxDefault;
+ } else {
+ return launchMethods[0]->getPitchMax(pitchMaxDefault);
+ }
+ } else {
+ return launchMethods[activeLaunchDetectionMethodIndex]->getPitchMax(pitchMaxDefault);
+ }
+
+}
+
+
}
diff --git a/src/lib/launchdetection/LaunchDetector.h b/src/lib/launchdetection/LaunchDetector.h
index 1a214b66e..4215b49d2 100644
--- a/src/lib/launchdetection/LaunchDetector.h
+++ b/src/lib/launchdetection/LaunchDetector.h
@@ -59,14 +59,23 @@ public:
void reset();
void update(float accel_x);
- bool getLaunchDetected();
+ LaunchDetectionResult getLaunchDetected();
bool launchDetectionEnabled() { return (bool)launchdetection_on.get(); };
float getThrottlePreTakeoff() {return throttlePreTakeoff.get(); }
+ /* Returns a maximum pitch in deg. Different launch methods may impose upper pitch limits during launch */
+ float getPitchMax(float pitchMaxDefault);
+
// virtual bool getLaunchDetected();
protected:
private:
+ int activeLaunchDetectionMethodIndex; /**< holds a index to the launchMethod in the array launchMethods
+ which detected a Launch. If no launchMethod has detected a launch yet the
+ value is -1. Once one launchMetthod has detected a launch only this
+ method is checked for further adavancing in the state machine (e.g. when
+ to power up the motors) */
+
LaunchMethod* launchMethods[1];
control::BlockParamInt launchdetection_on;
control::BlockParamFloat throttlePreTakeoff;
diff --git a/src/lib/launchdetection/LaunchMethod.h b/src/lib/launchdetection/LaunchMethod.h
index e04467f6a..8b5220cb3 100644
--- a/src/lib/launchdetection/LaunchMethod.h
+++ b/src/lib/launchdetection/LaunchMethod.h
@@ -44,13 +44,27 @@
namespace launchdetection
{
+enum LaunchDetectionResult {
+ LAUNCHDETECTION_RES_NONE = 0, /**< No launch has been detected */
+ LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL = 1, /**< Launch has been detected, the controller should
+ control the attitude. However any motors should not throttle
+ up and still be set to 'throttlePreTakeoff'.
+ For instance this is used to have a delay for the motor
+ when launching a fixed wing aircraft from a bungee */
+ LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS = 2 /**< Launch has been detected, teh controller should control
+ attitude and also throttle up the motors. */
+};
+
class LaunchMethod
{
public:
virtual void update(float accel_x) = 0;
- virtual bool getLaunchDetected() = 0;
+ virtual LaunchDetectionResult getLaunchDetected() const = 0;
virtual void reset() = 0;
+ /* Returns a upper pitch limit if required, otherwise returns pitchMaxDefault */
+ virtual float getPitchMax(float pitchMaxDefault) = 0;
+
protected:
private:
};
diff --git a/src/lib/launchdetection/launchdetection_params.c b/src/lib/launchdetection/launchdetection_params.c
index 8df8c696c..e3aa7ab2d 100644
--- a/src/lib/launchdetection/launchdetection_params.c
+++ b/src/lib/launchdetection/launchdetection_params.c
@@ -78,6 +78,31 @@ PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f);
PARAM_DEFINE_FLOAT(LAUN_CAT_T, 0.05f);
/**
+ * Motor delay
+ *
+ * Delay between starting attitude control and powering up the throttle (giving throttle control to the controller)
+ * Before this timespan is up the throttle will be set to LAUN_THR_PRE, set to 0 to deactivate
+ *
+ * @unit seconds
+ * @min 0
+ * @group Launch detection
+ */
+PARAM_DEFINE_FLOAT(LAUN_CAT_MDEL, 0.0f);
+
+/**
+ * Maximum pitch before the throttle is powered up (during motor delay phase)
+ *
+ * This is an extra limit for the maximum pitch which is imposed in the phase before the throttle turns on.
+ * This allows to limit the maximum pitch angle during a bungee launch (make the launch less steep).
+ *
+ * @unit deg
+ * @min 0
+ * @max 45
+ * @group Launch detection
+ */
+PARAM_DEFINE_FLOAT(LAUN_CAT_PMAX, 30.0f);
+
+/**
* Throttle setting while detecting launch.
*
* The throttle is set to this value while the system is waiting for the take-off.
diff --git a/src/lib/rc/module.mk b/src/lib/rc/module.mk
new file mode 100644
index 000000000..e089c6965
--- /dev/null
+++ b/src/lib/rc/module.mk
@@ -0,0 +1,40 @@
+############################################################################
+#
+# Copyright (c) 2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Yuntec ST24 transmitter protocol decoder
+#
+
+SRCS = st24.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/lib/rc/st24.c b/src/lib/rc/st24.c
new file mode 100644
index 000000000..e8a791b8f
--- /dev/null
+++ b/src/lib/rc/st24.c
@@ -0,0 +1,253 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * @file st24.h
+ *
+ * RC protocol implementation for Yuneec ST24 transmitter.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <stdbool.h>
+#include <stdio.h>
+#include "st24.h"
+
+enum ST24_DECODE_STATE {
+ ST24_DECODE_STATE_UNSYNCED = 0,
+ ST24_DECODE_STATE_GOT_STX1,
+ ST24_DECODE_STATE_GOT_STX2,
+ ST24_DECODE_STATE_GOT_LEN,
+ ST24_DECODE_STATE_GOT_TYPE,
+ ST24_DECODE_STATE_GOT_DATA
+};
+
+const char *decode_states[] = {"UNSYNCED",
+ "GOT_STX1",
+ "GOT_STX2",
+ "GOT_LEN",
+ "GOT_TYPE",
+ "GOT_DATA"
+ };
+
+/* define range mapping here, -+100% -> 1000..2000 */
+#define ST24_RANGE_MIN 0.0f
+#define ST24_RANGE_MAX 4096.0f
+
+#define ST24_TARGET_MIN 1000.0f
+#define ST24_TARGET_MAX 2000.0f
+
+/* pre-calculate the floating point stuff as far as possible at compile time */
+#define ST24_SCALE_FACTOR ((ST24_TARGET_MAX - ST24_TARGET_MIN) / (ST24_RANGE_MAX - ST24_RANGE_MIN))
+#define ST24_SCALE_OFFSET (int)(ST24_TARGET_MIN - (ST24_SCALE_FACTOR * ST24_RANGE_MIN + 0.5f))
+
+static enum ST24_DECODE_STATE _decode_state = ST24_DECODE_STATE_UNSYNCED;
+static unsigned _rxlen;
+
+static ReceiverFcPacket _rxpacket;
+
+uint8_t st24_common_crc8(uint8_t *ptr, uint8_t len)
+{
+ uint8_t i, crc ;
+ crc = 0;
+
+ while (len--) {
+ for (i = 0x80; i != 0; i >>= 1) {
+ if ((crc & 0x80) != 0) {
+ crc <<= 1;
+ crc ^= 0x07;
+
+ } else {
+ crc <<= 1;
+ }
+
+ if ((*ptr & i) != 0) {
+ crc ^= 0x07;
+ }
+ }
+
+ ptr++;
+ }
+
+ return (crc);
+}
+
+
+int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels,
+ uint16_t max_chan_count)
+{
+
+ int ret = 1;
+
+ switch (_decode_state) {
+ case ST24_DECODE_STATE_UNSYNCED:
+ if (byte == ST24_STX1) {
+ _decode_state = ST24_DECODE_STATE_GOT_STX1;
+ } else {
+ ret = 3;
+ }
+
+ break;
+
+ case ST24_DECODE_STATE_GOT_STX1:
+ if (byte == ST24_STX2) {
+ _decode_state = ST24_DECODE_STATE_GOT_STX2;
+
+ } else {
+ _decode_state = ST24_DECODE_STATE_UNSYNCED;
+ }
+
+ break;
+
+ case ST24_DECODE_STATE_GOT_STX2:
+
+ /* ensure no data overflow failure or hack is possible */
+ if ((unsigned)byte <= sizeof(_rxpacket.length) + sizeof(_rxpacket.type) + sizeof(_rxpacket.st24_data)) {
+ _rxpacket.length = byte;
+ _rxlen = 0;
+ _decode_state = ST24_DECODE_STATE_GOT_LEN;
+
+ } else {
+ _decode_state = ST24_DECODE_STATE_UNSYNCED;
+ }
+
+ break;
+
+ case ST24_DECODE_STATE_GOT_LEN:
+ _rxpacket.type = byte;
+ _rxlen++;
+ _decode_state = ST24_DECODE_STATE_GOT_TYPE;
+ break;
+
+ case ST24_DECODE_STATE_GOT_TYPE:
+ _rxpacket.st24_data[_rxlen - 1] = byte;
+ _rxlen++;
+
+ if (_rxlen == (_rxpacket.length - 1)) {
+ _decode_state = ST24_DECODE_STATE_GOT_DATA;
+ }
+
+ break;
+
+ case ST24_DECODE_STATE_GOT_DATA:
+ _rxpacket.crc8 = byte;
+ _rxlen++;
+
+ if (st24_common_crc8((uint8_t *) & (_rxpacket.length), _rxlen) == _rxpacket.crc8) {
+
+ ret = 0;
+
+ /* decode the actual packet */
+
+ switch (_rxpacket.type) {
+
+ case ST24_PACKET_TYPE_CHANNELDATA12: {
+ ChannelData12 *d = (ChannelData12 *)_rxpacket.st24_data;
+
+ *rssi = d->rssi;
+ *rx_count = d->packet_count;
+
+ /* this can lead to rounding of the strides */
+ *channel_count = (max_chan_count < 12) ? max_chan_count : 12;
+
+ unsigned stride_count = (*channel_count * 3) / 2;
+ unsigned chan_index = 0;
+
+ for (unsigned i = 0; i < stride_count; i += 3) {
+ channels[chan_index] = ((uint16_t)d->channel[i] << 4);
+ channels[chan_index] |= ((uint16_t)(0xF0 & d->channel[i + 1]) >> 4);
+ /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
+ channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
+ chan_index++;
+
+ channels[chan_index] = ((uint16_t)d->channel[i + 2]);
+ channels[chan_index] |= (((uint16_t)(0x0F & d->channel[i + 1])) << 8);
+ /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
+ channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
+ chan_index++;
+ }
+ }
+ break;
+
+ case ST24_PACKET_TYPE_CHANNELDATA24: {
+ ChannelData24 *d = (ChannelData24 *)&_rxpacket.st24_data;
+
+ *rssi = d->rssi;
+ *rx_count = d->packet_count;
+
+ /* this can lead to rounding of the strides */
+ *channel_count = (max_chan_count < 24) ? max_chan_count : 24;
+
+ unsigned stride_count = (*channel_count * 3) / 2;
+ unsigned chan_index = 0;
+
+ for (unsigned i = 0; i < stride_count; i += 3) {
+ channels[chan_index] = ((uint16_t)d->channel[i] << 4);
+ channels[chan_index] |= ((uint16_t)(0xF0 & d->channel[i + 1]) >> 4);
+ /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
+ channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
+ chan_index++;
+
+ channels[chan_index] = ((uint16_t)d->channel[i + 2]);
+ channels[chan_index] |= (((uint16_t)(0x0F & d->channel[i + 1])) << 8);
+ /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
+ channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
+ chan_index++;
+ }
+ }
+ break;
+
+ case ST24_PACKET_TYPE_TRANSMITTERGPSDATA: {
+
+ // ReceiverFcPacket* d = (ReceiverFcPacket*)&_rxpacket.st24_data;
+ /* we silently ignore this data for now, as it is unused */
+ ret = 2;
+ }
+ break;
+
+ default:
+ ret = 2;
+ break;
+ }
+
+ } else {
+ /* decoding failed */
+ ret = 4;
+ }
+
+ _decode_state = ST24_DECODE_STATE_UNSYNCED;
+ break;
+ }
+
+ return ret;
+}
diff --git a/src/lib/rc/st24.h b/src/lib/rc/st24.h
new file mode 100644
index 000000000..454234601
--- /dev/null
+++ b/src/lib/rc/st24.h
@@ -0,0 +1,163 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file st24.h
+ *
+ * RC protocol definition for Yuneec ST24 transmitter
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#pragma once
+
+#include <stdint.h>
+
+__BEGIN_DECLS
+
+#define ST24_DATA_LEN_MAX 64
+#define ST24_STX1 0x55
+#define ST24_STX2 0x55
+
+enum ST24_PACKET_TYPE {
+ ST24_PACKET_TYPE_CHANNELDATA12 = 0,
+ ST24_PACKET_TYPE_CHANNELDATA24,
+ ST24_PACKET_TYPE_TRANSMITTERGPSDATA
+};
+
+#pragma pack(push, 1)
+typedef struct {
+ uint8_t header1; ///< 0x55 for a valid packet
+ uint8_t header2; ///< 0x55 for a valid packet
+ uint8_t length; ///< length includes type, data, and crc = sizeof(type)+sizeof(data[payload_len])+sizeof(crc8)
+ uint8_t type; ///< from enum ST24_PACKET_TYPE
+ uint8_t st24_data[ST24_DATA_LEN_MAX];
+ uint8_t crc8; ///< crc8 checksum, calculated by st24_common_crc8 and including fields length, type and st24_data
+} ReceiverFcPacket;
+
+/**
+ * RC Channel data (12 channels).
+ *
+ * This is incoming from the ST24
+ */
+typedef struct {
+ uint16_t t; ///< packet counter or clock
+ uint8_t rssi; ///< signal strength
+ uint8_t packet_count; ///< Number of UART packets sent since reception of last RF frame (this tells something about age / rate)
+ uint8_t channel[18]; ///< channel data, 12 channels (12 bit numbers)
+} ChannelData12;
+
+/**
+ * RC Channel data (12 channels).
+ *
+ */
+typedef struct {
+ uint16_t t; ///< packet counter or clock
+ uint8_t rssi; ///< signal strength
+ uint8_t packet_count; ///< Number of UART packets sent since reception of last RF frame (this tells something about age / rate)
+ uint8_t channel[36]; ///< channel data, 24 channels (12 bit numbers)
+} ChannelData24;
+
+/**
+ * Telemetry packet
+ *
+ * This is outgoing to the ST24
+ *
+ * imuStatus:
+ * 8 bit total
+ * bits 0-2 for status
+ * - value 0 is FAILED
+ * - value 1 is INITIALIZING
+ * - value 2 is RUNNING
+ * - values 3 through 7 are reserved
+ * bits 3-7 are status for sensors (0 or 1)
+ * - mpu6050
+ * - accelerometer
+ * - primary gyro x
+ * - primary gyro y
+ * - primary gyro z
+ *
+ * pressCompassStatus
+ * 8 bit total
+ * bits 0-3 for compass status
+ * - value 0 is FAILED
+ * - value 1 is INITIALIZING
+ * - value 2 is RUNNING
+ * - value 3 - 15 are reserved
+ * bits 4-7 for pressure status
+ * - value 0 is FAILED
+ * - value 1 is INITIALIZING
+ * - value 2 is RUNNING
+ * - value 3 - 15 are reserved
+ *
+ */
+typedef struct {
+ uint16_t t; ///< packet counter or clock
+ int32_t lat; ///< lattitude (degrees) +/- 90 deg
+ int32_t lon; ///< longitude (degrees) +/- 180 deg
+ int32_t alt; ///< 0.01m resolution, altitude (meters)
+ int16_t vx, vy, vz; ///< velocity 0.01m res, +/-320.00 North-East- Down
+ uint8_t nsat; ///<number of satellites
+ uint8_t voltage; ///< 25.4V voltage = 5 + 255*0.1 = 30.5V, min=5V
+ uint8_t current; ///< 0.5A resolution
+ int16_t roll, pitch, yaw; ///< 0.01 degree resolution
+ uint8_t motorStatus; ///< 1 bit per motor for status 1=good, 0= fail
+ uint8_t imuStatus; ///< inertial measurement unit status
+ uint8_t pressCompassStatus; ///< baro / compass status
+} TelemetryData;
+
+#pragma pack(pop)
+
+/**
+ * CRC8 implementation for ST24 protocol
+ *
+ * @param prt Pointer to the data to CRC
+ * @param len number of bytes to accumulate in the checksum
+ * @return the checksum of these bytes over len
+ */
+uint8_t st24_common_crc8(uint8_t *ptr, uint8_t len);
+
+/**
+ * Decoder for ST24 protocol
+ *
+ * @param byte current char to read
+ * @param rssi pointer to a byte where the RSSI value is written back to
+ * @param rx_count pointer to a byte where the receive count of packets signce last wireless frame is written back to
+ * @param channels pointer to a datastructure of size max_chan_count where channel values (12 bit) are written back to
+ * @param max_chan_count maximum channels to decode - if more channels are decoded, the last n are skipped and success (0) is returned
+ * @return 0 for success (a decoded packet), 1 for no packet yet (accumulating), 2 for unknown packet, 3 for out of sync, 4 for checksum error
+ */
+__EXPORT int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count,
+ uint16_t *channels, uint16_t max_chan_count);
+
+__END_DECLS
diff --git a/src/modules/bottle_drop/bottle_drop.cpp b/src/modules/bottle_drop/bottle_drop.cpp
new file mode 100644
index 000000000..31c9157e1
--- /dev/null
+++ b/src/modules/bottle_drop/bottle_drop.cpp
@@ -0,0 +1,907 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file bottle_drop.cpp
+ *
+ * Bottle drop module for Outback Challenge 2014, Team Swiss Fang
+ *
+ * @author Dominik Juchli <juchlid@ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <math.h>
+#include <poll.h>
+#include <time.h>
+#include <sys/ioctl.h>
+#include <drivers/device/device.h>
+#include <drivers/drv_hrt.h>
+#include <arch/board/board.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_command.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/wind_estimate.h>
+#include <uORB/topics/parameter_update.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+#include <dataman/dataman.h>
+#include <mathlib/mathlib.h>
+#include <mavlink/mavlink_log.h>
+
+
+/**
+ * bottle_drop app start / stop handling function
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int bottle_drop_main(int argc, char *argv[]);
+
+class BottleDrop
+{
+public:
+ /**
+ * Constructor
+ */
+ BottleDrop();
+
+ /**
+ * Destructor, also kills task.
+ */
+ ~BottleDrop();
+
+ /**
+ * Start the task.
+ *
+ * @return OK on success.
+ */
+ int start();
+
+ /**
+ * Display status.
+ */
+ void status();
+
+ void open_bay();
+ void close_bay();
+ void drop();
+ void lock_release();
+
+private:
+ bool _task_should_exit; /**< if true, task should exit */
+ int _main_task; /**< handle for task */
+ int _mavlink_fd;
+
+ int _command_sub;
+ int _wind_estimate_sub;
+ struct vehicle_command_s _command;
+ struct vehicle_global_position_s _global_pos;
+ map_projection_reference_s ref;
+
+ orb_advert_t _actuator_pub;
+ struct actuator_controls_s _actuators;
+
+ bool _drop_approval;
+ hrt_abstime _doors_opened;
+ hrt_abstime _drop_time;
+
+ float _alt_clearance;
+
+ struct position_s {
+ double lat; ///< degrees
+ double lon; ///< degrees
+ float alt; ///< m
+ } _target_position, _drop_position;
+
+ enum DROP_STATE {
+ DROP_STATE_INIT = 0,
+ DROP_STATE_TARGET_VALID,
+ DROP_STATE_TARGET_SET,
+ DROP_STATE_BAY_OPEN,
+ DROP_STATE_DROPPED,
+ DROP_STATE_BAY_CLOSED
+ } _drop_state;
+
+ struct mission_s _onboard_mission;
+ orb_advert_t _onboard_mission_pub;
+
+ void task_main();
+
+ void handle_command(struct vehicle_command_s *cmd);
+
+ void answer_command(struct vehicle_command_s *cmd, enum VEHICLE_CMD_RESULT result);
+
+ /**
+ * Set the actuators
+ */
+ int actuators_publish();
+
+ /**
+ * Shim for calling task_main from task_create.
+ */
+ static void task_main_trampoline(int argc, char *argv[]);
+};
+
+namespace bottle_drop
+{
+BottleDrop *g_bottle_drop;
+}
+
+BottleDrop::BottleDrop() :
+
+ _task_should_exit(false),
+ _main_task(-1),
+ _mavlink_fd(-1),
+ _command_sub(-1),
+ _wind_estimate_sub(-1),
+ _command {},
+ _global_pos {},
+ ref {},
+ _actuator_pub(-1),
+ _actuators {},
+ _drop_approval(false),
+ _doors_opened(0),
+ _drop_time(0),
+ _alt_clearance(70.0f),
+ _target_position {},
+ _drop_position {},
+ _drop_state(DROP_STATE_INIT),
+ _onboard_mission {},
+ _onboard_mission_pub(-1)
+{
+}
+
+BottleDrop::~BottleDrop()
+{
+ if (_main_task != -1) {
+
+ /* task wakes up every 100ms or so at the longest */
+ _task_should_exit = true;
+
+ /* wait for a second for the task to quit at our request */
+ unsigned i = 0;
+
+ do {
+ /* wait 20ms */
+ usleep(20000);
+
+ /* if we have given up, kill it */
+ if (++i > 50) {
+ task_delete(_main_task);
+ break;
+ }
+ } while (_main_task != -1);
+ }
+
+ bottle_drop::g_bottle_drop = nullptr;
+}
+
+int
+BottleDrop::start()
+{
+ ASSERT(_main_task == -1);
+
+ /* start the task */
+ _main_task = task_spawn_cmd("bottle_drop",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_DEFAULT + 15,
+ 2048,
+ (main_t)&BottleDrop::task_main_trampoline,
+ nullptr);
+
+ if (_main_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
+
+ return OK;
+}
+
+
+void
+BottleDrop::status()
+{
+ warnx("drop state: %d", _drop_state);
+}
+
+void
+BottleDrop::open_bay()
+{
+ _actuators.control[0] = -1.0f;
+ _actuators.control[1] = 1.0f;
+
+ if (_doors_opened == 0) {
+ _doors_opened = hrt_absolute_time();
+ }
+ warnx("open doors");
+
+ actuators_publish();
+
+ usleep(500 * 1000);
+}
+
+void
+BottleDrop::close_bay()
+{
+ // closed door and locked survival kit
+ _actuators.control[0] = 1.0f;
+ _actuators.control[1] = -1.0f;
+
+ _doors_opened = 0;
+
+ actuators_publish();
+
+ // delay until the bay is closed
+ usleep(500 * 1000);
+}
+
+void
+BottleDrop::drop()
+{
+
+ // update drop actuator, wait 0.5s until the doors are open before dropping
+ hrt_abstime starttime = hrt_absolute_time();
+
+ // force the door open if we have to
+ if (_doors_opened == 0) {
+ open_bay();
+ warnx("bay not ready, forced open");
+ }
+
+ while (hrt_elapsed_time(&_doors_opened) < 500 * 1000 && hrt_elapsed_time(&starttime) < 2000000) {
+ usleep(50000);
+ warnx("delayed by door!");
+ }
+
+ _actuators.control[2] = 1.0f;
+
+ _drop_time = hrt_absolute_time();
+ actuators_publish();
+
+ warnx("dropping now");
+
+ // Give it time to drop
+ usleep(1000 * 1000);
+}
+
+void
+BottleDrop::lock_release()
+{
+ _actuators.control[2] = -1.0f;
+ actuators_publish();
+
+ warnx("closing release");
+}
+
+int
+BottleDrop::actuators_publish()
+{
+ _actuators.timestamp = hrt_absolute_time();
+
+ // lazily publish _actuators only once available
+ if (_actuator_pub > 0) {
+ return orb_publish(ORB_ID(actuator_controls_2), _actuator_pub, &_actuators);
+
+ } else {
+ _actuator_pub = orb_advertise(ORB_ID(actuator_controls_2), &_actuators);
+ if (_actuator_pub > 0) {
+ return OK;
+ } else {
+ return -1;
+ }
+ }
+}
+
+void
+BottleDrop::task_main()
+{
+
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ mavlink_log_info(_mavlink_fd, "[bottle_drop] started");
+
+ _command_sub = orb_subscribe(ORB_ID(vehicle_command));
+ _wind_estimate_sub = orb_subscribe(ORB_ID(wind_estimate));
+
+ bool updated = false;
+
+ float z_0; // ground properties
+ float turn_radius; // turn radius of the UAV
+ float precision; // Expected precision of the UAV
+
+ float ground_distance = _alt_clearance; // Replace by closer estimate in loop
+
+ // constant
+ float g = CONSTANTS_ONE_G; // constant of gravity [m/s^2]
+ float m = 0.5f; // mass of bottle [kg]
+ float rho = 1.2f; // air density [kg/m^3]
+ float A = ((0.063f * 0.063f) / 4.0f * M_PI_F); // Bottle cross section [m^2]
+ float dt_freefall_prediction = 0.01f; // step size of the free fall prediction [s]
+
+ // Has to be estimated by experiment
+ float cd = 0.86f; // Drag coefficient for a cylinder with a d/l ratio of 1/3 []
+ float t_signal =
+ 0.084f; // Time span between sending the signal and the bottle top reaching level height with the bottom of the plane [s]
+ float t_door =
+ 0.7f; // The time the system needs to open the door + safety, is also the time the palyload needs to safely escape the shaft [s]
+
+
+ // Definition
+ float h_0; // height over target
+ float az; // acceleration in z direction[m/s^2]
+ float vz; // velocity in z direction [m/s]
+ float z; // fallen distance [m]
+ float h; // height over target [m]
+ float ax; // acceleration in x direction [m/s^2]
+ float vx; // ground speed in x direction [m/s]
+ float x; // traveled distance in x direction [m]
+ float vw; // wind speed [m/s]
+ float vrx; // relative velocity in x direction [m/s]
+ float v; // relative speed vector [m/s]
+ float Fd; // Drag force [N]
+ float Fdx; // Drag force in x direction [N]
+ float Fdz; // Drag force in z direction [N]
+ float x_drop, y_drop; // coordinates of the drop point in reference to the target (projection of NED)
+ float x_t, y_t; // coordinates of the target in reference to the target x_t = 0, y_t = 0 (projection of NED)
+ float x_l, y_l; // local position in projected coordinates
+ float x_f, y_f; // to-be position of the UAV after dt_runs seconds in projected coordinates
+ double x_f_NED, y_f_NED; // to-be position of the UAV after dt_runs seconds in NED
+ float distance_open_door; // The distance the UAV travels during its doors open [m]
+ float approach_error = 0.0f; // The error in radians between current ground vector and desired ground vector
+ float distance_real = 0; // The distance between the UAVs position and the drop point [m]
+ float future_distance = 0; // The distance between the UAVs to-be position and the drop point [m]
+
+ unsigned counter = 0;
+
+ param_t param_gproperties = param_find("BD_GPROPERTIES");
+ param_t param_turn_radius = param_find("BD_TURNRADIUS");
+ param_t param_precision = param_find("BD_PRECISION");
+ param_t param_cd = param_find("BD_OBJ_CD");
+ param_t param_mass = param_find("BD_OBJ_MASS");
+ param_t param_surface = param_find("BD_OBJ_SURFACE");
+
+
+ param_get(param_precision, &precision);
+ param_get(param_turn_radius, &turn_radius);
+ param_get(param_gproperties, &z_0);
+ param_get(param_cd, &cd);
+ param_get(param_mass, &m);
+ param_get(param_surface, &A);
+
+ int vehicle_global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+
+ struct parameter_update_s update;
+ memset(&update, 0, sizeof(update));
+ int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
+
+ struct mission_item_s flight_vector_s {};
+ struct mission_item_s flight_vector_e {};
+
+ flight_vector_s.nav_cmd = NAV_CMD_WAYPOINT;
+ flight_vector_s.acceptance_radius = 50; // TODO: make parameter
+ flight_vector_s.autocontinue = true;
+ flight_vector_s.altitude_is_relative = false;
+
+ flight_vector_e.nav_cmd = NAV_CMD_WAYPOINT;
+ flight_vector_e.acceptance_radius = 50; // TODO: make parameter
+ flight_vector_e.autocontinue = true;
+ flight_vector_s.altitude_is_relative = false;
+
+ struct wind_estimate_s wind;
+
+ // wakeup source(s)
+ struct pollfd fds[1];
+
+ // Setup of loop
+ fds[0].fd = _command_sub;
+ fds[0].events = POLLIN;
+
+ // Whatever state the bay is in, we want it closed on startup
+ lock_release();
+ close_bay();
+
+ while (!_task_should_exit) {
+
+ /* wait for up to 100ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 50);
+
+ /* this is undesirable but not much we can do - might want to flag unhappy status */
+ if (pret < 0) {
+ warn("poll error %d, %d", pret, errno);
+ continue;
+ }
+
+ /* vehicle commands updated */
+ if (fds[0].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_command), _command_sub, &_command);
+ handle_command(&_command);
+ }
+
+ orb_check(vehicle_global_position_sub, &updated);
+ if (updated) {
+ /* copy global position */
+ orb_copy(ORB_ID(vehicle_global_position), vehicle_global_position_sub, &_global_pos);
+ }
+
+ if (_global_pos.timestamp == 0) {
+ continue;
+ }
+
+ const unsigned sleeptime_us = 9500;
+
+ hrt_abstime last_run = hrt_absolute_time();
+ float dt_runs = sleeptime_us / 1e6f;
+
+ // switch to faster updates during the drop
+ while (_drop_state > DROP_STATE_INIT) {
+
+ // Get wind estimate
+ orb_check(_wind_estimate_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(wind_estimate), _wind_estimate_sub, &wind);
+ }
+
+ // Get vehicle position
+ orb_check(vehicle_global_position_sub, &updated);
+ if (updated) {
+ // copy global position
+ orb_copy(ORB_ID(vehicle_global_position), vehicle_global_position_sub, &_global_pos);
+ }
+
+ // Get parameter updates
+ orb_check(parameter_update_sub, &updated);
+ if (updated) {
+ // copy global position
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
+
+ // update all parameters
+ param_get(param_gproperties, &z_0);
+ param_get(param_turn_radius, &turn_radius);
+ param_get(param_precision, &precision);
+ }
+
+ orb_check(_command_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_command), _command_sub, &_command);
+ handle_command(&_command);
+ }
+
+
+ float windspeed_norm = sqrtf(wind.windspeed_north * wind.windspeed_north + wind.windspeed_east * wind.windspeed_east);
+ float groundspeed_body = sqrtf(_global_pos.vel_n * _global_pos.vel_n + _global_pos.vel_e * _global_pos.vel_e);
+ ground_distance = _global_pos.alt - _target_position.alt;
+
+ // Distance to drop position and angle error to approach vector
+ // are relevant in all states greater than target valid (which calculates these positions)
+ if (_drop_state > DROP_STATE_TARGET_VALID) {
+ distance_real = fabsf(get_distance_to_next_waypoint(_global_pos.lat, _global_pos.lon, _drop_position.lat, _drop_position.lon));
+
+ float ground_direction = atan2f(_global_pos.vel_e, _global_pos.vel_n);
+ float approach_direction = get_bearing_to_next_waypoint(flight_vector_s.lat, flight_vector_s.lon, flight_vector_e.lat, flight_vector_e.lon);
+
+ approach_error = _wrap_pi(ground_direction - approach_direction);
+
+ if (counter % 90 == 0) {
+ mavlink_log_info(_mavlink_fd, "drop distance %u, heading error %u", (unsigned)distance_real, (unsigned)math::degrees(approach_error));
+ }
+ }
+
+ switch (_drop_state) {
+
+ case DROP_STATE_TARGET_VALID:
+ {
+
+ az = g; // acceleration in z direction[m/s^2]
+ vz = 0; // velocity in z direction [m/s]
+ z = 0; // fallen distance [m]
+ h_0 = _global_pos.alt - _target_position.alt; // height over target at start[m]
+ h = h_0; // height over target [m]
+ ax = 0; // acceleration in x direction [m/s^2]
+ vx = groundspeed_body;// XXX project // ground speed in x direction [m/s]
+ x = 0; // traveled distance in x direction [m]
+ vw = 0; // wind speed [m/s]
+ vrx = 0; // relative velocity in x direction [m/s]
+ v = groundspeed_body; // relative speed vector [m/s]
+ Fd = 0; // Drag force [N]
+ Fdx = 0; // Drag force in x direction [N]
+ Fdz = 0; // Drag force in z direction [N]
+
+
+ // Compute the distance the bottle will travel after it is dropped in body frame coordinates --> x
+ while (h > 0.05f) {
+ // z-direction
+ vz = vz + az * dt_freefall_prediction;
+ z = z + vz * dt_freefall_prediction;
+ h = h_0 - z;
+
+ // x-direction
+ vw = windspeed_norm * logf(h / z_0) / logf(ground_distance / z_0);
+ vx = vx + ax * dt_freefall_prediction;
+ x = x + vx * dt_freefall_prediction;
+ vrx = vx + vw;
+
+ // drag force
+ v = sqrtf(vz * vz + vrx * vrx);
+ Fd = 0.5f * rho * A * cd * (v * v);
+ Fdx = Fd * vrx / v;
+ Fdz = Fd * vz / v;
+
+ // acceleration
+ az = g - Fdz / m;
+ ax = -Fdx / m;
+ }
+
+ // compute drop vector
+ x = groundspeed_body * t_signal + x;
+
+ x_t = 0.0f;
+ y_t = 0.0f;
+
+ float wind_direction_n, wind_direction_e;
+
+ if (windspeed_norm < 0.5f) { // If there is no wind, an arbitrarily direction is chosen
+ wind_direction_n = 1.0f;
+ wind_direction_e = 0.0f;
+
+ } else {
+ wind_direction_n = wind.windspeed_north / windspeed_norm;
+ wind_direction_e = wind.windspeed_east / windspeed_norm;
+ }
+
+ x_drop = x_t + x * wind_direction_n;
+ y_drop = y_t + x * wind_direction_e;
+ map_projection_reproject(&ref, x_drop, y_drop, &_drop_position.lat, &_drop_position.lon);
+ _drop_position.alt = _target_position.alt + _alt_clearance;
+
+ // Compute flight vector
+ map_projection_reproject(&ref, x_drop + 2 * turn_radius * wind_direction_n, y_drop + 2 * turn_radius * wind_direction_e,
+ &(flight_vector_s.lat), &(flight_vector_s.lon));
+ flight_vector_s.altitude = _drop_position.alt;
+ map_projection_reproject(&ref, x_drop - turn_radius * wind_direction_n, y_drop - turn_radius * wind_direction_e,
+ &flight_vector_e.lat, &flight_vector_e.lon);
+ flight_vector_e.altitude = _drop_position.alt;
+
+ // Save WPs in datamanager
+ const ssize_t len = sizeof(struct mission_item_s);
+
+ if (dm_write(DM_KEY_WAYPOINTS_ONBOARD, 0, DM_PERSIST_IN_FLIGHT_RESET, &flight_vector_s, len) != len) {
+ warnx("ERROR: could not save onboard WP");
+ }
+
+ if (dm_write(DM_KEY_WAYPOINTS_ONBOARD, 1, DM_PERSIST_IN_FLIGHT_RESET, &flight_vector_e, len) != len) {
+ warnx("ERROR: could not save onboard WP");
+ }
+
+ _onboard_mission.count = 2;
+ _onboard_mission.current_seq = 0;
+
+ if (_onboard_mission_pub > 0) {
+ orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
+
+ } else {
+ _onboard_mission_pub = orb_advertise(ORB_ID(onboard_mission), &_onboard_mission);
+ }
+
+ float approach_direction = get_bearing_to_next_waypoint(flight_vector_s.lat, flight_vector_s.lon, flight_vector_e.lat, flight_vector_e.lon);
+ mavlink_log_critical(_mavlink_fd, "position set, approach heading: %u", (unsigned)distance_real, (unsigned)math::degrees(approach_direction + M_PI_F));
+
+ _drop_state = DROP_STATE_TARGET_SET;
+ }
+ break;
+
+ case DROP_STATE_TARGET_SET:
+ {
+ float distance_wp2 = get_distance_to_next_waypoint(_global_pos.lat, _global_pos.lon, flight_vector_e.lat, flight_vector_e.lon);
+
+ if (distance_wp2 < distance_real) {
+ _onboard_mission.current_seq = 0;
+ orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
+ } else {
+
+ // We're close enough - open the bay
+ distance_open_door = math::max(10.0f, 3.0f * fabsf(t_door * groundspeed_body));
+
+ if (isfinite(distance_real) && distance_real < distance_open_door &&
+ fabsf(approach_error) < math::radians(20.0f)) {
+ open_bay();
+ _drop_state = DROP_STATE_BAY_OPEN;
+ mavlink_log_info(_mavlink_fd, "#audio: opening bay");
+ }
+ }
+ }
+ break;
+
+ case DROP_STATE_BAY_OPEN:
+ {
+ if (_drop_approval) {
+ map_projection_project(&ref, _global_pos.lat, _global_pos.lon, &x_l, &y_l);
+ x_f = x_l + _global_pos.vel_n * dt_runs;
+ y_f = y_l + _global_pos.vel_e * dt_runs;
+ map_projection_reproject(&ref, x_f, y_f, &x_f_NED, &y_f_NED);
+ future_distance = get_distance_to_next_waypoint(x_f_NED, y_f_NED, _drop_position.lat, _drop_position.lon);
+
+ if (isfinite(distance_real) &&
+ (distance_real < precision) && ((distance_real < future_distance))) {
+ drop();
+ _drop_state = DROP_STATE_DROPPED;
+ mavlink_log_info(_mavlink_fd, "#audio: payload dropped");
+ } else {
+
+ float distance_wp2 = get_distance_to_next_waypoint(_global_pos.lat, _global_pos.lon, flight_vector_e.lat, flight_vector_e.lon);
+
+ if (distance_wp2 < distance_real) {
+ _onboard_mission.current_seq = 0;
+ orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
+ }
+ }
+ }
+ }
+ break;
+
+ case DROP_STATE_DROPPED:
+ /* 2s after drop, reset and close everything again */
+ if ((hrt_elapsed_time(&_doors_opened) > 2 * 1000 * 1000)) {
+ _drop_state = DROP_STATE_INIT;
+ _drop_approval = false;
+ lock_release();
+ close_bay();
+ mavlink_log_info(_mavlink_fd, "#audio: closing bay");
+
+ // remove onboard mission
+ _onboard_mission.current_seq = -1;
+ _onboard_mission.count = 0;
+ orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
+ }
+ break;
+ }
+
+ counter++;
+
+ // update_actuators();
+
+ // run at roughly 100 Hz
+ usleep(sleeptime_us);
+
+ dt_runs = hrt_elapsed_time(&last_run) / 1e6f;
+ last_run = hrt_absolute_time();
+ }
+ }
+
+ warnx("exiting.");
+
+ _main_task = -1;
+ _exit(0);
+}
+
+void
+BottleDrop::handle_command(struct vehicle_command_s *cmd)
+{
+ switch (cmd->command) {
+ case VEHICLE_CMD_CUSTOM_0:
+ /*
+ * param1 and param2 set to 1: open and drop
+ * param1 set to 1: open
+ * else: close (and don't drop)
+ */
+ if (cmd->param1 > 0.5f && cmd->param2 > 0.5f) {
+ open_bay();
+ drop();
+ mavlink_log_info(_mavlink_fd, "#audio: drop bottle");
+
+ } else if (cmd->param1 > 0.5f) {
+ open_bay();
+ mavlink_log_info(_mavlink_fd, "#audio: opening bay");
+
+ } else {
+ lock_release();
+ close_bay();
+ mavlink_log_info(_mavlink_fd, "#audio: closing bay");
+ }
+
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ break;
+
+ case VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY:
+
+ switch ((int)(cmd->param1 + 0.5f)) {
+ case 0:
+ _drop_approval = false;
+ mavlink_log_info(_mavlink_fd, "#audio: got drop position, no approval");
+ break;
+
+ case 1:
+ _drop_approval = true;
+ mavlink_log_info(_mavlink_fd, "#audio: got drop position and approval");
+ break;
+
+ default:
+ _drop_approval = false;
+ warnx("param1 val unknown");
+ break;
+ }
+
+ // XXX check all fields (2-3)
+ _alt_clearance = cmd->param4;
+ _target_position.lat = cmd->param5;
+ _target_position.lon = cmd->param6;
+ _target_position.alt = cmd->param7;
+ _drop_state = DROP_STATE_TARGET_VALID;
+ mavlink_log_info(_mavlink_fd, "got target: %8.4f, %8.4f, %8.4f", (double)_target_position.lat,
+ (double)_target_position.lon, (double)_target_position.alt);
+ map_projection_init(&ref, _target_position.lat, _target_position.lon);
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ break;
+
+ case VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY:
+
+ if (cmd->param1 < 0) {
+
+ // Clear internal states
+ _drop_approval = false;
+ _drop_state = DROP_STATE_INIT;
+
+ // Abort if mission is present
+ _onboard_mission.current_seq = -1;
+
+ if (_onboard_mission_pub > 0) {
+ orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
+ }
+
+ } else {
+ switch ((int)(cmd->param1 + 0.5f)) {
+ case 0:
+ _drop_approval = false;
+ break;
+
+ case 1:
+ _drop_approval = true;
+ mavlink_log_info(_mavlink_fd, "#audio: got drop approval");
+ break;
+
+ default:
+ _drop_approval = false;
+ break;
+ // XXX handle other values
+ }
+ }
+
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ break;
+
+ default:
+ break;
+ }
+}
+
+void
+BottleDrop::answer_command(struct vehicle_command_s *cmd, enum VEHICLE_CMD_RESULT result)
+{
+ switch (result) {
+ case VEHICLE_CMD_RESULT_ACCEPTED:
+ break;
+
+ case VEHICLE_CMD_RESULT_DENIED:
+ mavlink_log_critical(_mavlink_fd, "#audio: command denied: %u", cmd->command);
+ break;
+
+ case VEHICLE_CMD_RESULT_FAILED:
+ mavlink_log_critical(_mavlink_fd, "#audio: command failed: %u", cmd->command);
+ break;
+
+ case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
+ mavlink_log_critical(_mavlink_fd, "#audio: command temporarily rejected: %u", cmd->command);
+ break;
+
+ case VEHICLE_CMD_RESULT_UNSUPPORTED:
+ mavlink_log_critical(_mavlink_fd, "#audio: command unsupported: %u", cmd->command);
+ break;
+
+ default:
+ break;
+ }
+}
+
+void
+BottleDrop::task_main_trampoline(int argc, char *argv[])
+{
+ bottle_drop::g_bottle_drop->task_main();
+}
+
+static void usage()
+{
+ errx(1, "usage: bottle_drop {start|stop|status}");
+}
+
+int bottle_drop_main(int argc, char *argv[])
+{
+ if (argc < 2) {
+ usage();
+ }
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (bottle_drop::g_bottle_drop != nullptr) {
+ errx(1, "already running");
+ }
+
+ bottle_drop::g_bottle_drop = new BottleDrop;
+
+ if (bottle_drop::g_bottle_drop == nullptr) {
+ errx(1, "alloc failed");
+ }
+
+ if (OK != bottle_drop::g_bottle_drop->start()) {
+ delete bottle_drop::g_bottle_drop;
+ bottle_drop::g_bottle_drop = nullptr;
+ err(1, "start failed");
+ }
+
+ return 0;
+ }
+
+ if (bottle_drop::g_bottle_drop == nullptr) {
+ errx(1, "not running");
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ delete bottle_drop::g_bottle_drop;
+ bottle_drop::g_bottle_drop = nullptr;
+
+ } else if (!strcmp(argv[1], "status")) {
+ bottle_drop::g_bottle_drop->status();
+
+ } else if (!strcmp(argv[1], "drop")) {
+ bottle_drop::g_bottle_drop->drop();
+
+ } else if (!strcmp(argv[1], "open")) {
+ bottle_drop::g_bottle_drop->open_bay();
+
+ } else if (!strcmp(argv[1], "close")) {
+ bottle_drop::g_bottle_drop->close_bay();
+
+ } else if (!strcmp(argv[1], "lock")) {
+ bottle_drop::g_bottle_drop->lock_release();
+
+ } else {
+ usage();
+ }
+
+ return 0;
+}
diff --git a/src/modules/bottle_drop/bottle_drop_params.c b/src/modules/bottle_drop/bottle_drop_params.c
new file mode 100644
index 000000000..51ebfb9a1
--- /dev/null
+++ b/src/modules/bottle_drop/bottle_drop_params.c
@@ -0,0 +1,131 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file bottle_drop_params.c
+ * Bottle drop parameters
+ *
+ * @author Dominik Juchli <juchlid@ethz.ch>
+ */
+
+#include <nuttx/config.h>
+#include <systemlib/param/param.h>
+
+/**
+ * Ground drag property
+ *
+ * This parameter encodes the ground drag coefficient and the corresponding
+ * decrease in wind speed from the plane altitude to ground altitude.
+ *
+ * @unit unknown
+ * @min 0.001
+ * @max 0.1
+ * @group Payload drop
+ */
+PARAM_DEFINE_FLOAT(BD_GPROPERTIES, 0.03f);
+
+/**
+ * Plane turn radius
+ *
+ * The planes known minimal turn radius - use a higher value
+ * to make the plane maneuver more distant from the actual drop
+ * position. This is to ensure the wings are level during the drop.
+ *
+ * @unit meter
+ * @min 30.0
+ * @max 500.0
+ * @group Payload drop
+ */
+PARAM_DEFINE_FLOAT(BD_TURNRADIUS, 120.0f);
+
+/**
+ * Drop precision
+ *
+ * If the system is closer than this distance on passing over the
+ * drop position, it will release the payload. This is a safeguard
+ * to prevent a drop out of the required accuracy.
+ *
+ * @unit meter
+ * @min 1.0
+ * @max 80.0
+ * @group Payload drop
+ */
+PARAM_DEFINE_FLOAT(BD_PRECISION, 30.0f);
+
+/**
+ * Payload drag coefficient of the dropped object
+ *
+ * The drag coefficient (cd) is the typical drag
+ * constant for air. It is in general object specific,
+ * but the closest primitive shape to the actual object
+ * should give good results:
+ * http://en.wikipedia.org/wiki/Drag_coefficient
+ *
+ * @unit meter
+ * @min 0.08
+ * @max 1.5
+ * @group Payload drop
+ */
+PARAM_DEFINE_FLOAT(BD_OBJ_CD, 0.1f);
+
+/**
+ * Payload mass
+ *
+ * A typical small toy ball:
+ * 0.025 kg
+ *
+ * OBC water bottle:
+ * 0.6 kg
+ *
+ * @unit kilogram
+ * @min 0.001
+ * @max 5.0
+ * @group Payload drop
+ */
+PARAM_DEFINE_FLOAT(BD_OBJ_MASS, 0.6f);
+
+/**
+ * Payload front surface area
+ *
+ * A typical small toy ball:
+ * (0.045 * 0.045) / 4.0 * pi = 0.001590 m^2
+ *
+ * OBC water bottle:
+ * (0.063 * 0.063) / 4.0 * pi = 0.003117 m^2
+ *
+ * @unit m^2
+ * @min 0.001
+ * @max 0.5
+ * @group Payload drop
+ */
+PARAM_DEFINE_FLOAT(BD_OBJ_SURFACE, 0.00311724531f);
diff --git a/src/modules/bottle_drop/module.mk b/src/modules/bottle_drop/module.mk
new file mode 100644
index 000000000..6b18fff55
--- /dev/null
+++ b/src/modules/bottle_drop/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Daemon application
+#
+
+MODULE_COMMAND = bottle_drop
+
+SRCS = bottle_drop.cpp \
+ bottle_drop_params.c
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index 7a4e7a766..0cb41489f 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -83,7 +83,7 @@
* | accel_T[1][i] |
* [ accel_T[2][i] ]
*
- * b = [ accel_corr_ref[0][i] ] // One measurement per axis is enough
+ * b = [ accel_corr_ref[0][i] ] // One measurement per side is enough
* | accel_corr_ref[2][i] |
* [ accel_corr_ref[4][i] ]
*
@@ -162,6 +162,11 @@ int do_accel_calibration(int mavlink_fd)
mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
+ mavlink_log_info(mavlink_fd, "You need to put the system on all six sides");
+ sleep(3);
+ mavlink_log_info(mavlink_fd, "Follow the instructions on the screen");
+ sleep(5);
+
struct accel_scale accel_scale = {
0.0f,
1.0f,
@@ -258,7 +263,7 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
const int samples_num = 2500;
float accel_ref[6][3];
bool data_collected[6] = { false, false, false, false, false, false };
- const char *orientation_strs[6] = { "x+", "x-", "y+", "y-", "z+", "z-" };
+ const char *orientation_strs[6] = { "front", "back", "left", "right", "top", "bottom" };
int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
@@ -287,29 +292,37 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
break;
}
- mavlink_log_info(mavlink_fd, "directions left: %s%s%s%s%s%s",
- (!data_collected[0]) ? "x+ " : "",
- (!data_collected[1]) ? "x- " : "",
- (!data_collected[2]) ? "y+ " : "",
- (!data_collected[3]) ? "y- " : "",
- (!data_collected[4]) ? "z+ " : "",
- (!data_collected[5]) ? "z- " : "");
+ /* inform user which axes are still needed */
+ mavlink_log_info(mavlink_fd, "pending: %s%s%s%s%s%s",
+ (!data_collected[0]) ? "front " : "",
+ (!data_collected[1]) ? "back " : "",
+ (!data_collected[2]) ? "left " : "",
+ (!data_collected[3]) ? "right " : "",
+ (!data_collected[4]) ? "up " : "",
+ (!data_collected[5]) ? "down " : "");
+
+ /* allow user enough time to read the message */
+ sleep(3);
int orient = detect_orientation(mavlink_fd, sensor_combined_sub);
if (orient < 0) {
- res = ERROR;
- break;
+ mavlink_log_info(mavlink_fd, "invalid motion, hold still...");
+ sleep(3);
+ continue;
}
+ /* inform user about already handled side */
if (data_collected[orient]) {
- mavlink_log_info(mavlink_fd, "%s done, rotate to a different axis", orientation_strs[orient]);
+ mavlink_log_info(mavlink_fd, "%s side done, rotate to a different side", orientation_strs[orient]);
+ sleep(4);
continue;
}
- mavlink_log_info(mavlink_fd, "accel measurement started: %s axis", orientation_strs[orient]);
+ mavlink_log_info(mavlink_fd, "Hold still, starting to measure %s side", orientation_strs[orient]);
+ sleep(1);
read_accelerometer_avg(sensor_combined_sub, &(accel_ref[orient][0]), samples_num);
- mavlink_log_info(mavlink_fd, "result for %s axis: [ %.2f %.2f %.2f ]", orientation_strs[orient],
+ mavlink_log_info(mavlink_fd, "result for %s side: [ %.2f %.2f %.2f ]", orientation_strs[orient],
(double)accel_ref[orient][0],
(double)accel_ref[orient][1],
(double)accel_ref[orient][2]);
@@ -400,7 +413,7 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
/* is still now */
if (t_still == 0) {
/* first time */
- mavlink_log_info(mavlink_fd, "detected rest position, waiting...");
+ mavlink_log_info(mavlink_fd, "detected rest position, hold still...");
t_still = t;
t_timeout = t + timeout;
@@ -418,6 +431,7 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
/* not still, reset still start time */
if (t_still != 0) {
mavlink_log_info(mavlink_fd, "detected motion, hold still...");
+ sleep(3);
t_still = 0;
}
}
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
index 0e58c68b6..cae1d7684 100644
--- a/src/modules/commander/airspeed_calibration.cpp
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -61,6 +61,15 @@ static const int ERROR = -1;
static const char *sensor_name = "dpress";
+#define HUMAN_ASPD_CAL_FAILED_MSG "Calibration failed, see http://px4.io/help/aspd"
+
+static void feedback_calibration_failed(int mavlink_fd)
+{
+ sleep(5);
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ mavlink_log_critical(mavlink_fd, HUMAN_ASPD_CAL_FAILED_MSG);
+}
+
int do_airspeed_calibration(int mavlink_fd)
{
/* give directions */
@@ -99,7 +108,7 @@ int do_airspeed_calibration(int mavlink_fd)
float analog_scaling = 0.0f;
param_get(param_find("SENS_DPRES_ANSC"), &(analog_scaling));
if (fabsf(analog_scaling) < 0.1f) {
- mavlink_log_critical(mavlink_fd, "If analog sens, retry with [SENS_DPRES_ANSC=1000]");
+ mavlink_log_critical(mavlink_fd, "No airspeed sensor, see http://px4.io/help/aspd");
close(diff_pres_sub);
return ERROR;
}
@@ -138,7 +147,7 @@ int do_airspeed_calibration(int mavlink_fd)
} else if (poll_ret == 0) {
/* any poll failure for 1s is a reason to abort */
- mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ feedback_calibration_failed(mavlink_fd);
close(diff_pres_sub);
return ERROR;
}
@@ -175,16 +184,18 @@ int do_airspeed_calibration(int mavlink_fd)
}
} else {
- mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ feedback_calibration_failed(mavlink_fd);
close(diff_pres_sub);
return ERROR;
}
- mavlink_log_critical(mavlink_fd, "Offset of %d Pa, create airflow now!", (int)diff_pres_offset);
+ mavlink_log_critical(mavlink_fd, "Offset of %d Pascal", (int)diff_pres_offset);
/* wait 500 ms to ensure parameter propagated through the system */
usleep(500 * 1000);
+ mavlink_log_critical(mavlink_fd, "Create airflow now");
+
calibration_counter = 0;
const unsigned maxcount = 3000;
@@ -204,18 +215,18 @@ int do_airspeed_calibration(int mavlink_fd)
calibration_counter++;
if (fabsf(diff_pres.differential_pressure_raw_pa) < 50.0f) {
- if (calibration_counter % 100 == 0) {
- mavlink_log_critical(mavlink_fd, "Missing airflow! (%d, wanted: 50 Pa, #h101)",
- (int)diff_pres.differential_pressure_raw_pa);
+ if (calibration_counter % 500 == 0) {
+ mavlink_log_info(mavlink_fd, "Create air pressure! (got %d, wanted: 50 Pa)",
+ (int)diff_pres.differential_pressure_raw_pa);
}
continue;
}
/* do not allow negative values */
if (diff_pres.differential_pressure_raw_pa < 0.0f) {
- mavlink_log_info(mavlink_fd, "negative pressure: ERROR (%d Pa)",
- (int)diff_pres.differential_pressure_raw_pa);
- mavlink_log_critical(mavlink_fd, "%d Pa: swap static and dynamic ports!", (int)diff_pres.differential_pressure_raw_pa);
+ mavlink_log_info(mavlink_fd, "ERROR: Negative pressure difference detected! (%d Pa)",
+ (int)diff_pres.differential_pressure_raw_pa);
+ mavlink_log_critical(mavlink_fd, "Swap static and dynamic ports!");
close(diff_pres_sub);
/* the user setup is wrong, wipe the calibration to force a proper re-calibration */
@@ -233,24 +244,24 @@ int do_airspeed_calibration(int mavlink_fd)
close(diff_pres_sub);
- mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ feedback_calibration_failed(mavlink_fd);
return ERROR;
} else {
- mavlink_log_info(mavlink_fd, "positive pressure: OK (%d Pa)",
+ mavlink_log_info(mavlink_fd, "Positive pressure: OK (%d Pa)",
(int)diff_pres.differential_pressure_raw_pa);
break;
}
} else if (poll_ret == 0) {
/* any poll failure for 1s is a reason to abort */
- mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ feedback_calibration_failed(mavlink_fd);
close(diff_pres_sub);
return ERROR;
}
}
if (calibration_counter == maxcount) {
- mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ feedback_calibration_failed(mavlink_fd);
close(diff_pres_sub);
return ERROR;
}
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 2b528eef6..46caddd46 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -59,6 +59,7 @@
#include <string.h>
#include <math.h>
#include <poll.h>
+#include <float.h>
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
@@ -92,6 +93,7 @@
#include <systemlib/err.h>
#include <systemlib/cpuload.h>
#include <systemlib/rc_check.h>
+#include <geo/geo.h>
#include <systemlib/state_table.h>
#include <dataman/dataman.h>
@@ -126,8 +128,6 @@ extern struct system_load_s system_load;
#define POSITION_TIMEOUT (2 * 1000 * 1000) /**< consider the local or global position estimate invalid after 600ms */
#define FAILSAFE_DEFAULT_TIMEOUT (3 * 1000 * 1000) /**< hysteresis time - the failsafe will trigger after 3 seconds in this state */
-#define RC_TIMEOUT 500000
-#define DL_TIMEOUT 5 * 1000* 1000
#define OFFBOARD_TIMEOUT 500000
#define DIFFPRESS_TIMEOUT 2000000
@@ -207,7 +207,9 @@ void usage(const char *reason);
/**
* React to commands that are sent e.g. from the mavlink module.
*/
-bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd, struct actuator_armed_s *armed, struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub);
+bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd,
+ struct actuator_armed_s *armed, struct home_position_s *home, struct vehicle_global_position_s *global_pos,
+ orb_advert_t *home_pub);
/**
* Mainloop of commander.
@@ -230,7 +232,8 @@ void print_reject_arm(const char *msg);
void print_status();
-transition_result_t check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos);
+transition_result_t check_navigation_state_machine(struct vehicle_status_s *status,
+ struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos);
transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy);
@@ -260,7 +263,7 @@ int commander_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("commander",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
- 2950,
+ 3200,
commander_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
@@ -393,7 +396,8 @@ transition_result_t arm_disarm(bool arm, const int mavlink_fd_local, const char
// Transition the armed state. By passing mavlink_fd to arming_state_transition it will
// output appropriate error messages if the state cannot transition.
- arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd_local);
+ arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed,
+ true /* fRunPreArmChecks */, mavlink_fd_local);
if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
mavlink_log_info(mavlink_fd_local, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
@@ -406,11 +410,12 @@ transition_result_t arm_disarm(bool arm, const int mavlink_fd_local, const char
}
bool handle_command(struct vehicle_status_s *status_local, const struct safety_s *safety_local,
- struct vehicle_command_s *cmd, struct actuator_armed_s *armed_local,
- struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub)
+ struct vehicle_command_s *cmd, struct actuator_armed_s *armed_local,
+ struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub)
{
/* only handle commands that are meant to be handled by this system and component */
- if (cmd->target_system != status_local->system_id || ((cmd->target_component != status_local->component_id) && (cmd->target_component != 0))) { // component_id 0: valid for all components
+ if (cmd->target_system != status_local->system_id || ((cmd->target_component != status_local->component_id)
+ && (cmd->target_component != 0))) { // component_id 0: valid for all components
return false;
}
@@ -537,13 +542,13 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
} else {
mavlink_log_critical(mavlink_fd, "REJ CMD: %.1f %.1f %.1f %.1f %.1f %.1f %.1f %.1f",
- (double)cmd->param1,
- (double)cmd->param2,
- (double)cmd->param3,
- (double)cmd->param4,
- (double)cmd->param5,
- (double)cmd->param6,
- (double)cmd->param7);
+ (double)cmd->param1,
+ (double)cmd->param2,
+ (double)cmd->param3,
+ (double)cmd->param4,
+ (double)cmd->param5,
+ (double)cmd->param6,
+ (double)cmd->param7);
}
}
break;
@@ -553,11 +558,44 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
if (cmd->param1 > 0.5f) {
//XXX update state machine?
armed_local->force_failsafe = true;
- warnx("forcing failsafe");
+ warnx("forcing failsafe (termination)");
+
} else {
armed_local->force_failsafe = false;
- warnx("disabling failsafe");
+ warnx("disabling failsafe (termination)");
+ }
+
+ /* param2 is currently used for other failsafe modes */
+ status_local->engine_failure_cmd = false;
+ status_local->data_link_lost_cmd = false;
+ status_local->gps_failure_cmd = false;
+ status_local->rc_signal_lost_cmd = false;
+
+ if ((int)cmd->param2 <= 0) {
+ /* reset all commanded failure modes */
+ warnx("reset all non-flighttermination failsafe commands");
+
+ } else if ((int)cmd->param2 == 1) {
+ /* trigger engine failure mode */
+ status_local->engine_failure_cmd = true;
+ warnx("engine failure mode commanded");
+
+ } else if ((int)cmd->param2 == 2) {
+ /* trigger data link loss mode */
+ status_local->data_link_lost_cmd = true;
+ warnx("data link loss mode commanded");
+
+ } else if ((int)cmd->param2 == 3) {
+ /* trigger gps loss mode */
+ status_local->gps_failure_cmd = true;
+ warnx("gps loss mode commanded");
+
+ } else if ((int)cmd->param2 == 4) {
+ /* trigger rc loss mode */
+ status_local->rc_signal_lost_cmd = true;
+ warnx("rc loss mode commanded");
}
+
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
}
break;
@@ -609,10 +647,44 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
}
break;
+ case VEHICLE_CMD_NAV_GUIDED_ENABLE: {
+ transition_result_t res = TRANSITION_DENIED;
+ static main_state_t main_state_pre_offboard = MAIN_STATE_MANUAL;
+
+ if (status_local->main_state != MAIN_STATE_OFFBOARD) {
+ main_state_pre_offboard = status_local->main_state;
+ }
+
+ if (cmd->param1 > 0.5f) {
+ res = main_state_transition(status_local, MAIN_STATE_OFFBOARD);
+
+ if (res == TRANSITION_DENIED) {
+ print_reject_mode(status_local, "OFFBOARD");
+ status_local->offboard_control_set_by_command = false;
+
+ } else {
+ /* Set flag that offboard was set via command, main state is not overridden by rc */
+ status_local->offboard_control_set_by_command = true;
+ }
+
+ } else {
+ /* If the mavlink command is used to enable or disable offboard control:
+ * switch back to previous mode when disabling */
+ res = main_state_transition(status_local, main_state_pre_offboard);
+ status_local->offboard_control_set_by_command = false;
+ }
+ }
+ break;
+
case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
case VEHICLE_CMD_PREFLIGHT_STORAGE:
+ case VEHICLE_CMD_CUSTOM_0:
+ case VEHICLE_CMD_CUSTOM_1:
+ case VEHICLE_CMD_CUSTOM_2:
+ case VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY:
+ case VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY:
/* ignore commands that handled in low prio loop */
break;
@@ -652,6 +724,12 @@ int commander_thread_main(int argc, char *argv[])
param_t _param_takeoff_alt = param_find("NAV_TAKEOFF_ALT");
param_t _param_enable_parachute = param_find("NAV_PARACHUTE_EN");
param_t _param_enable_datalink_loss = param_find("COM_DL_LOSS_EN");
+ param_t _param_datalink_loss_timeout = param_find("COM_DL_LOSS_T");
+ param_t _param_rc_loss_timeout = param_find("COM_RC_LOSS_T");
+ param_t _param_datalink_regain_timeout = param_find("COM_DL_REG_T");
+ param_t _param_ef_throttle_thres = param_find("COM_EF_THROT");
+ param_t _param_ef_current2throttle_thres = param_find("COM_EF_C2T");
+ param_t _param_ef_time_thres = param_find("COM_EF_TIME");
/* welcome user */
warnx("starting");
@@ -739,9 +817,12 @@ int commander_thread_main(int argc, char *argv[])
// CIRCUIT BREAKERS
status.circuit_breaker_engaged_power_check = false;
status.circuit_breaker_engaged_airspd_check = false;
+ status.circuit_breaker_engaged_enginefailure_check = false;
+ status.circuit_breaker_engaged_gpsfailure_check = false;
/* publish initial state */
status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
+
if (status_pub < 0) {
warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
warnx("exiting.");
@@ -767,11 +848,14 @@ int commander_thread_main(int argc, char *argv[])
/* init mission state, do it here to allow navigator to use stored mission even if mavlink failed to start */
orb_advert_t mission_pub = -1;
mission_s mission;
+
if (dm_read(DM_KEY_MISSION_STATE, 0, &mission, sizeof(mission_s)) == sizeof(mission_s)) {
if (mission.dataman_id >= 0 && mission.dataman_id <= 1) {
- warnx("loaded mission state: dataman_id=%d, count=%u, current=%d", mission.dataman_id, mission.count, mission.current_seq);
+ warnx("loaded mission state: dataman_id=%d, count=%u, current=%d", mission.dataman_id, mission.count,
+ mission.current_seq);
mavlink_log_info(mavlink_fd, "[cmd] dataman_id=%d, count=%u, current=%d",
- mission.dataman_id, mission.count, mission.current_seq);
+ mission.dataman_id, mission.count, mission.current_seq);
+
} else {
const char *missionfail = "reading mission state failed";
warnx("%s", missionfail);
@@ -844,11 +928,13 @@ int commander_thread_main(int argc, char *argv[])
/* Subscribe to telemetry status topics */
int telemetry_subs[TELEMETRY_STATUS_ORB_ID_NUM];
uint64_t telemetry_last_heartbeat[TELEMETRY_STATUS_ORB_ID_NUM];
+ uint64_t telemetry_last_dl_loss[TELEMETRY_STATUS_ORB_ID_NUM];
bool telemetry_lost[TELEMETRY_STATUS_ORB_ID_NUM];
for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]);
telemetry_last_heartbeat[i] = 0;
+ telemetry_last_dl_loss[i] = 0;
telemetry_lost[i] = true;
}
@@ -875,6 +961,8 @@ int commander_thread_main(int argc, char *argv[])
int gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
struct vehicle_gps_position_s gps_position;
memset(&gps_position, 0, sizeof(gps_position));
+ gps_position.eph = FLT_MAX;
+ gps_position.epv = FLT_MAX;
/* Subscribe to sensor topic */
int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
@@ -932,6 +1020,15 @@ int commander_thread_main(int argc, char *argv[])
transition_result_t arming_ret;
int32_t datalink_loss_enabled = false;
+ int32_t datalink_loss_timeout = 10;
+ float rc_loss_timeout = 0.5;
+ int32_t datalink_regain_timeout = 0;
+
+ /* Thresholds for engine failure detection */
+ int32_t ef_throttle_thres = 1.0f;
+ int32_t ef_current2throttle_thres = 0.0f;
+ int32_t ef_time_thres = 1000.0f;
+ uint64_t timestamp_engine_healthy = 0; /**< absolute time when engine was healty */
/* check which state machines for changes, clear "changed" flag */
bool arming_state_changed = false;
@@ -979,8 +1076,14 @@ int commander_thread_main(int argc, char *argv[])
param_get(_param_system_id, &(status.system_id));
param_get(_param_component_id, &(status.component_id));
- status.circuit_breaker_engaged_power_check = circuit_breaker_enabled("CBRK_SUPPLY_CHK", CBRK_SUPPLY_CHK_KEY);
- status.circuit_breaker_engaged_airspd_check = circuit_breaker_enabled("CBRK_AIRSPD_CHK", CBRK_AIRSPD_CHK_KEY);
+ status.circuit_breaker_engaged_power_check =
+ circuit_breaker_enabled("CBRK_SUPPLY_CHK", CBRK_SUPPLY_CHK_KEY);
+ status.circuit_breaker_engaged_airspd_check =
+ circuit_breaker_enabled("CBRK_AIRSPD_CHK", CBRK_AIRSPD_CHK_KEY);
+ status.circuit_breaker_engaged_enginefailure_check =
+ circuit_breaker_enabled("CBRK_ENGINEFAIL", CBRK_ENGINEFAIL_KEY);
+ status.circuit_breaker_engaged_gpsfailure_check =
+ circuit_breaker_enabled("CBRK_GPSFAIL", CBRK_GPSFAIL_KEY);
status_changed = true;
@@ -992,6 +1095,12 @@ int commander_thread_main(int argc, char *argv[])
param_get(_param_takeoff_alt, &takeoff_alt);
param_get(_param_enable_parachute, &parachute_enabled);
param_get(_param_enable_datalink_loss, &datalink_loss_enabled);
+ param_get(_param_datalink_loss_timeout, &datalink_loss_timeout);
+ param_get(_param_rc_loss_timeout, &rc_loss_timeout);
+ param_get(_param_datalink_regain_timeout, &datalink_regain_timeout);
+ param_get(_param_ef_throttle_thres, &ef_throttle_thres);
+ param_get(_param_ef_current2throttle_thres, &ef_current2throttle_thres);
+ param_get(_param_ef_time_thres, &ef_time_thres);
}
orb_check(sp_man_sub, &updated);
@@ -1012,6 +1121,7 @@ int commander_thread_main(int argc, char *argv[])
status.offboard_control_signal_lost = false;
status_changed = true;
}
+
} else {
if (!status.offboard_control_signal_lost) {
status.offboard_control_signal_lost = true;
@@ -1030,9 +1140,9 @@ int commander_thread_main(int argc, char *argv[])
/* perform system checks when new telemetry link connected */
if (mavlink_fd &&
- telemetry_last_heartbeat[i] == 0 &&
- telemetry.heartbeat_time > 0 &&
- hrt_elapsed_time(&telemetry.heartbeat_time) < DL_TIMEOUT) {
+ telemetry_last_heartbeat[i] == 0 &&
+ telemetry.heartbeat_time > 0 &&
+ hrt_elapsed_time(&telemetry.heartbeat_time) < datalink_loss_timeout * 1e6) {
(void)rc_calibration_check(mavlink_fd);
}
@@ -1045,6 +1155,27 @@ int commander_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors);
+
+ /* Check if the barometer is healthy and issue a warning in the GCS if not so.
+ * Because the barometer is used for calculating AMSL altitude which is used to ensure
+ * vertical separation from other airtraffic the operator has to know when the
+ * barometer is inoperational.
+ * */
+ if (hrt_elapsed_time(&sensors.baro_timestamp) < FAILSAFE_DEFAULT_TIMEOUT) {
+ /* handle the case where baro was regained */
+ if (status.barometer_failure) {
+ status.barometer_failure = false;
+ status_changed = true;
+ mavlink_log_critical(mavlink_fd, "baro healthy");
+ }
+
+ } else {
+ if (!status.barometer_failure) {
+ status.barometer_failure = true;
+ status_changed = true;
+ mavlink_log_critical(mavlink_fd, "baro failed");
+ }
+ }
}
orb_check(diff_pres_sub, &updated);
@@ -1060,10 +1191,11 @@ int commander_thread_main(int argc, char *argv[])
if (hrt_elapsed_time(&system_power.timestamp) < 200000) {
if (system_power.servo_valid &&
- !system_power.brick_valid &&
- !system_power.usb_connected) {
+ !system_power.brick_valid &&
+ !system_power.usb_connected) {
/* flying only on servo rail, this is unsafe */
status.condition_power_input_valid = false;
+
} else {
status.condition_power_input_valid = true;
}
@@ -1083,9 +1215,11 @@ int commander_thread_main(int argc, char *argv[])
/* disarm if safety is now on and still armed */
if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) {
- arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
+ arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY :
+ ARMING_STATE_STANDBY_ERROR);
- if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd)) {
+ if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed,
+ true /* fRunPreArmChecks */, mavlink_fd)) {
mavlink_log_info(mavlink_fd, "DISARMED by safety switch");
arming_state_changed = true;
}
@@ -1129,9 +1263,8 @@ int commander_thread_main(int argc, char *argv[])
}
}
- check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_good, &(status.condition_global_position_valid), &status_changed);
-
- /* check if GPS fix is ok */
+ check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_good, &(status.condition_global_position_valid),
+ &status_changed);
/* update home position */
if (!status.condition_home_position_valid && status.condition_global_position_valid && !armed.armed &&
@@ -1181,8 +1314,11 @@ int commander_thread_main(int argc, char *argv[])
local_eph_good = false;
}
}
- check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && local_eph_good, &(status.condition_local_position_valid), &status_changed);
- check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed);
+
+ check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid
+ && local_eph_good, &(status.condition_local_position_valid), &status_changed);
+ check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid,
+ &(status.condition_local_altitude_valid), &status_changed);
if (status.condition_local_altitude_valid) {
if (status.condition_landed != local_position.landed) {
@@ -1213,7 +1349,8 @@ int commander_thread_main(int argc, char *argv[])
/* get throttle (if armed), as we only care about energy negative throttle also counts */
float throttle = (armed.armed) ? fabsf(actuator_controls.control[3]) : 0.0f;
- status.battery_remaining = battery_remaining_estimate_voltage(battery.voltage_filtered_v, battery.discharged_mah, throttle);
+ status.battery_remaining = battery_remaining_estimate_voltage(battery.voltage_filtered_v, battery.discharged_mah,
+ throttle);
}
}
@@ -1270,8 +1407,8 @@ int commander_thread_main(int argc, char *argv[])
last_idle_time = system_load.tasks[0].total_runtime;
/* check if board is connected via USB */
- //struct stat statbuf;
- //on_usb_power = (stat("/dev/ttyACM0", &statbuf) == 0);
+ struct stat statbuf;
+ on_usb_power = (stat("/dev/ttyACM0", &statbuf) == 0);
}
/* if battery voltage is getting lower, warn using buzzer, etc. */
@@ -1281,26 +1418,30 @@ int commander_thread_main(int argc, char *argv[])
status.battery_warning = VEHICLE_BATTERY_WARNING_LOW;
status_changed = true;
- } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.09f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) {
+ } else if (!on_usb_power && status.condition_battery_voltage_valid && status.battery_remaining < 0.09f
+ && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) {
/* critical battery voltage, this is rather an emergency, change state machine */
critical_battery_voltage_actions_done = true;
mavlink_log_emergency(mavlink_fd, "CRITICAL BATTERY, LAND IMMEDIATELY");
status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL;
if (armed.armed) {
- arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed, mavlink_fd);
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed, true /* fRunPreArmChecks */,
+ mavlink_fd);
if (arming_ret == TRANSITION_CHANGED) {
arming_state_changed = true;
}
} else {
- arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed, mavlink_fd);
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed, true /* fRunPreArmChecks */,
+ mavlink_fd);
if (arming_ret == TRANSITION_CHANGED) {
arming_state_changed = true;
}
}
+
status_changed = true;
}
@@ -1309,7 +1450,8 @@ int commander_thread_main(int argc, char *argv[])
/* If in INIT state, try to proceed to STANDBY state */
if (status.arming_state == ARMING_STATE_INIT && low_prio_task == LOW_PRIO_TASK_NONE) {
/* TODO: check for sensors */
- arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd);
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, true /* fRunPreArmChecks */,
+ mavlink_fd);
if (arming_ret == TRANSITION_CHANGED) {
arming_state_changed = true;
@@ -1335,14 +1477,64 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position);
}
+ /* Initialize map projection if gps is valid */
+ if (!map_projection_global_initialized()
+ && (gps_position.eph < eph_threshold)
+ && (gps_position.epv < epv_threshold)
+ && hrt_elapsed_time((hrt_abstime *)&gps_position.timestamp_position) < 1e6) {
+ /* set reference for global coordinates <--> local coordiantes conversion and map_projection */
+ globallocalconverter_init((double)gps_position.lat * 1.0e-7, (double)gps_position.lon * 1.0e-7,
+ (float)gps_position.alt * 1.0e-3f, hrt_absolute_time());
+ }
+
+ /* check if GPS fix is ok */
+ if (status.circuit_breaker_engaged_gpsfailure_check ||
+ (gps_position.fix_type >= 3 &&
+ hrt_elapsed_time(&gps_position.timestamp_position) < FAILSAFE_DEFAULT_TIMEOUT)) {
+ /* handle the case where gps was regained */
+ if (status.gps_failure) {
+ status.gps_failure = false;
+ status_changed = true;
+ mavlink_log_critical(mavlink_fd, "gps regained");
+ }
+
+ } else {
+ if (!status.gps_failure) {
+ status.gps_failure = true;
+ status_changed = true;
+ mavlink_log_critical(mavlink_fd, "gps fix lost");
+ }
+ }
+
+ /* start mission result check */
orb_check(mission_result_sub, &updated);
if (updated) {
orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result);
+
+ /* Check for geofence violation */
+ if (armed.armed && (mission_result.geofence_violated || mission_result.flight_termination)) {
+ //XXX: make this configurable to select different actions (e.g. navigation modes)
+ /* this will only trigger if geofence is activated via param and a geofence file is present, also there is a circuit breaker to disable the actual flight termination in the px4io driver */
+ armed.force_failsafe = true;
+ status_changed = true;
+ static bool flight_termination_printed = false;
+
+ if (!flight_termination_printed) {
+ warnx("Flight termination because of navigator request or geofence");
+ mavlink_log_critical(mavlink_fd, "GF violation: flight termination");
+ flight_termination_printed = true;
+ }
+
+ if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
+ mavlink_log_critical(mavlink_fd, "GF violation: flight termination");
+ }
+ } // no reset is done here on purpose, on geofence violation we want to stay in flighttermination
}
/* RC input check */
- if (!status.rc_input_blocked && sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
+ if (!status.rc_input_blocked && sp_man.timestamp != 0 &&
+ hrt_absolute_time() < sp_man.timestamp + (uint64_t)(rc_loss_timeout * 1e6f)) {
/* handle the case where RC signal was regained */
if (!status.rc_signal_found_once) {
status.rc_signal_found_once = true;
@@ -1367,11 +1559,15 @@ int commander_thread_main(int argc, char *argv[])
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
/* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
- arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
- arming_ret = arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd);
+ arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY :
+ ARMING_STATE_STANDBY_ERROR);
+ arming_ret = arming_state_transition(&status, &safety, new_arming_state, &armed, true /* fRunPreArmChecks */,
+ mavlink_fd);
+
if (arming_ret == TRANSITION_CHANGED) {
arming_state_changed = true;
}
+
stick_off_counter = 0;
} else {
@@ -1393,8 +1589,11 @@ int commander_thread_main(int argc, char *argv[])
*/
if (status.main_state != MAIN_STATE_MANUAL) {
print_reject_arm("NOT ARMING: Switch to MANUAL mode first.");
+
} else {
- arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, mavlink_fd);
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, true /* fRunPreArmChecks */,
+ mavlink_fd);
+
if (arming_ret == TRANSITION_CHANGED) {
arming_state_changed = true;
}
@@ -1417,6 +1616,7 @@ int commander_thread_main(int argc, char *argv[])
} else {
mavlink_log_info(mavlink_fd, "DISARMED by RC");
}
+
arming_state_changed = true;
} else if (arming_ret == TRANSITION_DENIED) {
@@ -1452,16 +1652,29 @@ int commander_thread_main(int argc, char *argv[])
/* data links check */
bool have_link = false;
+
for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
- if (telemetry_last_heartbeat[i] != 0 && hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) {
- /* handle the case where data link was regained */
- if (telemetry_lost[i]) {
+ if (telemetry_last_heartbeat[i] != 0 &&
+ hrt_elapsed_time(&telemetry_last_heartbeat[i]) < datalink_loss_timeout * 1e6) {
+ /* handle the case where data link was regained,
+ * accept datalink as healthy only after datalink_regain_timeout seconds
+ * */
+ if (telemetry_lost[i] &&
+ hrt_elapsed_time(&telemetry_last_dl_loss[i]) > datalink_regain_timeout * 1e6) {
+
mavlink_log_critical(mavlink_fd, "data link %i regained", i);
telemetry_lost[i] = false;
+ have_link = true;
+
+ } else if (!telemetry_lost[i]) {
+ /* telemetry was healthy also in last iteration
+ * we don't have to check a timeout */
+ have_link = true;
}
- have_link = true;
} else {
+ telemetry_last_dl_loss[i] = hrt_absolute_time();
+
if (!telemetry_lost[i]) {
mavlink_log_critical(mavlink_fd, "data link %i lost", i);
telemetry_lost[i] = true;
@@ -1480,10 +1693,42 @@ int commander_thread_main(int argc, char *argv[])
if (!status.data_link_lost) {
mavlink_log_critical(mavlink_fd, "ALL DATA LINKS LOST");
status.data_link_lost = true;
+ status.data_link_lost_counter++;
status_changed = true;
}
}
+ /* Check engine failure
+ * only for fixed wing for now
+ */
+ if (!status.circuit_breaker_engaged_enginefailure_check &&
+ status.is_rotary_wing == false &&
+ armed.armed &&
+ ((actuator_controls.control[3] > ef_throttle_thres &&
+ battery.current_a / actuator_controls.control[3] <
+ ef_current2throttle_thres) ||
+ (status.engine_failure))) {
+ /* potential failure, measure time */
+ if (timestamp_engine_healthy > 0 &&
+ hrt_elapsed_time(&timestamp_engine_healthy) >
+ ef_time_thres * 1e6 &&
+ !status.engine_failure) {
+ status.engine_failure = true;
+ status_changed = true;
+ mavlink_log_critical(mavlink_fd, "Engine Failure");
+ }
+
+ } else {
+ /* no failure reset flag */
+ timestamp_engine_healthy = hrt_absolute_time();
+
+ if (status.engine_failure) {
+ status.engine_failure = false;
+ status_changed = true;
+ }
+ }
+
+
/* handle commands last, as the system needs to be updated to handle them */
orb_check(cmd_sub, &updated);
@@ -1497,6 +1742,57 @@ int commander_thread_main(int argc, char *argv[])
}
}
+ /* Check for failure combinations which lead to flight termination */
+ if (armed.armed) {
+ /* At this point the data link and the gps system have been checked
+ * If we are not in a manual (RC stick controlled mode)
+ * and both failed we want to terminate the flight */
+ if (status.main_state != MAIN_STATE_MANUAL &&
+ status.main_state != MAIN_STATE_ACRO &&
+ status.main_state != MAIN_STATE_ALTCTL &&
+ status.main_state != MAIN_STATE_POSCTL &&
+ ((status.data_link_lost && status.gps_failure) ||
+ (status.data_link_lost_cmd && status.gps_failure_cmd))) {
+ armed.force_failsafe = true;
+ status_changed = true;
+ static bool flight_termination_printed = false;
+
+ if (!flight_termination_printed) {
+ warnx("Flight termination because of data link loss && gps failure");
+ mavlink_log_critical(mavlink_fd, "DL and GPS lost: flight termination");
+ flight_termination_printed = true;
+ }
+
+ if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
+ mavlink_log_critical(mavlink_fd, "DL and GPS lost: flight termination");
+ }
+ }
+
+ /* At this point the rc signal and the gps system have been checked
+ * If we are in manual (controlled with RC):
+ * if both failed we want to terminate the flight */
+ if ((status.main_state == MAIN_STATE_ACRO ||
+ status.main_state == MAIN_STATE_MANUAL ||
+ status.main_state == MAIN_STATE_ALTCTL ||
+ status.main_state == MAIN_STATE_POSCTL) &&
+ ((status.rc_signal_lost && status.gps_failure) ||
+ (status.rc_signal_lost_cmd && status.gps_failure_cmd))) {
+ armed.force_failsafe = true;
+ status_changed = true;
+ static bool flight_termination_printed = false;
+
+ if (!flight_termination_printed) {
+ warnx("Flight termination because of RC signal loss && gps failure");
+ flight_termination_printed = true;
+ }
+
+ if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) {
+ mavlink_log_critical(mavlink_fd, "RC and GPS lost: flight termination");
+ }
+ }
+ }
+
+
hrt_abstime t1 = hrt_absolute_time();
/* print new state */
@@ -1531,6 +1827,7 @@ int commander_thread_main(int argc, char *argv[])
/* mark home position as set */
status.condition_home_position_valid = true;
}
+
arming_state_changed = false;
}
@@ -1538,7 +1835,8 @@ int commander_thread_main(int argc, char *argv[])
/* now set navigation state according to failsafe and main state */
bool nav_state_changed = set_nav_state(&status, (bool)datalink_loss_enabled,
- mission_result.finished);
+ mission_result.finished,
+ mission_result.stay_in_failsafe);
// TODO handle mode changes by commands
if (main_state_changed) {
@@ -1574,7 +1872,8 @@ int commander_thread_main(int argc, char *argv[])
}
/* play arming and battery warning tunes */
- if (!arm_tune_played && armed.armed && (!safety.safety_switch_available || (safety.safety_switch_available && safety.safety_off))) {
+ if (!arm_tune_played && armed.armed && (!safety.safety_switch_available || (safety.safety_switch_available
+ && safety.safety_off))) {
/* play tune when armed */
set_tune(TONE_ARMING_WARNING_TUNE);
arm_tune_played = true;
@@ -1744,9 +2043,15 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s
/* set main state according to RC switches */
transition_result_t res = TRANSITION_DENIED;
+ /* if offboard is set allready by a mavlink command, abort */
+ if (status.offboard_control_set_by_command) {
+ return main_state_transition(status_local, MAIN_STATE_OFFBOARD);
+ }
+
/* offboard switch overrides main switch */
if (sp_man->offboard_switch == SWITCH_POS_ON) {
res = main_state_transition(status_local, MAIN_STATE_OFFBOARD);
+
if (res == TRANSITION_DENIED) {
print_reject_mode(status_local, "OFFBOARD");
@@ -1768,6 +2073,7 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s
} else {
res = main_state_transition(status_local, MAIN_STATE_MANUAL);
}
+
// TRANSITION_DENIED is not possible here
break;
@@ -1782,7 +2088,7 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s
print_reject_mode(status_local, "POSCTL");
}
- // fallback to ALTCTL
+ // fallback to ALTCTL
res = main_state_transition(status_local, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
@@ -1806,14 +2112,14 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s
break; // changed successfully or already in this state
}
- print_reject_mode(status_local, "AUTO_RTL");
+ print_reject_mode(status_local, "AUTO_RTL");
- // fallback to LOITER if home position not set
- res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
+ // fallback to LOITER if home position not set
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
- if (res != TRANSITION_DENIED) {
- break; // changed successfully or already in this state
- }
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
} else if (sp_man->loiter_switch == SWITCH_POS_ON) {
res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
@@ -1822,7 +2128,7 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s
break; // changed successfully or already in this state
}
- print_reject_mode(status_local, "AUTO_LOITER");
+ print_reject_mode(status_local, "AUTO_LOITER");
} else {
res = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION);
@@ -1831,22 +2137,22 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s
break; // changed successfully or already in this state
}
- print_reject_mode(status_local, "AUTO_MISSION");
+ print_reject_mode(status_local, "AUTO_MISSION");
- // fallback to LOITER if home position not set
- res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
+ // fallback to LOITER if home position not set
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
- if (res != TRANSITION_DENIED) {
- break; // changed successfully or already in this state
- }
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
}
- // fallback to POSCTL
- res = main_state_transition(status_local, MAIN_STATE_POSCTL);
+ // fallback to POSCTL
+ res = main_state_transition(status_local, MAIN_STATE_POSCTL);
- if (res != TRANSITION_DENIED) {
- break; // changed successfully or already in this state
- }
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
// fallback to ALTCTL
res = main_state_transition(status_local, MAIN_STATE_ALTCTL);
@@ -1928,6 +2234,7 @@ set_control_mode()
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
break;
+
case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE:
control_mode.flag_control_rates_enabled = true;
control_mode.flag_control_attitude_enabled = true;
@@ -1936,22 +2243,30 @@ set_control_mode()
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
break;
- case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY:
+
+ case OFFBOARD_CONTROL_MODE_DIRECT_FORCE:
control_mode.flag_control_rates_enabled = true;
- control_mode.flag_control_attitude_enabled = true;
- control_mode.flag_control_altitude_enabled = true; /* XXX: hack for now */
- control_mode.flag_control_climb_rate_enabled = true;
- control_mode.flag_control_position_enabled = true; /* XXX: hack for now */
- control_mode.flag_control_velocity_enabled = true;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_force_enabled = true;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
break;
- case OFFBOARD_CONTROL_MODE_DIRECT_POSITION:
+
+ case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED:
+ case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED:
+ case OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED:
+ case OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED:
control_mode.flag_control_rates_enabled = true;
control_mode.flag_control_attitude_enabled = true;
control_mode.flag_control_altitude_enabled = true;
control_mode.flag_control_climb_rate_enabled = true;
control_mode.flag_control_position_enabled = true;
control_mode.flag_control_velocity_enabled = true;
+ //XXX: the flags could depend on sp_offboard.ignore
break;
+
default:
control_mode.flag_control_rates_enabled = false;
control_mode.flag_control_attitude_enabled = false;
@@ -1960,6 +2275,7 @@ set_control_mode()
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
}
+
break;
case NAVIGATION_STATE_POSCTL:
@@ -1978,6 +2294,7 @@ set_control_mode()
case NAVIGATION_STATE_AUTO_LOITER:
case NAVIGATION_STATE_AUTO_RTL:
case NAVIGATION_STATE_AUTO_RTGS:
+ case NAVIGATION_STATE_AUTO_LANDENGFAIL:
control_mode.flag_control_manual_enabled = false;
control_mode.flag_control_auto_enabled = true;
control_mode.flag_control_rates_enabled = true;
@@ -1989,6 +2306,18 @@ set_control_mode()
control_mode.flag_control_termination_enabled = false;
break;
+ case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
+ control_mode.flag_control_manual_enabled = false;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ control_mode.flag_control_termination_enabled = false;
+ break;
+
case NAVIGATION_STATE_LAND:
control_mode.flag_control_manual_enabled = false;
control_mode.flag_control_auto_enabled = true;
@@ -2156,7 +2485,8 @@ void *commander_low_prio_loop(void *arg)
int calib_ret = ERROR;
/* try to go to INIT/PREFLIGHT arming state */
- if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed, mavlink_fd)) {
+ if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed,
+ true /* fRunPreArmChecks */, mavlink_fd)) {
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
break;
}
@@ -2219,7 +2549,7 @@ void *commander_low_prio_loop(void *arg)
tune_negative(true);
}
- arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd);
+ arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, true /* fRunPreArmChecks */, mavlink_fd);
break;
}
diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c
index dba68700b..1b0c4258b 100644
--- a/src/modules/commander/commander_params.c
+++ b/src/modules/commander/commander_params.c
@@ -105,3 +105,69 @@ PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f);
* @max 1
*/
PARAM_DEFINE_INT32(COM_DL_LOSS_EN, 0);
+
+ /** Datalink loss time threshold
+ *
+ * After this amount of seconds without datalink the data link lost mode triggers
+ *
+ * @group commander
+ * @unit second
+ * @min 0
+ * @max 30
+ */
+PARAM_DEFINE_INT32(COM_DL_LOSS_T, 10);
+
+/** Datalink regain time threshold
+ *
+ * After a data link loss: after this this amount of seconds with a healthy datalink the 'datalink loss'
+ * flag is set back to false
+ *
+ * @group commander
+ * @unit second
+ * @min 0
+ * @max 30
+ */
+PARAM_DEFINE_INT32(COM_DL_REG_T, 0);
+
+/** Engine Failure Throttle Threshold
+ *
+ * Engine failure triggers only above this throttle value
+ *
+ * @group commander
+ * @min 0.0f
+ * @max 1.0f
+ */
+PARAM_DEFINE_FLOAT(COM_EF_THROT, 0.5f);
+
+/** Engine Failure Current/Throttle Threshold
+ *
+ * Engine failure triggers only below this current/throttle value
+ *
+ * @group commander
+ * @min 0.0f
+ * @max 7.0f
+ */
+PARAM_DEFINE_FLOAT(COM_EF_C2T, 5.0f);
+
+/** Engine Failure Time Threshold
+ *
+ * Engine failure triggers only if the throttle threshold and the
+ * current to throttle threshold are violated for this time
+ *
+ * @group commander
+ * @unit second
+ * @min 0.0f
+ * @max 7.0f
+ */
+PARAM_DEFINE_FLOAT(COM_EF_TIME, 10.0f);
+
+/** RC loss time threshold
+ *
+ * After this amount of seconds without RC connection the rc lost flag is set to true
+ *
+ * @group commander
+ * @unit second
+ * @min 0
+ * @max 35
+ */
+PARAM_DEFINE_FLOAT(COM_RC_LOSS_T, 0.5);
diff --git a/src/modules/commander/commander_tests/commander_tests.cpp b/src/modules/commander/commander_tests/commander_tests.cpp
index 0abb84a82..2bfa5d0bb 100644
--- a/src/modules/commander/commander_tests/commander_tests.cpp
+++ b/src/modules/commander/commander_tests/commander_tests.cpp
@@ -48,7 +48,5 @@ extern "C" __EXPORT int commander_tests_main(int argc, char *argv[]);
int commander_tests_main(int argc, char *argv[])
{
- stateMachineHelperTest();
-
- return 0;
+ return stateMachineHelperTest() ? 0 : -1;
}
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
index 2e18c4284..874090e93 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -49,7 +49,7 @@ public:
StateMachineHelperTest();
virtual ~StateMachineHelperTest();
- virtual void runTests(void);
+ virtual bool run_tests(void);
private:
bool armingStateTransitionTest();
@@ -286,7 +286,7 @@ bool StateMachineHelperTest::armingStateTransitionTest(void)
armed.ready_to_arm = test->current_state.ready_to_arm;
// Attempt transition
- transition_result_t result = arming_state_transition(&status, &safety, test->requested_state, &armed, 0 /* no mavlink_fd */);
+ transition_result_t result = arming_state_transition(&status, &safety, test->requested_state, &armed, false /* no pre-arm checks */, 0 /* no mavlink_fd */);
// Validate result of transition
ut_assert(test->assertMsg, test->expected_transition_result == result);
@@ -335,12 +335,12 @@ bool StateMachineHelperTest::mainStateTransitionTest(void)
MTT_ALL_NOT_VALID,
MAIN_STATE_ACRO, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
- { "transition: MANUAL to AUTO_MISSION - global position valid",
- MTT_GLOBAL_POS_VALID,
+ { "transition: MANUAL to AUTO_MISSION - global position valid, home position valid",
+ MTT_GLOBAL_POS_VALID | MTT_HOME_POS_VALID,
MAIN_STATE_MANUAL, MAIN_STATE_AUTO_MISSION, TRANSITION_CHANGED },
- { "transition: AUTO_MISSION to MANUAL - global position valid",
- MTT_GLOBAL_POS_VALID,
+ { "transition: AUTO_MISSION to MANUAL - global position valid, home position valid",
+ MTT_GLOBAL_POS_VALID | MTT_HOME_POS_VALID,
MAIN_STATE_AUTO_MISSION, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
{ "transition: MANUAL to AUTO_LOITER - global position valid",
@@ -488,16 +488,13 @@ bool StateMachineHelperTest::isSafeTest(void)
return true;
}
-void StateMachineHelperTest::runTests(void)
+bool StateMachineHelperTest::run_tests(void)
{
ut_run_test(armingStateTransitionTest);
ut_run_test(mainStateTransitionTest);
ut_run_test(isSafeTest);
+
+ return (_tests_failed == 0);
}
-void stateMachineHelperTest(void)
-{
- StateMachineHelperTest* test = new StateMachineHelperTest();
- test->runTests();
- test->printResults();
-}
+ut_declare_test(stateMachineHelperTest, StateMachineHelperTest) \ No newline at end of file
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.h b/src/modules/commander/commander_tests/state_machine_helper_test.h
index bbf66255e..cf6719095 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.h
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.h
@@ -39,6 +39,6 @@
#ifndef STATE_MACHINE_HELPER_TEST_H_
#define STATE_MACHINE_HELPER_TEST_
-void stateMachineHelperTest(void);
+bool stateMachineHelperTest(void);
#endif /* STATE_MACHINE_HELPER_TEST_H_ */
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index d89c67c2b..8ab14dd52 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -63,7 +63,10 @@ static const char *sensor_name = "gyro";
int do_gyro_calibration(int mavlink_fd)
{
mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
- mavlink_log_info(mavlink_fd, "don't move system");
+ mavlink_log_info(mavlink_fd, "HOLD STILL");
+
+ /* wait for the user to respond */
+ sleep(2);
struct gyro_scale gyro_scale = {
0.0f,
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 23900f386..7be8de9c6 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -155,7 +155,7 @@ int do_mag_calibration(int mavlink_fd)
uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
unsigned poll_errcount = 0;
- mavlink_log_info(mavlink_fd, "rotate in a figure 8 around all axis");
+ mavlink_log_info(mavlink_fd, "Turn on all sides: front/back,left/right,up/down");
calibration_counter = 0;
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 3c3d2f233..9568752ae 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -99,11 +99,12 @@ static const char * const state_names[ARMING_STATE_MAX] = {
};
transition_result_t
-arming_state_transition(struct vehicle_status_s *status, /// current vehicle status
- const struct safety_s *safety, /// current safety settings
- arming_state_t new_arming_state, /// arming state requested
- struct actuator_armed_s *armed, /// current armed status
- const int mavlink_fd) /// mavlink fd for error reporting, 0 for none
+arming_state_transition(struct vehicle_status_s *status, ///< current vehicle status
+ const struct safety_s *safety, ///< current safety settings
+ arming_state_t new_arming_state, ///< arming state requested
+ struct actuator_armed_s *armed, ///< current armed status
+ bool fRunPreArmChecks, ///< true: run the pre-arm checks, false: no pre-arm checks, for unit testing
+ const int mavlink_fd) ///< mavlink fd for error reporting, 0 for none
{
// Double check that our static arrays are still valid
ASSERT(ARMING_STATE_INIT == 0);
@@ -125,7 +126,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current
int prearm_ret = OK;
/* only perform the check if we have to */
- if (new_arming_state == ARMING_STATE_ARMED) {
+ if (fRunPreArmChecks && new_arming_state == ARMING_STATE_ARMED) {
prearm_ret = prearm_check(status, mavlink_fd);
}
@@ -181,12 +182,19 @@ arming_state_transition(struct vehicle_status_s *status, /// current
// Fail transition if power levels on the avionics rail
// are measured but are insufficient
- if (status->condition_power_input_valid && ((status->avionics_power_rail_voltage > 0.0f) &&
- (status->avionics_power_rail_voltage < 4.9f))) {
-
- mavlink_log_critical(mavlink_fd, "NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage);
- feedback_provided = true;
- valid_transition = false;
+ if (status->condition_power_input_valid && (status->avionics_power_rail_voltage > 0.0f)) {
+ // Check avionics rail voltages
+ if (status->avionics_power_rail_voltage < 4.75f) {
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Avionics power low: %6.2f Volt", (double)status->avionics_power_rail_voltage);
+ feedback_provided = true;
+ valid_transition = false;
+ } else if (status->avionics_power_rail_voltage < 4.9f) {
+ mavlink_log_critical(mavlink_fd, "CAUTION: Avionics power low: %6.2f Volt", (double)status->avionics_power_rail_voltage);
+ feedback_provided = true;
+ } else if (status->avionics_power_rail_voltage > 5.4f) {
+ mavlink_log_critical(mavlink_fd, "CAUTION: Avionics power high: %6.2f Volt", (double)status->avionics_power_rail_voltage);
+ feedback_provided = true;
+ }
}
}
@@ -435,7 +443,8 @@ transition_result_t hil_state_transition(hil_state_t new_state, int status_pub,
/**
* Check failsafe and main status and set navigation status for navigator accordingly
*/
-bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished)
+bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished,
+ const bool stay_in_failsafe)
{
navigation_state_t nav_state_old = status->nav_state;
@@ -449,11 +458,11 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
case MAIN_STATE_ALTCTL:
case MAIN_STATE_POSCTL:
/* require RC for all manual modes */
- if (status->rc_signal_lost && armed) {
+ if ((status->rc_signal_lost || status->rc_signal_lost_cmd) && armed) {
status->failsafe = true;
if (status->condition_global_position_valid && status->condition_home_position_valid) {
- status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ status->nav_state = NAVIGATION_STATE_AUTO_RCRECOVER;
} else if (status->condition_local_position_valid) {
status->nav_state = NAVIGATION_STATE_LAND;
} else if (status->condition_local_altitude_valid) {
@@ -489,14 +498,29 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
case MAIN_STATE_AUTO_MISSION:
/* go into failsafe
+ * - if commanded to do so
+ * - if we have an engine failure
* - if either the datalink is enabled and lost as well as RC is lost
* - if there is no datalink and the mission is finished */
- if (((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) ||
+ if (status->engine_failure_cmd) {
+ status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL;
+ } else if (status->data_link_lost_cmd) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
+ } else if (status->gps_failure_cmd) {
+ status->nav_state = NAVIGATION_STATE_AUTO_LANDGPSFAIL;
+ } else if (status->rc_signal_lost_cmd) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS; //XXX
+ /* Finished handling commands which have priority , now handle failures */
+ } else if (status->gps_failure) {
+ status->nav_state = NAVIGATION_STATE_AUTO_LANDGPSFAIL;
+ } else if (status->engine_failure) {
+ status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL;
+ } else if (((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) ||
(!data_link_loss_enabled && status->rc_signal_lost && mission_finished)) {
status->failsafe = true;
if (status->condition_global_position_valid && status->condition_home_position_valid) {
- status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
} else if (status->condition_local_position_valid) {
status->nav_state = NAVIGATION_STATE_LAND;
} else if (status->condition_local_altitude_valid) {
@@ -520,31 +544,20 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
}
/* don't bother if RC is lost and mission is not yet finished */
- } else if (status->rc_signal_lost) {
+ } else if (status->rc_signal_lost && !stay_in_failsafe) {
/* this mode is ok, we don't need RC for missions */
status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
- } else {
+ } else if (!stay_in_failsafe){
/* everything is perfect */
status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
}
break;
case MAIN_STATE_AUTO_LOITER:
- /* go into failsafe if datalink and RC is lost */
- if ((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) {
- status->failsafe = true;
-
- if (status->condition_global_position_valid && status->condition_home_position_valid) {
- status->nav_state = NAVIGATION_STATE_AUTO_RTL;
- } else if (status->condition_local_position_valid) {
- status->nav_state = NAVIGATION_STATE_LAND;
- } else if (status->condition_local_altitude_valid) {
- status->nav_state = NAVIGATION_STATE_DESCEND;
- } else {
- status->nav_state = NAVIGATION_STATE_TERMINATION;
- }
-
+ /* go into failsafe on a engine failure */
+ if (status->engine_failure) {
+ status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL;
/* also go into failsafe if just datalink is lost */
} else if (status->data_link_lost && data_link_loss_enabled) {
status->failsafe = true;
@@ -585,8 +598,12 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
break;
case MAIN_STATE_AUTO_RTL:
- /* require global position and home */
- if ((!status->condition_global_position_valid || !status->condition_home_position_valid)) {
+ /* require global position and home, also go into failsafe on an engine failure */
+
+ if (status->engine_failure) {
+ status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL;
+ } else if ((!status->condition_global_position_valid ||
+ !status->condition_home_position_valid)) {
status->failsafe = true;
if (status->condition_local_position_valid) {
diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h
index bb1b87e71..61d0f29d0 100644
--- a/src/modules/commander/state_machine_helper.h
+++ b/src/modules/commander/state_machine_helper.h
@@ -57,13 +57,13 @@ typedef enum {
bool is_safe(const struct vehicle_status_s *current_state, const struct safety_s *safety, const struct actuator_armed_s *armed);
transition_result_t arming_state_transition(struct vehicle_status_s *current_state, const struct safety_s *safety,
- arming_state_t new_arming_state, struct actuator_armed_s *armed, const int mavlink_fd);
+ arming_state_t new_arming_state, struct actuator_armed_s *armed, bool fRunPreArmChecks, const int mavlink_fd);
transition_result_t main_state_transition(struct vehicle_status_s *current_state, main_state_t new_main_state);
transition_result_t hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_state, const int mavlink_fd);
-bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished);
+bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished, const bool stay_in_failsafe);
int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd);
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
index ca1fe9bbb..b2355d4d8 100644
--- a/src/modules/dataman/dataman.c
+++ b/src/modules/dataman/dataman.c
@@ -797,7 +797,7 @@ start(void)
sem_init(&g_init_sema, 1, 0);
/* start the worker thread */
- if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2000, task_main, NULL)) <= 0) {
+ if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 2000, task_main, NULL)) <= 0) {
warn("task start failed");
return -1;
}
diff --git a/src/modules/dataman/module.mk b/src/modules/dataman/module.mk
index 234607b3d..7ebe09fb7 100644
--- a/src/modules/dataman/module.mk
+++ b/src/modules/dataman/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = dataman
SRCS = dataman.c
MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index 91d17e787..685f5e12f 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -58,6 +58,7 @@
#include <drivers/drv_accel.h>
#include <drivers/drv_mag.h>
#include <drivers/drv_baro.h>
+#include <drivers/drv_range_finder.h>
#ifdef SENSOR_COMBINED_SUB
#include <uORB/topics/sensor_combined.h>
#endif
@@ -96,7 +97,10 @@ extern "C" __EXPORT int ekf_att_pos_estimator_main(int argc, char *argv[]);
__EXPORT uint32_t millis();
+__EXPORT uint64_t getMicros();
+
static uint64_t IMUmsec = 0;
+static uint64_t IMUusec = 0;
static const uint64_t FILTER_INIT_DELAY = 1 * 1000 * 1000;
uint32_t millis()
@@ -104,6 +108,11 @@ uint32_t millis()
return IMUmsec;
}
+uint64_t getMicros()
+{
+ return IMUusec;
+}
+
class FixedwingEstimator
{
public:
@@ -171,6 +180,7 @@ private:
#else
int _sensor_combined_sub;
#endif
+ int _distance_sub; /**< distance measurement */
int _airspeed_sub; /**< airspeed subscription */
int _baro_sub; /**< barometer subscription */
int _gps_sub; /**< GPS subscription */
@@ -196,7 +206,8 @@ private:
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
struct vehicle_local_position_s _local_pos; /**< local vehicle position */
struct vehicle_gps_position_s _gps; /**< GPS position */
- struct wind_estimate_s _wind; /**< Wind estimate */
+ struct wind_estimate_s _wind; /**< wind estimate */
+ struct range_finder_report _distance; /**< distance estimate */
struct gyro_scale _gyro_offsets;
struct accel_scale _accel_offsets;
@@ -226,6 +237,7 @@ private:
hrt_abstime _filter_start_time;
hrt_abstime _last_sensor_timestamp;
hrt_abstime _last_run;
+ hrt_abstime _distance_last_valid;
bool _gyro_valid;
bool _accel_valid;
bool _mag_valid;
@@ -342,6 +354,7 @@ FixedwingEstimator::FixedwingEstimator() :
#else
_sensor_combined_sub(-1),
#endif
+ _distance_sub(-1),
_airspeed_sub(-1),
_baro_sub(-1),
_gps_sub(-1),
@@ -369,6 +382,7 @@ FixedwingEstimator::FixedwingEstimator() :
_local_pos({}),
_gps({}),
_wind({}),
+ _distance{},
_gyro_offsets({}),
_accel_offsets({}),
@@ -399,6 +413,7 @@ FixedwingEstimator::FixedwingEstimator() :
_filter_start_time(0),
_last_sensor_timestamp(0),
_last_run(0),
+ _distance_last_valid(0),
_gyro_valid(false),
_accel_valid(false),
_mag_valid(false),
@@ -549,6 +564,7 @@ FixedwingEstimator::parameters_update()
_ekf->gyroProcessNoise = _parameters.gyro_pnoise;
_ekf->accelProcessNoise = _parameters.acc_pnoise;
_ekf->airspeedMeasurementSigma = _parameters.eas_noise;
+ _ekf->rngFinderPitch = 0.0f; // XXX base on SENS_BOARD_Y_OFF
}
return OK;
@@ -581,12 +597,12 @@ FixedwingEstimator::check_filter_state()
const char* const feedback[] = { 0,
"NaN in states, resetting",
- "stale IMU data, resetting",
+ "stale sensor data, resetting",
"got initial position lock",
"excessive gyro offsets",
- "GPS velocity divergence",
+ "velocity diverted, check accel config",
"excessive covariances",
- "unknown condition"};
+ "unknown condition, resetting"};
// Print out error condition
if (check) {
@@ -598,7 +614,7 @@ FixedwingEstimator::check_filter_state()
}
warnx("reset: %s", feedback[warn_index]);
- mavlink_log_critical(_mavlink_fd, "[ekf] re-init: %s", feedback[warn_index]);
+ mavlink_log_critical(_mavlink_fd, "[ekf check] %s", feedback[warn_index]);
}
struct estimator_status_report rep;
@@ -704,6 +720,7 @@ FixedwingEstimator::task_main()
/*
* do subscriptions
*/
+ _distance_sub = orb_subscribe(ORB_ID(sensor_range_finder));
_baro_sub = orb_subscribe(ORB_ID(sensor_baro0));
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
_gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
@@ -753,6 +770,7 @@ FixedwingEstimator::task_main()
bool newHgtData = false;
bool newAdsData = false;
bool newDataMag = false;
+ bool newRangeData = false;
float posNED[3] = {0.0f, 0.0f, 0.0f}; // North, East Down position (m)
@@ -765,7 +783,7 @@ FixedwingEstimator::task_main()
while (!_task_should_exit) {
- /* wait for up to 500ms for data */
+ /* wait for up to 100ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
/* timed out - periodic check for _task_should_exit, etc. */
@@ -850,7 +868,8 @@ FixedwingEstimator::task_main()
}
_last_sensor_timestamp = _gyro.timestamp;
- IMUmsec = _gyro.timestamp / 1e3f;
+ IMUmsec = _gyro.timestamp / 1e3;
+ IMUusec = _gyro.timestamp;
float deltaT = (_gyro.timestamp - _last_run) / 1e6f;
_last_run = _gyro.timestamp;
@@ -914,7 +933,8 @@ FixedwingEstimator::task_main()
// Copy gyro and accel
_last_sensor_timestamp = _sensor_combined.timestamp;
- IMUmsec = _sensor_combined.timestamp / 1e3f;
+ IMUmsec = _sensor_combined.timestamp / 1e3;
+ IMUusec = _sensor_combined.timestamp;
float deltaT = (_sensor_combined.timestamp - _last_run) / 1e6f;
@@ -994,8 +1014,6 @@ FixedwingEstimator::task_main()
if (gps_updated) {
- last_gps = _gps.timestamp_position;
-
orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &_gps);
perf_count(_perf_gps);
@@ -1008,11 +1026,17 @@ FixedwingEstimator::task_main()
_gps_start_time = hrt_absolute_time();
/* check if we had a GPS outage for a long time */
- if (hrt_elapsed_time(&last_gps) > 5 * 1000 * 1000) {
+ float gps_elapsed = hrt_elapsed_time(&last_gps) / 1e6f;
+
+ const float pos_reset_threshold = 5.0f; // seconds
+
+ /* timeout of 5 seconds */
+ if (gps_elapsed > pos_reset_threshold) {
_ekf->ResetPosition();
_ekf->ResetVelocity();
_ekf->ResetStoredStates();
}
+ _ekf->updateDtGpsFilt(math::constrain((_gps.timestamp_position - last_gps) / 1e6f, 0.01f, pos_reset_threshold));
/* fuse GPS updates */
@@ -1044,6 +1068,8 @@ FixedwingEstimator::task_main()
newDataGps = true;
+ last_gps = _gps.timestamp_position;
+
}
}
@@ -1052,8 +1078,15 @@ FixedwingEstimator::task_main()
orb_check(_baro_sub, &baro_updated);
if (baro_updated) {
+
+ hrt_abstime baro_last = _baro.timestamp;
+
orb_copy(ORB_ID(sensor_baro0), _baro_sub, &_baro);
+ float baro_elapsed = (_baro.timestamp - baro_last) / 1e6f;
+
+ _ekf->updateDtHgtFilt(math::constrain(baro_elapsed, 0.001f, 0.1f));
+
_ekf->baroHgt = _baro.altitude;
if (!_baro_init) {
@@ -1114,6 +1147,19 @@ FixedwingEstimator::task_main()
newDataMag = false;
}
+ orb_check(_distance_sub, &newRangeData);
+
+ if (newRangeData) {
+ orb_copy(ORB_ID(sensor_range_finder), _distance_sub, &_distance);
+
+ if (_distance.valid) {
+ _ekf->rngMea = _distance.distance;
+ _distance_last_valid = _distance.timestamp;
+ } else {
+ newRangeData = false;
+ }
+ }
+
/*
* CHECK IF ITS THE RIGHT TIME TO RUN THINGS ALREADY
*/
@@ -1197,6 +1243,7 @@ FixedwingEstimator::task_main()
} else if (_ekf->statesInitialised) {
// We're apparently initialized in this case now
+ // check (and reset the filter as needed)
int check = check_filter_state();
if (check) {
@@ -1206,21 +1253,7 @@ FixedwingEstimator::task_main()
// Run the strapdown INS equations every IMU update
_ekf->UpdateStrapdownEquationsNED();
- #if 0
- // debug code - could be tunred into a filter mnitoring/watchdog function
- float tempQuat[4];
-
- for (uint8_t j = 0; j <= 3; j++) tempQuat[j] = states[j];
-
- quat2eul(eulerEst, tempQuat);
- for (uint8_t j = 0; j <= 2; j++) eulerDif[j] = eulerEst[j] - ahrsEul[j];
-
- if (eulerDif[2] > pi) eulerDif[2] -= 2 * pi;
-
- if (eulerDif[2] < -pi) eulerDif[2] += 2 * pi;
-
- #endif
// store the predicted states for subsequent use by measurement fusion
_ekf->StoreStates(IMUmsec);
// Check if on ground - status is used by covariance prediction
@@ -1334,6 +1367,13 @@ FixedwingEstimator::task_main()
_ekf->fuseVtasData = false;
}
+ if (newRangeData) {
+ _ekf->fuseRngData = true;
+ _ekf->useRangeFinder = true;
+ _ekf->RecallStates(_ekf->statesAtRngTime, (IMUmsec - 100.0f));
+ _ekf->GroundEKF();
+ }
+
// Output results
math::Quaternion q(_ekf->states[0], _ekf->states[1], _ekf->states[2], _ekf->states[3]);
@@ -1447,6 +1487,10 @@ FixedwingEstimator::task_main()
_global_pos.vel_d = _local_pos.vz;
}
+ /* terrain altitude */
+ _global_pos.terrain_alt = _ekf->hgtRef - _ekf->flowStates[1];
+ _global_pos.terrain_alt_valid = (_distance_last_valid > 0) &&
+ (hrt_elapsed_time(&_distance_last_valid) < 20 * 1000 * 1000);
_global_pos.yaw = _local_pos.yaw;
@@ -1467,8 +1511,10 @@ FixedwingEstimator::task_main()
if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
_wind.timestamp = _global_pos.timestamp;
- _wind.windspeed_north = _ekf->states[14];
- _wind.windspeed_east = _ekf->states[15];
+ _wind.windspeed_north = _ekf->windSpdFiltNorth;
+ _wind.windspeed_east = _ekf->windSpdFiltEast;
+ // XXX we need to do something smart about the covariance here
+ // but we default to the estimate covariance for now
_wind.covariance_north = _ekf->P[14][14];
_wind.covariance_east = _ekf->P[15][15];
diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
index ffdd29a5b..c17e034ad 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
@@ -2,6 +2,11 @@
#include <string.h>
#include <stdio.h>
#include <stdarg.h>
+#include <math.h>
+
+#ifndef M_PI_F
+#define M_PI_F ((float)M_PI)
+#endif
#define EKF_COVARIANCE_DIVERGED 1.0e8f
@@ -38,13 +43,14 @@ AttPosEKF::AttPosEKF() :
resetStates{},
storedStates{},
statetimeStamp{},
+ lastVelPosFusion(millis()),
statesAtVelTime{},
statesAtPosTime{},
statesAtHgtTime{},
statesAtMagMeasTime{},
statesAtVtasMeasTime{},
statesAtRngTime{},
- statesAtOptFlowTime{},
+ statesAtFlowTime{},
correctedDelAng(),
correctedDelVel(),
summedDelAng(),
@@ -59,7 +65,16 @@ AttPosEKF::AttPosEKF() :
accel(),
dVelIMU(),
dAngIMU(),
- dtIMU(0),
+ dtIMU(0.005f),
+ dtIMUfilt(0.005f),
+ dtVelPos(0.01f),
+ dtVelPosFilt(0.01f),
+ dtHgtFilt(0.01f),
+ dtGpsFilt(0.1f),
+ windSpdFiltNorth(0.0f),
+ windSpdFiltEast(0.0f),
+ windSpdFiltAltitude(0.0f),
+ windSpdFiltClimb(0.0f),
fusionModeGPS(0),
innovVelPos{},
varInnovVelPos{},
@@ -103,13 +118,14 @@ AttPosEKF::AttPosEKF() :
inhibitWindStates(true),
inhibitMagStates(true),
- inhibitGndHgtState(true),
+ inhibitGndState(true),
+ inhibitScaleState(true),
onGround(true),
staticMode(true),
useAirspeed(true),
useCompass(true),
- useRangeFinder(false),
+ useRangeFinder(true),
useOpticalFlow(false),
ekfDiverged(false),
@@ -117,7 +133,24 @@ AttPosEKF::AttPosEKF() :
current_ekf_state{},
last_ekf_error{},
numericalProtection(true),
- storeIndex(0)
+ storeIndex(0),
+ storedOmega{},
+ Popt{},
+ flowStates{},
+ prevPosN(0.0f),
+ prevPosE(0.0f),
+ auxFlowObsInnov{},
+ auxFlowObsInnovVar{},
+ fScaleFactorVar(0.0f),
+ Tnb_flow{},
+ R_LOS(0.0f),
+ auxFlowTestRatio{},
+ auxRngTestRatio(0.0f),
+ flowInnovGate(0.0f),
+ auxFlowInnovGate(0.0f),
+ rngInnovGate(0.0f),
+ minFlowRng(0.0f),
+ moCompR_LOS(0.0f)
{
memset(&last_ekf_error, 0, sizeof(last_ekf_error));
memset(&current_ekf_state, 0, sizeof(current_ekf_state));
@@ -260,6 +293,9 @@ void AttPosEKF::UpdateStrapdownEquationsNED()
// Constrain states (to protect against filter divergence)
ConstrainStates();
+
+ // update filtered IMU time step length
+ dtIMUfilt = 0.99f * dtIMUfilt + 0.01f * dtIMU;
}
void AttPosEKF::CovariancePrediction(float dt)
@@ -312,7 +348,7 @@ void AttPosEKF::CovariancePrediction(float dt)
} else {
for (uint8_t i=16; i<=21; i++) processNoise[i] = 0;
}
- if (!inhibitGndHgtState) {
+ if (!inhibitGndState) {
processNoise[22] = dt * sqrtf(sq(states[4]) + sq(states[5])) * gndHgtSigma;
} else {
processNoise[22] = 0;
@@ -962,6 +998,21 @@ void AttPosEKF::CovariancePrediction(float dt)
ConstrainVariances();
}
+void AttPosEKF::updateDtGpsFilt(float dt)
+{
+ dtGpsFilt = ConstrainFloat(dt, 0.001f, 2.0f) * 0.05f + dtGpsFilt * 0.95f;
+}
+
+void AttPosEKF::updateDtHgtFilt(float dt)
+{
+ dtHgtFilt = ConstrainFloat(dt, 0.001f, 2.0f) * 0.05f + dtHgtFilt * 0.95f;
+}
+
+void AttPosEKF::updateDtVelPosFilt(float dt)
+{
+ dtVelPosFilt = ConstrainFloat(dt, 0.0005f, 2.0f) * 0.05f + dtVelPosFilt * 0.95f;
+}
+
void AttPosEKF::FuseVelposNED()
{
@@ -998,6 +1049,18 @@ void AttPosEKF::FuseVelposNED()
// associated with sequential fusion
if (fuseVelData || fusePosData || fuseHgtData)
{
+ uint64_t tNow = getMicros();
+ updateDtVelPosFilt((tNow - lastVelPosFusion) / 1e6f);
+ lastVelPosFusion = tNow;
+
+ // scaler according to the number of repetitions of the
+ // same measurement in one fusion step
+ float gpsVarianceScaler = dtGpsFilt / dtVelPosFilt;
+
+ // scaler according to the number of repetitions of the
+ // same measurement in one fusion step
+ float hgtVarianceScaler = dtHgtFilt / dtVelPosFilt;
+
// set the GPS data timeout depending on whether airspeed data is present
if (useAirspeed) horizRetryTime = gpsRetryTime;
else horizRetryTime = gpsRetryTimeNoTAS;
@@ -1010,12 +1073,12 @@ void AttPosEKF::FuseVelposNED()
// Estimate the GPS Velocity, GPS horiz position and height measurement variances.
velErr = 0.2f*accNavMag; // additional error in GPS velocities caused by manoeuvring
posErr = 0.2f*accNavMag; // additional error in GPS position caused by manoeuvring
- R_OBS[0] = sq(vneSigma) + sq(velErr);
+ R_OBS[0] = gpsVarianceScaler * sq(vneSigma) + sq(velErr);
R_OBS[1] = R_OBS[0];
- R_OBS[2] = sq(vdSigma) + sq(velErr);
- R_OBS[3] = sq(posNeSigma) + sq(posErr);
+ R_OBS[2] = gpsVarianceScaler * sq(vdSigma) + sq(velErr);
+ R_OBS[3] = gpsVarianceScaler * sq(posNeSigma) + sq(posErr);
R_OBS[4] = R_OBS[3];
- R_OBS[5] = sq(posDSigma) + sq(posErr);
+ R_OBS[5] = hgtVarianceScaler * sq(posDSigma) + sq(posErr);
// calculate innovations and check GPS data validity using an innovation consistency check
if (fuseVelData)
@@ -1032,10 +1095,16 @@ void AttPosEKF::FuseVelposNED()
// apply a 5-sigma threshold
current_ekf_state.velHealth = (sq(velInnov[0]) + sq(velInnov[1]) + sq(velInnov[2])) < 25.0f * (varInnovVelPos[0] + varInnovVelPos[1] + varInnovVelPos[2]);
current_ekf_state.velTimeout = (millis() - current_ekf_state.velFailTime) > horizRetryTime;
- if (current_ekf_state.velHealth || current_ekf_state.velTimeout)
- {
+ if (current_ekf_state.velHealth || staticMode) {
current_ekf_state.velHealth = true;
current_ekf_state.velFailTime = millis();
+ } else if (current_ekf_state.velTimeout || !current_ekf_state.posHealth) {
+ // XXX check
+ current_ekf_state.velHealth = true;
+ ResetVelocity();
+ ResetStoredStates();
+ // do not fuse bad data
+ fuseVelData = false;
}
else
{
@@ -1056,6 +1125,17 @@ void AttPosEKF::FuseVelposNED()
{
current_ekf_state.posHealth = true;
current_ekf_state.posFailTime = millis();
+
+ if (current_ekf_state.posTimeout) {
+ ResetPosition();
+
+ // XXX cross-check the state reset
+ ResetStoredStates();
+
+ // do not fuse position data on this time
+ // step
+ fusePosData = false;
+ }
}
else
{
@@ -1070,10 +1150,18 @@ void AttPosEKF::FuseVelposNED()
// apply a 10-sigma threshold
current_ekf_state.hgtHealth = sq(hgtInnov) < 100.0f*varInnovVelPos[5];
current_ekf_state.hgtTimeout = (millis() - current_ekf_state.hgtFailTime) > hgtRetryTime;
- if (current_ekf_state.hgtHealth || current_ekf_state.hgtTimeout)
+ if (current_ekf_state.hgtHealth || current_ekf_state.hgtTimeout || staticMode)
{
current_ekf_state.hgtHealth = true;
current_ekf_state.hgtFailTime = millis();
+
+ // if we just reset from a timeout, do not fuse
+ // the height data, but reset height and stored states
+ if (current_ekf_state.hgtTimeout) {
+ ResetHeight();
+ ResetStoredStates();
+ fuseHgtData = false;
+ }
}
else
{
@@ -1148,7 +1236,7 @@ void AttPosEKF::FuseVelposNED()
}
}
// Don't update terrain state if inhibited
- if (inhibitGndHgtState) {
+ if (inhibitGndState) {
Kfusion[22] = 0;
}
@@ -1331,7 +1419,7 @@ void AttPosEKF::FuseMagnetometer()
Kfusion[i] = 0;
}
}
- if (!inhibitGndHgtState) {
+ if (!inhibitGndState) {
Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[3] - P[22][2]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[5] - P[22][18]*SK_MX[4]);
} else {
Kfusion[22] = 0;
@@ -1405,11 +1493,6 @@ void AttPosEKF::FuseMagnetometer()
Kfusion[20] = 0;
Kfusion[21] = 0;
}
- if (!inhibitGndHgtState) {
- Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]);
- } else {
- Kfusion[22] = 0;
- }
varInnovMag[1] = 1.0f/SK_MY[0];
innovMag[1] = MagPred[1] - magData.y;
}
@@ -1480,11 +1563,6 @@ void AttPosEKF::FuseMagnetometer()
Kfusion[20] = 0;
Kfusion[21] = 0;
}
- if (!inhibitGndHgtState) {
- Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] + P[22][3]*SH_MAG[0] - P[22][1]*SK_MZ[2] + P[22][2]*SK_MZ[3] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[5] - P[22][17]*SK_MZ[4]);
- } else {
- Kfusion[22] = 0;
- }
varInnovMag[2] = 1.0f/SK_MZ[0];
innovMag[2] = MagPred[2] - magData.z;
@@ -1591,6 +1669,32 @@ void AttPosEKF::FuseAirspeed()
// Perform fusion of True Airspeed measurement
if (useAirspeed && fuseVtasData && (VtasPred > 1.0f) && (VtasMeas > 8.0f))
{
+
+ float altDiff = fabsf(windSpdFiltAltitude - hgtMea);
+
+ if (isfinite(windSpdFiltClimb)) {
+ windSpdFiltClimb = ((1.0f - 0.0002f) * windSpdFiltClimb) + (0.0002f * states[6]);
+ } else {
+ windSpdFiltClimb = states[6];
+ }
+
+ if (altDiff < 20.0f) {
+ // Lowpass the output of the wind estimate - we want a long-term
+ // stable estimate, but not start to load into the overall dynamics
+ // of the system (which adjusting covariances would do)
+
+ // Change filter coefficient based on altitude change rate
+ float windFiltCoeff = ConstrainFloat(fabsf(windSpdFiltClimb) / 1000.0f, 0.00005f, 0.2f);
+
+ windSpdFiltNorth = ((1.0f - windFiltCoeff) * windSpdFiltNorth) + (windFiltCoeff * vwn);
+ windSpdFiltEast = ((1.0f - windFiltCoeff) * windSpdFiltEast) + (windFiltCoeff * vwe);
+ } else {
+ windSpdFiltNorth = vwn;
+ windSpdFiltEast = vwe;
+ }
+
+ windSpdFiltAltitude = hgtMea;
+
// Calculate observation jacobians
SH_TAS[0] = 1/(sqrt(sq(ve - vwe) + sq(vn - vwn) + sq(vd)));
SH_TAS[1] = (SH_TAS[0]*(2.0f*ve - 2*vwe))/2.0f;
@@ -1650,11 +1754,6 @@ void AttPosEKF::FuseAirspeed()
Kfusion[i] = 0;
}
}
- if (!inhibitGndHgtState) {
- Kfusion[22] = SK_TAS*(P[22][4]*SH_TAS[2] - P[22][14]*SH_TAS[2] + P[22][5]*SH_TAS[1] - P[22][15]*SH_TAS[1] + P[22][6]*vd*SH_TAS[0]);
- } else {
- Kfusion[22] = 0;
- }
varInnovVtas = 1.0f/SK_TAS;
// Calculate the measurement innovation
@@ -1786,8 +1885,11 @@ void AttPosEKF::FuseRangeFinder()
rngPred = (ptd - pd)/cosRngTilt;
innovRng = rngPred - rngMea;
- // Check the innovation for consistency and don't fuse if > 5Sigma
- if ((innovRng*innovRng*SK_RNG[0]) < 25)
+ // calculate the innovation consistency test ratio
+ auxRngTestRatio = sq(innovRng) / (sq(rngInnovGate) * varInnovRng);
+
+ // Check the innovation for consistency and don't fuse if out of bounds
+ if (auxRngTestRatio < 1.0f)
{
// correct the state vector
states[22] = states[22] - Kfusion[22] * innovRng;
@@ -1802,285 +1904,387 @@ void AttPosEKF::FuseRangeFinder()
void AttPosEKF::FuseOptFlow()
{
- static uint8_t obsIndex;
- static float SH_LOS[13];
- static float SKK_LOS[15];
- static float SK_LOS[2];
- static float q0 = 0.0f;
- static float q1 = 0.0f;
- static float q2 = 0.0f;
- static float q3 = 1.0f;
- static float vn = 0.0f;
- static float ve = 0.0f;
- static float vd = 0.0f;
- static float pd = 0.0f;
- static float ptd = 0.0f;
- static float R_LOS = 0.01f;
- static float losPred[2];
-
- // Transformation matrix from nav to body axes
- Mat3f Tnb_local;
- // Transformation matrix from body to sensor axes
- // assume camera is aligned with Z body axis plus a misalignment
- // defined by 3 small angles about X, Y and Z body axis
- Mat3f Tbs;
- Tbs.x.y = a3;
- Tbs.y.x = -a3;
- Tbs.x.z = -a2;
- Tbs.z.x = a2;
- Tbs.y.z = a1;
- Tbs.z.y = -a1;
- // Transformation matrix from navigation to sensor axes
- Mat3f Tns;
- float H_LOS[n_states];
- for (uint8_t i = 0; i < n_states; i++) {
- H_LOS[i] = 0.0f;
- }
- Vector3f velNED_local;
- Vector3f relVelSensor;
+// static uint8_t obsIndex;
+// static float SH_LOS[13];
+// static float SKK_LOS[15];
+// static float SK_LOS[2];
+// static float q0 = 0.0f;
+// static float q1 = 0.0f;
+// static float q2 = 0.0f;
+// static float q3 = 1.0f;
+// static float vn = 0.0f;
+// static float ve = 0.0f;
+// static float vd = 0.0f;
+// static float pd = 0.0f;
+// static float ptd = 0.0f;
+// static float R_LOS = 0.01f;
+// static float losPred[2];
+
+// // Transformation matrix from nav to body axes
+// Mat3f Tnb_local;
+// // Transformation matrix from body to sensor axes
+// // assume camera is aligned with Z body axis plus a misalignment
+// // defined by 3 small angles about X, Y and Z body axis
+// Mat3f Tbs;
+// Tbs.x.y = a3;
+// Tbs.y.x = -a3;
+// Tbs.x.z = -a2;
+// Tbs.z.x = a2;
+// Tbs.y.z = a1;
+// Tbs.z.y = -a1;
+// // Transformation matrix from navigation to sensor axes
+// Mat3f Tns;
+// float H_LOS[n_states];
+// for (uint8_t i = 0; i < n_states; i++) {
+// H_LOS[i] = 0.0f;
+// }
+// Vector3f velNED_local;
+// Vector3f relVelSensor;
+
+// // Perform sequential fusion of optical flow measurements only when in the air and tilt is less than 30 deg.
+// if (useOpticalFlow && (fuseOptFlowData || obsIndex == 1) && !onGround && Tbs.z.z > 0.866f && rngMea > 5.0f && rngMea < 39.0f)
+// {
+// // Sequential fusion of XY components to spread processing load across
+// // two prediction time steps.
+
+// // Calculate observation jacobians and Kalman gains
+// if (fuseOptFlowData)
+// {
+// // Copy required states to local variable names
+// q0 = statesAtOptFlowTime[0];
+// q1 = statesAtOptFlowTime[1];
+// q2 = statesAtOptFlowTime[2];
+// q3 = statesAtOptFlowTime[3];
+// vn = statesAtOptFlowTime[4];
+// ve = statesAtOptFlowTime[5];
+// vd = statesAtOptFlowTime[6];
+// pd = statesAtOptFlowTime[9];
+// ptd = statesAtOptFlowTime[22];
+// velNED_local.x = vn;
+// velNED_local.y = ve;
+// velNED_local.z = vd;
+
+// // calculate rotation from NED to body axes
+// float q00 = sq(q0);
+// float q11 = sq(q1);
+// float q22 = sq(q2);
+// float q33 = sq(q3);
+// float q01 = q0 * q1;
+// float q02 = q0 * q2;
+// float q03 = q0 * q3;
+// float q12 = q1 * q2;
+// float q13 = q1 * q3;
+// float q23 = q2 * q3;
+// Tnb_local.x.x = q00 + q11 - q22 - q33;
+// Tnb_local.y.y = q00 - q11 + q22 - q33;
+// Tnb_local.z.z = q00 - q11 - q22 + q33;
+// Tnb_local.y.x = 2*(q12 - q03);
+// Tnb_local.z.x = 2*(q13 + q02);
+// Tnb_local.x.y = 2*(q12 + q03);
+// Tnb_local.z.y = 2*(q23 - q01);
+// Tnb_local.x.z = 2*(q13 - q02);
+// Tnb_local.y.z = 2*(q23 + q01);
+
+// // calculate transformation from NED to sensor axes
+// Tns = Tbs*Tnb_local;
+
+// // calculate range from ground plain to centre of sensor fov assuming flat earth
+// float range = ConstrainFloat(((ptd - pd)/Tns.z.z),0.5f,100.0f);
+
+// // calculate relative velocity in sensor frame
+// relVelSensor = Tns*velNED_local;
+
+// // divide velocity by range and include angular rate effects to get predicted angular LOS rates relative to X and Y axes
+// losPred[0] = relVelSensor.y/range;
+// losPred[1] = -relVelSensor.x/range;
+
+// //printf("relVelSensor.x=%5.1f, relVelSensor.y=%5.1f\n", relVelSensor.x, relVelSensor.y);
+// //printf("Xpred=%5.2f, Xmea=%5.2f, Ypred=%5.2f, Ymea=%5.2f, delAng.x=%4.4f, delAng.y=%4.4f\n", losPred[0], losData[0], losPred[1], losData[1], delAng.x, delAng.y);
+// //printf("omegaX=%5.2f, omegaY=%5.2f, velY=%5.1f velX=%5.1f\n, range=%5.1f\n", delAngRel.x/dt, delAngRel.y/dt, relVelSensor.y, relVelSensor.x, range);
+
+// // Calculate observation jacobians
+// SH_LOS[0] = a1*(2*q0*q1 + 2*q2*q3) + a2*(2*q0*q2 - 2*q1*q3) - sq(q0) + sq(q1) + sq(q2) - sq(q3);
+// SH_LOS[1] = vd*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3)) - ve*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3)) + vn*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3));
+// SH_LOS[2] = ve*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3)) - vd*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3)) + vn*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3));
+// SH_LOS[3] = 1/(pd - ptd);
+// SH_LOS[4] = 2*q1 - 2*a2*q3 + 2*a3*q2;
+// SH_LOS[5] = 2*a2*q2 - 2*q0 + 2*a3*q3;
+// SH_LOS[6] = 2*q2 + 2*a2*q0 - 2*a3*q1;
+// SH_LOS[7] = 1/sq(pd - ptd);
+// SH_LOS[8] = 2*q2 + 2*a1*q3 - 2*a3*q1;
+// SH_LOS[9] = 2*q3 - 2*a1*q2 + 2*a3*q0;
+// SH_LOS[10] = 2*a1*q1 - 2*q0 + 2*a3*q3;
+// SH_LOS[11] = 2*q3 + 2*a2*q1 + 2*a3*q0;
+// SH_LOS[12] = 2*q1 + 2*a1*q0 + 2*a3*q2;
+
+// for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0;
+// H_LOS[0] = - SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]);
+// H_LOS[1] = - SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]);
+// H_LOS[2] = SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]) - SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3);
+// H_LOS[3] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]);
+// H_LOS[4] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3));
+// H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3));
+// H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3));
+// H_LOS[9] = SH_LOS[0]*SH_LOS[2]*SH_LOS[7];
+// H_LOS[22] = -SH_LOS[0]*SH_LOS[2]*SH_LOS[7];
+
+// // Calculate Kalman gain
+// SKK_LOS[0] = a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3);
+// SKK_LOS[1] = a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3);
+// SKK_LOS[2] = a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3);
+// SKK_LOS[3] = a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3);
+// SKK_LOS[4] = a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3);
+// SKK_LOS[5] = a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3);
+// SKK_LOS[6] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]);
+// SKK_LOS[7] = SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]);
+// SKK_LOS[8] = SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]);
+// SKK_LOS[9] = SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]);
+// SKK_LOS[10] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]);
+// SKK_LOS[11] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]);
+// SKK_LOS[12] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]);
+// SKK_LOS[13] = SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]);
+// SKK_LOS[14] = SH_LOS[0];
+
+// SK_LOS[0] = 1/(R_LOS + SKK_LOS[8]*(P[0][0]*SKK_LOS[8] + P[1][0]*SKK_LOS[7] + P[2][0]*SKK_LOS[9] - P[3][0]*SKK_LOS[6] - P[9][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][0]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][0]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[7]*(P[0][1]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] + P[2][1]*SKK_LOS[9] - P[3][1]*SKK_LOS[6] - P[9][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][1]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][1]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[9]*(P[0][2]*SKK_LOS[8] + P[1][2]*SKK_LOS[7] + P[2][2]*SKK_LOS[9] - P[3][2]*SKK_LOS[6] - P[9][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][2]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][2]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SKK_LOS[6]*(P[0][3]*SKK_LOS[8] + P[1][3]*SKK_LOS[7] + P[2][3]*SKK_LOS[9] - P[3][3]*SKK_LOS[6] - P[9][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][3]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][3]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[8] + P[1][9]*SKK_LOS[7] + P[2][9]*SKK_LOS[9] - P[3][9]*SKK_LOS[6] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][9]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][9]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[8] + P[1][22]*SKK_LOS[7] + P[2][22]*SKK_LOS[9] - P[3][22]*SKK_LOS[6] - P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][22]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][22]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14]*(P[0][4]*SKK_LOS[8] + P[1][4]*SKK_LOS[7] + P[2][4]*SKK_LOS[9] - P[3][4]*SKK_LOS[6] - P[9][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][4]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14]*(P[0][5]*SKK_LOS[8] + P[1][5]*SKK_LOS[7] + P[2][5]*SKK_LOS[9] - P[3][5]*SKK_LOS[6] - P[9][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]*(P[0][6]*SKK_LOS[8] + P[1][6]*SKK_LOS[7] + P[2][6]*SKK_LOS[9] - P[3][6]*SKK_LOS[6] - P[9][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]));
+// Kfusion[0] = -SK_LOS[0]*(P[0][0]*SKK_LOS[8] + P[0][1]*SKK_LOS[7] - P[0][3]*SKK_LOS[6] + P[0][2]*SKK_LOS[9] - P[0][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[0][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[0][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[1] = -SK_LOS[0]*(P[1][0]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] - P[1][3]*SKK_LOS[6] + P[1][2]*SKK_LOS[9] - P[1][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[1][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[1][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[2] = -SK_LOS[0]*(P[2][0]*SKK_LOS[8] + P[2][1]*SKK_LOS[7] - P[2][3]*SKK_LOS[6] + P[2][2]*SKK_LOS[9] - P[2][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[2][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[2][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[3] = -SK_LOS[0]*(P[3][0]*SKK_LOS[8] + P[3][1]*SKK_LOS[7] - P[3][3]*SKK_LOS[6] + P[3][2]*SKK_LOS[9] - P[3][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[3][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[3][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[4] = -SK_LOS[0]*(P[4][0]*SKK_LOS[8] + P[4][1]*SKK_LOS[7] - P[4][3]*SKK_LOS[6] + P[4][2]*SKK_LOS[9] - P[4][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[4][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[5] = -SK_LOS[0]*(P[5][0]*SKK_LOS[8] + P[5][1]*SKK_LOS[7] - P[5][3]*SKK_LOS[6] + P[5][2]*SKK_LOS[9] - P[5][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[6] = -SK_LOS[0]*(P[6][0]*SKK_LOS[8] + P[6][1]*SKK_LOS[7] - P[6][3]*SKK_LOS[6] + P[6][2]*SKK_LOS[9] - P[6][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[7] = -SK_LOS[0]*(P[7][0]*SKK_LOS[8] + P[7][1]*SKK_LOS[7] - P[7][3]*SKK_LOS[6] + P[7][2]*SKK_LOS[9] - P[7][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[7][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[7][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[8] = -SK_LOS[0]*(P[8][0]*SKK_LOS[8] + P[8][1]*SKK_LOS[7] - P[8][3]*SKK_LOS[6] + P[8][2]*SKK_LOS[9] - P[8][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[8][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[8][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[9] = -SK_LOS[0]*(P[9][0]*SKK_LOS[8] + P[9][1]*SKK_LOS[7] - P[9][3]*SKK_LOS[6] + P[9][2]*SKK_LOS[9] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[9][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[9][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[10] = -SK_LOS[0]*(P[10][0]*SKK_LOS[8] + P[10][1]*SKK_LOS[7] - P[10][3]*SKK_LOS[6] + P[10][2]*SKK_LOS[9] - P[10][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[10][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[10][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[11] = -SK_LOS[0]*(P[11][0]*SKK_LOS[8] + P[11][1]*SKK_LOS[7] - P[11][3]*SKK_LOS[6] + P[11][2]*SKK_LOS[9] - P[11][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[11][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[11][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[12] = -SK_LOS[0]*(P[12][0]*SKK_LOS[8] + P[12][1]*SKK_LOS[7] - P[12][3]*SKK_LOS[6] + P[12][2]*SKK_LOS[9] - P[12][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[12][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[12][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[13] = 0.0f;//-SK_LOS[0]*(P[13][0]*SKK_LOS[8] + P[13][1]*SKK_LOS[7] - P[13][3]*SKK_LOS[6] + P[13][2]*SKK_LOS[9] - P[13][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[13][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[13][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[14] = -SK_LOS[0]*(P[14][0]*SKK_LOS[8] + P[14][1]*SKK_LOS[7] - P[14][3]*SKK_LOS[6] + P[14][2]*SKK_LOS[9] - P[14][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[14][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[14][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[15] = -SK_LOS[0]*(P[15][0]*SKK_LOS[8] + P[15][1]*SKK_LOS[7] - P[15][3]*SKK_LOS[6] + P[15][2]*SKK_LOS[9] - P[15][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[15][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[15][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[16] = -SK_LOS[0]*(P[16][0]*SKK_LOS[8] + P[16][1]*SKK_LOS[7] - P[16][3]*SKK_LOS[6] + P[16][2]*SKK_LOS[9] - P[16][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[16][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[16][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[17] = -SK_LOS[0]*(P[17][0]*SKK_LOS[8] + P[17][1]*SKK_LOS[7] - P[17][3]*SKK_LOS[6] + P[17][2]*SKK_LOS[9] - P[17][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[17][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[17][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[18] = -SK_LOS[0]*(P[18][0]*SKK_LOS[8] + P[18][1]*SKK_LOS[7] - P[18][3]*SKK_LOS[6] + P[18][2]*SKK_LOS[9] - P[18][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[18][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[18][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[19] = -SK_LOS[0]*(P[19][0]*SKK_LOS[8] + P[19][1]*SKK_LOS[7] - P[19][3]*SKK_LOS[6] + P[19][2]*SKK_LOS[9] - P[19][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[19][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[19][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[20] = -SK_LOS[0]*(P[20][0]*SKK_LOS[8] + P[20][1]*SKK_LOS[7] - P[20][3]*SKK_LOS[6] + P[20][2]*SKK_LOS[9] - P[20][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[20][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[20][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[21] = -SK_LOS[0]*(P[21][0]*SKK_LOS[8] + P[21][1]*SKK_LOS[7] - P[21][3]*SKK_LOS[6] + P[21][2]*SKK_LOS[9] - P[21][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[21][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[21][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// Kfusion[22] = -SK_LOS[0]*(P[22][0]*SKK_LOS[8] + P[22][1]*SKK_LOS[7] - P[22][3]*SKK_LOS[6] + P[22][2]*SKK_LOS[9] - P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[22][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[22][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+// varInnovOptFlow[0] = 1.0f/SK_LOS[0];
+// innovOptFlow[0] = losPred[0] - losData[0];
+
+// // set the observation index to 1 to fuse the y component next time round and reset the commence fusion flag
+// obsIndex = 1;
+// fuseOptFlowData = false;
+// }
+// else if (obsIndex == 1) // we are now fusing the Y measurement
+// {
+// // Calculate observation jacobians
+// for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0;
+// H_LOS[0] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]);
+// H_LOS[1] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]);
+// H_LOS[2] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]);
+// H_LOS[3] = SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]) - SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1);
+// H_LOS[4] = SH_LOS[0]*SH_LOS[3]*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3));
+// H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3));
+// H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3));
+// H_LOS[9] = -SH_LOS[0]*SH_LOS[1]*SH_LOS[7];
+// H_LOS[22] = SH_LOS[0]*SH_LOS[1]*SH_LOS[7];
+
+// // Calculate Kalman gains
+// SK_LOS[1] = 1/(R_LOS + SKK_LOS[12]*(P[0][2]*SKK_LOS[10] + P[1][2]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[3][2]*SKK_LOS[13] - P[9][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][2]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][2]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SKK_LOS[13]*(P[0][3]*SKK_LOS[10] + P[1][3]*SKK_LOS[11] + P[2][3]*SKK_LOS[12] - P[3][3]*SKK_LOS[13] - P[9][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][3]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][3]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[10]*(P[0][0]*SKK_LOS[10] + P[1][0]*SKK_LOS[11] + P[2][0]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][0]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][0]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][0]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[11]*(P[0][1]*SKK_LOS[10] + P[1][1]*SKK_LOS[11] + P[2][1]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][1]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][1]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][1]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[10] + P[1][9]*SKK_LOS[11] + P[2][9]*SKK_LOS[12] - P[3][9]*SKK_LOS[13] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][9]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][9]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[10] + P[1][22]*SKK_LOS[11] + P[2][22]*SKK_LOS[12] - P[3][22]*SKK_LOS[13] - P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][22]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][22]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14]*(P[0][4]*SKK_LOS[10] + P[1][4]*SKK_LOS[11] + P[2][4]*SKK_LOS[12] - P[3][4]*SKK_LOS[13] - P[9][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][4]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]*(P[0][5]*SKK_LOS[10] + P[1][5]*SKK_LOS[11] + P[2][5]*SKK_LOS[12] - P[3][5]*SKK_LOS[13] - P[9][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]*(P[0][6]*SKK_LOS[10] + P[1][6]*SKK_LOS[11] + P[2][6]*SKK_LOS[12] - P[3][6]*SKK_LOS[13] - P[9][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]));
+// Kfusion[0] = SK_LOS[1]*(P[0][0]*SKK_LOS[10] - P[0][3]*SKK_LOS[13] + P[0][1]*SKK_LOS[11] + P[0][2]*SKK_LOS[12] - P[0][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[0][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[1] = SK_LOS[1]*(P[1][0]*SKK_LOS[10] - P[1][3]*SKK_LOS[13] + P[1][1]*SKK_LOS[11] + P[1][2]*SKK_LOS[12] - P[1][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[1][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[2] = SK_LOS[1]*(P[2][0]*SKK_LOS[10] - P[2][3]*SKK_LOS[13] + P[2][1]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[2][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[2][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[3] = SK_LOS[1]*(P[3][0]*SKK_LOS[10] - P[3][3]*SKK_LOS[13] + P[3][1]*SKK_LOS[11] + P[3][2]*SKK_LOS[12] - P[3][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[3][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[4] = SK_LOS[1]*(P[4][0]*SKK_LOS[10] - P[4][3]*SKK_LOS[13] + P[4][1]*SKK_LOS[11] + P[4][2]*SKK_LOS[12] - P[4][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[4][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[5] = SK_LOS[1]*(P[5][0]*SKK_LOS[10] - P[5][3]*SKK_LOS[13] + P[5][1]*SKK_LOS[11] + P[5][2]*SKK_LOS[12] - P[5][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[6] = SK_LOS[1]*(P[6][0]*SKK_LOS[10] - P[6][3]*SKK_LOS[13] + P[6][1]*SKK_LOS[11] + P[6][2]*SKK_LOS[12] - P[6][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[7] = SK_LOS[1]*(P[7][0]*SKK_LOS[10] - P[7][3]*SKK_LOS[13] + P[7][1]*SKK_LOS[11] + P[7][2]*SKK_LOS[12] - P[7][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[7][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[8] = SK_LOS[1]*(P[8][0]*SKK_LOS[10] - P[8][3]*SKK_LOS[13] + P[8][1]*SKK_LOS[11] + P[8][2]*SKK_LOS[12] - P[8][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[8][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[9] = SK_LOS[1]*(P[9][0]*SKK_LOS[10] - P[9][3]*SKK_LOS[13] + P[9][1]*SKK_LOS[11] + P[9][2]*SKK_LOS[12] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[9][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[10] = SK_LOS[1]*(P[10][0]*SKK_LOS[10] - P[10][3]*SKK_LOS[13] + P[10][1]*SKK_LOS[11] + P[10][2]*SKK_LOS[12] - P[10][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[10][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[11] = SK_LOS[1]*(P[11][0]*SKK_LOS[10] - P[11][3]*SKK_LOS[13] + P[11][1]*SKK_LOS[11] + P[11][2]*SKK_LOS[12] - P[11][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[11][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[12] = SK_LOS[1]*(P[12][0]*SKK_LOS[10] - P[12][3]*SKK_LOS[13] + P[12][1]*SKK_LOS[11] + P[12][2]*SKK_LOS[12] - P[12][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[12][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[13] = 0.0f;//SK_LOS[1]*(P[13][0]*SKK_LOS[10] - P[13][3]*SKK_LOS[13] + P[13][1]*SKK_LOS[11] + P[13][2]*SKK_LOS[12] - P[13][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[13][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[14] = SK_LOS[1]*(P[14][0]*SKK_LOS[10] - P[14][3]*SKK_LOS[13] + P[14][1]*SKK_LOS[11] + P[14][2]*SKK_LOS[12] - P[14][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[14][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[15] = SK_LOS[1]*(P[15][0]*SKK_LOS[10] - P[15][3]*SKK_LOS[13] + P[15][1]*SKK_LOS[11] + P[15][2]*SKK_LOS[12] - P[15][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[15][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[16] = SK_LOS[1]*(P[16][0]*SKK_LOS[10] - P[16][3]*SKK_LOS[13] + P[16][1]*SKK_LOS[11] + P[16][2]*SKK_LOS[12] - P[16][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[16][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[17] = SK_LOS[1]*(P[17][0]*SKK_LOS[10] - P[17][3]*SKK_LOS[13] + P[17][1]*SKK_LOS[11] + P[17][2]*SKK_LOS[12] - P[17][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[17][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[18] = SK_LOS[1]*(P[18][0]*SKK_LOS[10] - P[18][3]*SKK_LOS[13] + P[18][1]*SKK_LOS[11] + P[18][2]*SKK_LOS[12] - P[18][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[18][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[19] = SK_LOS[1]*(P[19][0]*SKK_LOS[10] - P[19][3]*SKK_LOS[13] + P[19][1]*SKK_LOS[11] + P[19][2]*SKK_LOS[12] - P[19][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[19][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[20] = SK_LOS[1]*(P[20][0]*SKK_LOS[10] - P[20][3]*SKK_LOS[13] + P[20][1]*SKK_LOS[11] + P[20][2]*SKK_LOS[12] - P[20][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[20][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[21] = SK_LOS[1]*(P[21][0]*SKK_LOS[10] - P[21][3]*SKK_LOS[13] + P[21][1]*SKK_LOS[11] + P[21][2]*SKK_LOS[12] - P[21][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[21][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// Kfusion[22] = SK_LOS[1]*(P[22][0]*SKK_LOS[10] - P[22][3]*SKK_LOS[13] + P[22][1]*SKK_LOS[11] + P[22][2]*SKK_LOS[12] - P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[22][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+// varInnovOptFlow[1] = 1.0f/SK_LOS[1];
+// innovOptFlow[1] = losPred[1] - losData[1];
+
+// // reset the observation index
+// obsIndex = 0;
+// fuseOptFlowData = false;
+// }
+
+// // Check the innovation for consistency and don't fuse if > 3Sigma
+// if ((innovOptFlow[obsIndex]*innovOptFlow[obsIndex]/varInnovOptFlow[obsIndex]) < 9.0f)
+// {
+// // correct the state vector
+// for (uint8_t j = 0; j < n_states; j++)
+// {
+// states[j] = states[j] - Kfusion[j] * innovOptFlow[obsIndex];
+// }
+// // normalise the quaternion states
+// float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
+// if (quatMag > 1e-12f)
+// {
+// for (uint8_t j= 0; j<=3; j++)
+// {
+// float quatMagInv = 1.0f/quatMag;
+// states[j] = states[j] * quatMagInv;
+// }
+// }
+// // correct the covariance P = (I - K*H)*P
+// // take advantage of the empty columns in KH to reduce the
+// // number of operations
+// for (uint8_t i = 0; i < n_states; i++)
+// {
+// for (uint8_t j = 0; j <= 6; j++)
+// {
+// KH[i][j] = Kfusion[i] * H_LOS[j];
+// }
+// for (uint8_t j = 7; j <= 8; j++)
+// {
+// KH[i][j] = 0.0f;
+// }
+// KH[i][9] = Kfusion[i] * H_LOS[9];
+// for (uint8_t j = 10; j <= 21; j++)
+// {
+// KH[i][j] = 0.0f;
+// }
+// KH[i][22] = Kfusion[i] * H_LOS[22];
+// }
+// for (uint8_t i = 0; i < n_states; i++)
+// {
+// for (uint8_t j = 0; j < n_states; j++)
+// {
+// KHP[i][j] = 0.0f;
+// for (uint8_t k = 0; k <= 6; k++)
+// {
+// KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
+// }
+// KHP[i][j] = KHP[i][j] + KH[i][9] * P[9][j];
+// KHP[i][j] = KHP[i][j] + KH[i][22] * P[2][j];
+// }
+// }
+// }
+// for (uint8_t i = 0; i < n_states; i++)
+// {
+// for (uint8_t j = 0; j < n_states; j++)
+// {
+// P[i][j] = P[i][j] - KHP[i][j];
+// }
+// }
+// ForceSymmetry();
+// ConstrainVariances();
+// }
+}
-// Perform sequential fusion of optical flow measurements only when in the air and tilt is less than 30 deg.
- if (useOpticalFlow && (fuseOptFlowData || obsIndex == 1) && !onGround && Tbs.z.z > 0.866f && rngMea > 5.0f && rngMea < 39.0f)
- {
- // Sequential fusion of XY components to spread processing load across
- // two prediction time steps.
+/*
+Estimation of optical flow sensor focal length scale factor and terrain height using a two state EKF
+This fiter requires optical flow rates that are not motion compensated
+Range to ground measurement is assumed to be via a narrow beam type sensor - eg laser
+*/
+void AttPosEKF::GroundEKF()
+{
+ // propagate ground position state noise each time this is called using the difference in position since the last observations and an RMS gradient assumption
+ // limit distance to prevent intialisation afer bad gps causing bad numerical conditioning
+ if (!inhibitGndState) {
+ float distanceTravelledSq;
+ distanceTravelledSq = sq(statesAtRngTime[7] - prevPosN) + sq(statesAtRngTime[8] - prevPosE);
+ prevPosN = statesAtRngTime[7];
+ prevPosE = statesAtRngTime[8];
+ distanceTravelledSq = min(distanceTravelledSq, 100.0f);
+ Popt[1][1] += (distanceTravelledSq * sq(gndHgtSigma));
+ }
+ // we aren't using optical flow measurements in this hacked implementation so set the covariances for this state to zero to avoid numerical problems
+ Popt[0][0] = 0.0f;
+ Popt[0][1] = 0.0f;
+ Popt[1][0] = 0.0f;
+
+ // Fuse range finder data
+ // Need to check that our range finder tilt angle is less than 30 degrees
+ float cosRngTilt = - Tbn.z.x * sinf(rngFinderPitch) + Tbn.z.z * cosf(rngFinderPitch);
+ if (useRangeFinder && fuseRngData && cosRngTilt > 0.87f) {
+ float range; // range from camera to centre of image
+ float q0; // quaternion at optical flow measurement time
+ float q1; // quaternion at optical flow measurement time
+ float q2; // quaternion at optical flow measurement time
+ float q3; // quaternion at optical flow measurement time
+ float R_RNG = 0.5; // range measurement variance (m^2) TODO make this a function of range and tilt to allow for sensor, alignment and AHRS errors
+
+ // Copy required states to local variable names
+ q0 = statesAtRngTime[0];
+ q1 = statesAtRngTime[1];
+ q2 = statesAtRngTime[2];
+ q3 = statesAtRngTime[3];
+
+ // calculate Kalman gains
+ float SK_RNG[3];
+ SK_RNG[0] = sq(q0) - sq(q1) - sq(q2) + sq(q3);
+ SK_RNG[1] = 1/(R_RNG + Popt[1][1]/sq(SK_RNG[0]));
+ SK_RNG[2] = 1/SK_RNG[0];
+ float K_RNG[2];
+ if (!inhibitScaleState) {
+ K_RNG[0] = Popt[0][1]*SK_RNG[1]*SK_RNG[2];
+ } else {
+ K_RNG[0] = 0.0f;
+ }
+ if (!inhibitGndState) {
+ K_RNG[1] = Popt[1][1]*SK_RNG[1]*SK_RNG[2];
+ } else {
+ K_RNG[1] = 0.0f;
+ }
- // Calculate observation jacobians and Kalman gains
- if (fuseOptFlowData)
- {
- // Copy required states to local variable names
- q0 = statesAtOptFlowTime[0];
- q1 = statesAtOptFlowTime[1];
- q2 = statesAtOptFlowTime[2];
- q3 = statesAtOptFlowTime[3];
- vn = statesAtOptFlowTime[4];
- ve = statesAtOptFlowTime[5];
- vd = statesAtOptFlowTime[6];
- pd = statesAtOptFlowTime[9];
- ptd = statesAtOptFlowTime[22];
- velNED_local.x = vn;
- velNED_local.y = ve;
- velNED_local.z = vd;
-
- // calculate rotation from NED to body axes
- float q00 = sq(q0);
- float q11 = sq(q1);
- float q22 = sq(q2);
- float q33 = sq(q3);
- float q01 = q0 * q1;
- float q02 = q0 * q2;
- float q03 = q0 * q3;
- float q12 = q1 * q2;
- float q13 = q1 * q3;
- float q23 = q2 * q3;
- Tnb_local.x.x = q00 + q11 - q22 - q33;
- Tnb_local.y.y = q00 - q11 + q22 - q33;
- Tnb_local.z.z = q00 - q11 - q22 + q33;
- Tnb_local.y.x = 2*(q12 - q03);
- Tnb_local.z.x = 2*(q13 + q02);
- Tnb_local.x.y = 2*(q12 + q03);
- Tnb_local.z.y = 2*(q23 - q01);
- Tnb_local.x.z = 2*(q13 - q02);
- Tnb_local.y.z = 2*(q23 + q01);
-
- // calculate transformation from NED to sensor axes
- Tns = Tbs*Tnb_local;
-
- // calculate range from ground plain to centre of sensor fov assuming flat earth
- float range = ConstrainFloat(((ptd - pd)/Tns.z.z),0.5f,100.0f);
-
- // calculate relative velocity in sensor frame
- relVelSensor = Tns*velNED_local;
-
- // divide velocity by range and include angular rate effects to get predicted angular LOS rates relative to X and Y axes
- losPred[0] = relVelSensor.y/range;
- losPred[1] = -relVelSensor.x/range;
-
- //printf("relVelSensor.x=%5.1f, relVelSensor.y=%5.1f\n", relVelSensor.x, relVelSensor.y);
- //printf("Xpred=%5.2f, Xmea=%5.2f, Ypred=%5.2f, Ymea=%5.2f, delAng.x=%4.4f, delAng.y=%4.4f\n", losPred[0], losData[0], losPred[1], losData[1], delAng.x, delAng.y);
- //printf("omegaX=%5.2f, omegaY=%5.2f, velY=%5.1f velX=%5.1f\n, range=%5.1f\n", delAngRel.x/dt, delAngRel.y/dt, relVelSensor.y, relVelSensor.x, range);
+ // Calculate the innovation variance for data logging
+ varInnovRng = 1.0f/SK_RNG[1];
- // Calculate observation jacobians
- SH_LOS[0] = a1*(2*q0*q1 + 2*q2*q3) + a2*(2*q0*q2 - 2*q1*q3) - sq(q0) + sq(q1) + sq(q2) - sq(q3);
- SH_LOS[1] = vd*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3)) - ve*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3)) + vn*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3));
- SH_LOS[2] = ve*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3)) - vd*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3)) + vn*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3));
- SH_LOS[3] = 1/(pd - ptd);
- SH_LOS[4] = 2*q1 - 2*a2*q3 + 2*a3*q2;
- SH_LOS[5] = 2*a2*q2 - 2*q0 + 2*a3*q3;
- SH_LOS[6] = 2*q2 + 2*a2*q0 - 2*a3*q1;
- SH_LOS[7] = 1/sq(pd - ptd);
- SH_LOS[8] = 2*q2 + 2*a1*q3 - 2*a3*q1;
- SH_LOS[9] = 2*q3 - 2*a1*q2 + 2*a3*q0;
- SH_LOS[10] = 2*a1*q1 - 2*q0 + 2*a3*q3;
- SH_LOS[11] = 2*q3 + 2*a2*q1 + 2*a3*q0;
- SH_LOS[12] = 2*q1 + 2*a1*q0 + 2*a3*q2;
-
- for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0;
- H_LOS[0] = - SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]);
- H_LOS[1] = - SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]);
- H_LOS[2] = SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]) - SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3);
- H_LOS[3] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]);
- H_LOS[4] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3));
- H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3));
- H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3));
- H_LOS[9] = SH_LOS[0]*SH_LOS[2]*SH_LOS[7];
- H_LOS[22] = -SH_LOS[0]*SH_LOS[2]*SH_LOS[7];
+ // constrain terrain height to be below the vehicle
+ flowStates[1] = maxf(flowStates[1], statesAtRngTime[9] + minFlowRng);
- // Calculate Kalman gain
- SKK_LOS[0] = a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3);
- SKK_LOS[1] = a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3);
- SKK_LOS[2] = a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3);
- SKK_LOS[3] = a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3);
- SKK_LOS[4] = a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3);
- SKK_LOS[5] = a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3);
- SKK_LOS[6] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]);
- SKK_LOS[7] = SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]);
- SKK_LOS[8] = SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]);
- SKK_LOS[9] = SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]);
- SKK_LOS[10] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]);
- SKK_LOS[11] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]);
- SKK_LOS[12] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]);
- SKK_LOS[13] = SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]);
- SKK_LOS[14] = SH_LOS[0];
-
- SK_LOS[0] = 1/(R_LOS + SKK_LOS[8]*(P[0][0]*SKK_LOS[8] + P[1][0]*SKK_LOS[7] + P[2][0]*SKK_LOS[9] - P[3][0]*SKK_LOS[6] - P[9][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][0]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][0]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[7]*(P[0][1]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] + P[2][1]*SKK_LOS[9] - P[3][1]*SKK_LOS[6] - P[9][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][1]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][1]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[9]*(P[0][2]*SKK_LOS[8] + P[1][2]*SKK_LOS[7] + P[2][2]*SKK_LOS[9] - P[3][2]*SKK_LOS[6] - P[9][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][2]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][2]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SKK_LOS[6]*(P[0][3]*SKK_LOS[8] + P[1][3]*SKK_LOS[7] + P[2][3]*SKK_LOS[9] - P[3][3]*SKK_LOS[6] - P[9][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][3]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][3]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[8] + P[1][9]*SKK_LOS[7] + P[2][9]*SKK_LOS[9] - P[3][9]*SKK_LOS[6] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][9]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][9]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[8] + P[1][22]*SKK_LOS[7] + P[2][22]*SKK_LOS[9] - P[3][22]*SKK_LOS[6] - P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][22]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][22]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14]*(P[0][4]*SKK_LOS[8] + P[1][4]*SKK_LOS[7] + P[2][4]*SKK_LOS[9] - P[3][4]*SKK_LOS[6] - P[9][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][4]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14]*(P[0][5]*SKK_LOS[8] + P[1][5]*SKK_LOS[7] + P[2][5]*SKK_LOS[9] - P[3][5]*SKK_LOS[6] - P[9][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]*(P[0][6]*SKK_LOS[8] + P[1][6]*SKK_LOS[7] + P[2][6]*SKK_LOS[9] - P[3][6]*SKK_LOS[6] - P[9][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]));
- Kfusion[0] = -SK_LOS[0]*(P[0][0]*SKK_LOS[8] + P[0][1]*SKK_LOS[7] - P[0][3]*SKK_LOS[6] + P[0][2]*SKK_LOS[9] - P[0][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[0][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[0][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[1] = -SK_LOS[0]*(P[1][0]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] - P[1][3]*SKK_LOS[6] + P[1][2]*SKK_LOS[9] - P[1][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[1][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[1][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[2] = -SK_LOS[0]*(P[2][0]*SKK_LOS[8] + P[2][1]*SKK_LOS[7] - P[2][3]*SKK_LOS[6] + P[2][2]*SKK_LOS[9] - P[2][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[2][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[2][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[3] = -SK_LOS[0]*(P[3][0]*SKK_LOS[8] + P[3][1]*SKK_LOS[7] - P[3][3]*SKK_LOS[6] + P[3][2]*SKK_LOS[9] - P[3][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[3][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[3][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[4] = -SK_LOS[0]*(P[4][0]*SKK_LOS[8] + P[4][1]*SKK_LOS[7] - P[4][3]*SKK_LOS[6] + P[4][2]*SKK_LOS[9] - P[4][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[4][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[5] = -SK_LOS[0]*(P[5][0]*SKK_LOS[8] + P[5][1]*SKK_LOS[7] - P[5][3]*SKK_LOS[6] + P[5][2]*SKK_LOS[9] - P[5][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[6] = -SK_LOS[0]*(P[6][0]*SKK_LOS[8] + P[6][1]*SKK_LOS[7] - P[6][3]*SKK_LOS[6] + P[6][2]*SKK_LOS[9] - P[6][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[7] = -SK_LOS[0]*(P[7][0]*SKK_LOS[8] + P[7][1]*SKK_LOS[7] - P[7][3]*SKK_LOS[6] + P[7][2]*SKK_LOS[9] - P[7][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[7][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[7][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[8] = -SK_LOS[0]*(P[8][0]*SKK_LOS[8] + P[8][1]*SKK_LOS[7] - P[8][3]*SKK_LOS[6] + P[8][2]*SKK_LOS[9] - P[8][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[8][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[8][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[9] = -SK_LOS[0]*(P[9][0]*SKK_LOS[8] + P[9][1]*SKK_LOS[7] - P[9][3]*SKK_LOS[6] + P[9][2]*SKK_LOS[9] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[9][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[9][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[10] = -SK_LOS[0]*(P[10][0]*SKK_LOS[8] + P[10][1]*SKK_LOS[7] - P[10][3]*SKK_LOS[6] + P[10][2]*SKK_LOS[9] - P[10][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[10][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[10][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[11] = -SK_LOS[0]*(P[11][0]*SKK_LOS[8] + P[11][1]*SKK_LOS[7] - P[11][3]*SKK_LOS[6] + P[11][2]*SKK_LOS[9] - P[11][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[11][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[11][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[12] = -SK_LOS[0]*(P[12][0]*SKK_LOS[8] + P[12][1]*SKK_LOS[7] - P[12][3]*SKK_LOS[6] + P[12][2]*SKK_LOS[9] - P[12][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[12][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[12][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[13] = 0.0f;//-SK_LOS[0]*(P[13][0]*SKK_LOS[8] + P[13][1]*SKK_LOS[7] - P[13][3]*SKK_LOS[6] + P[13][2]*SKK_LOS[9] - P[13][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[13][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[13][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[14] = -SK_LOS[0]*(P[14][0]*SKK_LOS[8] + P[14][1]*SKK_LOS[7] - P[14][3]*SKK_LOS[6] + P[14][2]*SKK_LOS[9] - P[14][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[14][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[14][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[15] = -SK_LOS[0]*(P[15][0]*SKK_LOS[8] + P[15][1]*SKK_LOS[7] - P[15][3]*SKK_LOS[6] + P[15][2]*SKK_LOS[9] - P[15][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[15][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[15][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[16] = -SK_LOS[0]*(P[16][0]*SKK_LOS[8] + P[16][1]*SKK_LOS[7] - P[16][3]*SKK_LOS[6] + P[16][2]*SKK_LOS[9] - P[16][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[16][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[16][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[17] = -SK_LOS[0]*(P[17][0]*SKK_LOS[8] + P[17][1]*SKK_LOS[7] - P[17][3]*SKK_LOS[6] + P[17][2]*SKK_LOS[9] - P[17][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[17][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[17][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[18] = -SK_LOS[0]*(P[18][0]*SKK_LOS[8] + P[18][1]*SKK_LOS[7] - P[18][3]*SKK_LOS[6] + P[18][2]*SKK_LOS[9] - P[18][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[18][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[18][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[19] = -SK_LOS[0]*(P[19][0]*SKK_LOS[8] + P[19][1]*SKK_LOS[7] - P[19][3]*SKK_LOS[6] + P[19][2]*SKK_LOS[9] - P[19][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[19][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[19][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[20] = -SK_LOS[0]*(P[20][0]*SKK_LOS[8] + P[20][1]*SKK_LOS[7] - P[20][3]*SKK_LOS[6] + P[20][2]*SKK_LOS[9] - P[20][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[20][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[20][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[21] = -SK_LOS[0]*(P[21][0]*SKK_LOS[8] + P[21][1]*SKK_LOS[7] - P[21][3]*SKK_LOS[6] + P[21][2]*SKK_LOS[9] - P[21][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[21][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[21][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- Kfusion[22] = -SK_LOS[0]*(P[22][0]*SKK_LOS[8] + P[22][1]*SKK_LOS[7] - P[22][3]*SKK_LOS[6] + P[22][2]*SKK_LOS[9] - P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[22][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[22][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
- varInnovOptFlow[0] = 1.0f/SK_LOS[0];
- innovOptFlow[0] = losPred[0] - losData[0];
-
- // reset the observation index to 0 (we start by fusing the X
- // measurement)
- obsIndex = 0;
- fuseOptFlowData = false;
- }
- else if (obsIndex == 1) // we are now fusing the Y measurement
- {
- // Calculate observation jacobians
- for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0;
- H_LOS[0] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]);
- H_LOS[1] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]);
- H_LOS[2] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]);
- H_LOS[3] = SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]) - SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1);
- H_LOS[4] = SH_LOS[0]*SH_LOS[3]*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3));
- H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3));
- H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3));
- H_LOS[9] = -SH_LOS[0]*SH_LOS[1]*SH_LOS[7];
- H_LOS[22] = SH_LOS[0]*SH_LOS[1]*SH_LOS[7];
-
- // Calculate Kalman gains
- SK_LOS[1] = 1/(R_LOS + SKK_LOS[12]*(P[0][2]*SKK_LOS[10] + P[1][2]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[3][2]*SKK_LOS[13] - P[9][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][2]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][2]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SKK_LOS[13]*(P[0][3]*SKK_LOS[10] + P[1][3]*SKK_LOS[11] + P[2][3]*SKK_LOS[12] - P[3][3]*SKK_LOS[13] - P[9][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][3]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][3]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[10]*(P[0][0]*SKK_LOS[10] + P[1][0]*SKK_LOS[11] + P[2][0]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][0]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][0]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][0]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[11]*(P[0][1]*SKK_LOS[10] + P[1][1]*SKK_LOS[11] + P[2][1]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][1]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][1]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][1]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[10] + P[1][9]*SKK_LOS[11] + P[2][9]*SKK_LOS[12] - P[3][9]*SKK_LOS[13] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][9]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][9]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[10] + P[1][22]*SKK_LOS[11] + P[2][22]*SKK_LOS[12] - P[3][22]*SKK_LOS[13] - P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][22]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][22]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14]*(P[0][4]*SKK_LOS[10] + P[1][4]*SKK_LOS[11] + P[2][4]*SKK_LOS[12] - P[3][4]*SKK_LOS[13] - P[9][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][4]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]*(P[0][5]*SKK_LOS[10] + P[1][5]*SKK_LOS[11] + P[2][5]*SKK_LOS[12] - P[3][5]*SKK_LOS[13] - P[9][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]*(P[0][6]*SKK_LOS[10] + P[1][6]*SKK_LOS[11] + P[2][6]*SKK_LOS[12] - P[3][6]*SKK_LOS[13] - P[9][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]));
- Kfusion[0] = SK_LOS[1]*(P[0][0]*SKK_LOS[10] - P[0][3]*SKK_LOS[13] + P[0][1]*SKK_LOS[11] + P[0][2]*SKK_LOS[12] - P[0][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[0][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[1] = SK_LOS[1]*(P[1][0]*SKK_LOS[10] - P[1][3]*SKK_LOS[13] + P[1][1]*SKK_LOS[11] + P[1][2]*SKK_LOS[12] - P[1][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[1][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[2] = SK_LOS[1]*(P[2][0]*SKK_LOS[10] - P[2][3]*SKK_LOS[13] + P[2][1]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[2][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[2][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[3] = SK_LOS[1]*(P[3][0]*SKK_LOS[10] - P[3][3]*SKK_LOS[13] + P[3][1]*SKK_LOS[11] + P[3][2]*SKK_LOS[12] - P[3][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[3][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[4] = SK_LOS[1]*(P[4][0]*SKK_LOS[10] - P[4][3]*SKK_LOS[13] + P[4][1]*SKK_LOS[11] + P[4][2]*SKK_LOS[12] - P[4][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[4][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[5] = SK_LOS[1]*(P[5][0]*SKK_LOS[10] - P[5][3]*SKK_LOS[13] + P[5][1]*SKK_LOS[11] + P[5][2]*SKK_LOS[12] - P[5][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[6] = SK_LOS[1]*(P[6][0]*SKK_LOS[10] - P[6][3]*SKK_LOS[13] + P[6][1]*SKK_LOS[11] + P[6][2]*SKK_LOS[12] - P[6][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[7] = SK_LOS[1]*(P[7][0]*SKK_LOS[10] - P[7][3]*SKK_LOS[13] + P[7][1]*SKK_LOS[11] + P[7][2]*SKK_LOS[12] - P[7][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[7][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[8] = SK_LOS[1]*(P[8][0]*SKK_LOS[10] - P[8][3]*SKK_LOS[13] + P[8][1]*SKK_LOS[11] + P[8][2]*SKK_LOS[12] - P[8][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[8][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[9] = SK_LOS[1]*(P[9][0]*SKK_LOS[10] - P[9][3]*SKK_LOS[13] + P[9][1]*SKK_LOS[11] + P[9][2]*SKK_LOS[12] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[9][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[10] = SK_LOS[1]*(P[10][0]*SKK_LOS[10] - P[10][3]*SKK_LOS[13] + P[10][1]*SKK_LOS[11] + P[10][2]*SKK_LOS[12] - P[10][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[10][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[11] = SK_LOS[1]*(P[11][0]*SKK_LOS[10] - P[11][3]*SKK_LOS[13] + P[11][1]*SKK_LOS[11] + P[11][2]*SKK_LOS[12] - P[11][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[11][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[12] = SK_LOS[1]*(P[12][0]*SKK_LOS[10] - P[12][3]*SKK_LOS[13] + P[12][1]*SKK_LOS[11] + P[12][2]*SKK_LOS[12] - P[12][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[12][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[13] = 0.0f;//SK_LOS[1]*(P[13][0]*SKK_LOS[10] - P[13][3]*SKK_LOS[13] + P[13][1]*SKK_LOS[11] + P[13][2]*SKK_LOS[12] - P[13][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[13][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[14] = SK_LOS[1]*(P[14][0]*SKK_LOS[10] - P[14][3]*SKK_LOS[13] + P[14][1]*SKK_LOS[11] + P[14][2]*SKK_LOS[12] - P[14][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[14][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[15] = SK_LOS[1]*(P[15][0]*SKK_LOS[10] - P[15][3]*SKK_LOS[13] + P[15][1]*SKK_LOS[11] + P[15][2]*SKK_LOS[12] - P[15][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[15][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[16] = SK_LOS[1]*(P[16][0]*SKK_LOS[10] - P[16][3]*SKK_LOS[13] + P[16][1]*SKK_LOS[11] + P[16][2]*SKK_LOS[12] - P[16][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[16][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[17] = SK_LOS[1]*(P[17][0]*SKK_LOS[10] - P[17][3]*SKK_LOS[13] + P[17][1]*SKK_LOS[11] + P[17][2]*SKK_LOS[12] - P[17][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[17][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[18] = SK_LOS[1]*(P[18][0]*SKK_LOS[10] - P[18][3]*SKK_LOS[13] + P[18][1]*SKK_LOS[11] + P[18][2]*SKK_LOS[12] - P[18][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[18][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[19] = SK_LOS[1]*(P[19][0]*SKK_LOS[10] - P[19][3]*SKK_LOS[13] + P[19][1]*SKK_LOS[11] + P[19][2]*SKK_LOS[12] - P[19][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[19][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[20] = SK_LOS[1]*(P[20][0]*SKK_LOS[10] - P[20][3]*SKK_LOS[13] + P[20][1]*SKK_LOS[11] + P[20][2]*SKK_LOS[12] - P[20][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[20][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[21] = SK_LOS[1]*(P[21][0]*SKK_LOS[10] - P[21][3]*SKK_LOS[13] + P[21][1]*SKK_LOS[11] + P[21][2]*SKK_LOS[12] - P[21][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[21][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- Kfusion[22] = SK_LOS[1]*(P[22][0]*SKK_LOS[10] - P[22][3]*SKK_LOS[13] + P[22][1]*SKK_LOS[11] + P[22][2]*SKK_LOS[12] - P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[22][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
- varInnovOptFlow[1] = 1.0f/SK_LOS[1];
- innovOptFlow[1] = losPred[1] - losData[1];
- }
+ // estimate range to centre of image
+ range = (flowStates[1] - statesAtRngTime[9]) * SK_RNG[2];
- // Check the innovation for consistency and don't fuse if > 3Sigma
- if ((innovOptFlow[obsIndex]*innovOptFlow[obsIndex]/varInnovOptFlow[obsIndex]) < 9.0f)
- {
- // correct the state vector
- for (uint8_t j = 0; j < n_states; j++)
- {
- states[j] = states[j] - Kfusion[j] * innovOptFlow[obsIndex];
- }
- // normalise the quaternion states
- float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
- if (quatMag > 1e-12f)
- {
- for (uint8_t j= 0; j<=3; j++)
- {
- float quatMagInv = 1.0f/quatMag;
- states[j] = states[j] * quatMagInv;
- }
- }
- // correct the covariance P = (I - K*H)*P
- // take advantage of the empty columns in KH to reduce the
- // number of operations
- for (uint8_t i = 0; i < n_states; i++)
- {
- for (uint8_t j = 0; j <= 6; j++)
- {
- KH[i][j] = Kfusion[i] * H_LOS[j];
- }
- for (uint8_t j = 7; j <= 8; j++)
- {
- KH[i][j] = 0.0f;
- }
- KH[i][9] = Kfusion[i] * H_LOS[9];
- for (uint8_t j = 10; j <= 21; j++)
- {
- KH[i][j] = 0.0f;
- }
- KH[i][22] = Kfusion[i] * H_LOS[22];
- }
- for (uint8_t i = 0; i < n_states; i++)
- {
- for (uint8_t j = 0; j < n_states; j++)
- {
- KHP[i][j] = 0.0f;
- for (uint8_t k = 0; k <= 6; k++)
- {
- KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
- }
- KHP[i][j] = KHP[i][j] + KH[i][9] * P[9][j];
- KHP[i][j] = KHP[i][j] + KH[i][22] * P[2][j];
- }
- }
- }
- for (uint8_t i = 0; i < n_states; i++)
+ // Calculate the measurement innovation
+ innovRng = range - rngMea;
+
+ // calculate the innovation consistency test ratio
+ auxRngTestRatio = sq(innovRng) / (sq(rngInnovGate) * varInnovRng);
+
+ // Check the innovation for consistency and don't fuse if out of bounds
+ if (auxRngTestRatio < 1.0f)
{
- for (uint8_t j = 0; j < n_states; j++)
- {
- P[i][j] = P[i][j] - KHP[i][j];
+ // correct the state
+ for (uint8_t i = 0; i < 2 ; i++) {
+ flowStates[i] -= K_RNG[i] * innovRng;
}
+ // constrain the states
+
+ // constrain focal length to 0.1 to 10 mm
+ flowStates[0] = ConstrainFloat(flowStates[0], 0.1f, 10.0f);
+ // constrain altitude
+ flowStates[1] = maxf(flowStates[1], statesAtRngTime[9] + minFlowRng);
+
+ // correct the covariance matrix
+ float nextPopt[2][2];
+ nextPopt[0][0] = Popt[0][0] - (Popt[0][1]*Popt[1][0]*SK_RNG[1]*SK_RNG[2]) * SK_RNG[2];
+ nextPopt[0][1] = Popt[0][1] - (Popt[0][1]*Popt[1][1]*SK_RNG[1]*SK_RNG[2]) * SK_RNG[2];
+ nextPopt[1][0] = -Popt[1][0]*((Popt[1][1]*SK_RNG[1]*SK_RNG[2]) * SK_RNG[2] - 1.0f);
+ nextPopt[1][1] = -Popt[1][1]*((Popt[1][1]*SK_RNG[1]*SK_RNG[2]) * SK_RNG[2] - 1.0f);
+ // prevent the state variances from becoming negative and maintain symmetry
+ Popt[0][0] = maxf(nextPopt[0][0],0.0f);
+ Popt[1][1] = maxf(nextPopt[1][1],0.0f);
+ Popt[0][1] = 0.5f * (nextPopt[0][1] + nextPopt[1][0]);
+ Popt[1][0] = Popt[0][1];
}
}
- obsIndex = obsIndex + 1;
- ForceSymmetry();
- ConstrainVariances();
}
void AttPosEKF::zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last)
@@ -2101,6 +2305,24 @@ float AttPosEKF::sq(float valIn)
return valIn*valIn;
}
+float AttPosEKF::maxf(float valIn1, float valIn2)
+{
+ if (valIn1 >= valIn2) {
+ return valIn1;
+ } else {
+ return valIn2;
+ }
+}
+
+float AttPosEKF::min(float valIn1, float valIn2)
+{
+ if (valIn1 <= valIn2) {
+ return valIn1;
+ } else {
+ return valIn2;
+ }
+}
+
// Store states in a history array along with time stamp
void AttPosEKF::StoreStates(uint64_t timestamp_ms)
{
@@ -2297,9 +2519,9 @@ void AttPosEKF::OnGroundCheck()
}
// don't update terrain offset state if on ground
if (onGround) {
- inhibitGndHgtState = true;
+ inhibitGndState = true;
} else {
- inhibitGndHgtState = false;
+ inhibitGndState = false;
}
}
@@ -2339,15 +2561,15 @@ void AttPosEKF::CovarianceInit()
P[22][22] = sq(0.5f);
}
-float AttPosEKF::ConstrainFloat(float val, float min, float max)
+float AttPosEKF::ConstrainFloat(float val, float min_val, float max_val)
{
float ret;
- if (val > max) {
- ret = max;
- ekf_debug("> max: %8.4f, val: %8.4f", (double)max, (double)val);
- } else if (val < min) {
- ret = min;
- ekf_debug("< min: %8.4f, val: %8.4f", (double)min, (double)val);
+ if (val > max_val) {
+ ret = max_val;
+ ekf_debug("> max: %8.4f, val: %8.4f", (double)max_val, (double)val);
+ } else if (val < min_val) {
+ ret = min_val;
+ ekf_debug("< min: %8.4f, val: %8.4f", (double)min_val, (double)val);
} else {
ret = val;
}
@@ -2981,9 +3203,14 @@ void AttPosEKF::ZeroVariables()
{
// Initialize on-init initialized variables
-
+ dtIMUfilt = ConstrainFloat(dtIMU, 0.001f, 0.02f);
+ dtVelPosFilt = ConstrainFloat(dtVelPos, 0.04f, 0.5f);
+ dtGpsFilt = 1.0f / 5.0f;
+ dtHgtFilt = 1.0f / 100.0f;
storeIndex = 0;
+ lastVelPosFusion = millis();
+
// Do the data structure init
for (unsigned i = 0; i < n_states; i++) {
for (unsigned j = 0; j < n_states; j++) {
@@ -3003,6 +3230,13 @@ void AttPosEKF::ZeroVariables()
dVelIMU.zero();
lastGyroOffset.zero();
+ windSpdFiltNorth = 0.0f;
+ windSpdFiltEast = 0.0f;
+ // setting the altitude to zero will give us a higher
+ // gain to adjust faster in the first step
+ windSpdFiltAltitude = 0.0f;
+ windSpdFiltClimb = 0.0f;
+
for (unsigned i = 0; i < data_buffer_size; i++) {
for (unsigned j = 0; j < n_states; j++) {
diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.h b/src/modules/ekf_att_pos_estimator/estimator_23states.h
index faa6735ca..a607955a8 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_23states.h
+++ b/src/modules/ekf_att_pos_estimator/estimator_23states.h
@@ -80,6 +80,14 @@ public:
airspeedMeasurementSigma = 1.4f;
gyroProcessNoise = 1.4544411e-2f;
accelProcessNoise = 0.5f;
+
+ gndHgtSigma = 0.1f; // terrain gradient 1-sigma
+ R_LOS = 0.03f; // optical flow measurement noise variance (rad/sec)^2
+ flowInnovGate = 3.0f; // number of standard deviations applied to the optical flow innovation consistency check
+ auxFlowInnovGate = 10.0f; // number of standard deviations applied to the optical flow innovation consistency check used by the auxiliary filter
+ rngInnovGate = 10.0f; // number of standard deviations applied to the rnage finder innovation consistency check
+ minFlowRng = 0.01f; //minimum range between ground and flow sensor
+ moCompR_LOS = 0.2; // scaler from sensor gyro rate to uncertainty in LOS rate
}
struct mag_state_struct {
@@ -116,13 +124,16 @@ public:
float storedStates[n_states][data_buffer_size]; // state vectors stored for the last 50 time steps
uint32_t statetimeStamp[data_buffer_size]; // time stamp for each state vector stored
+ // Times
+ uint64_t lastVelPosFusion; // the time of the last velocity fusion, in the standard time unit of the filter
+
float statesAtVelTime[n_states]; // States at the effective measurement time for posNE and velNED measurements
float statesAtPosTime[n_states]; // States at the effective measurement time for posNE and velNED measurements
float statesAtHgtTime[n_states]; // States at the effective measurement time for the hgtMea measurement
float statesAtMagMeasTime[n_states]; // filter satates at the effective measurement time
float statesAtVtasMeasTime[n_states]; // filter states at the effective measurement time
float statesAtRngTime[n_states]; // filter states at the effective measurement time
- float statesAtOptFlowTime[n_states]; // States at the effective optical flow measurement time
+ float statesAtFlowTime[n_states]; // States at the effective optical flow measurement time
Vector3f correctedDelAng; // delta angles about the xyz body axes corrected for errors (rad)
Vector3f correctedDelVel; // delta velocities along the XYZ body axes corrected for errors (m/s)
@@ -140,7 +151,16 @@ public:
Vector3f accel; // acceleration vector in XYZ body axes measured by the IMU (m/s^2)
Vector3f dVelIMU;
Vector3f dAngIMU;
- float dtIMU; // time lapsed since the last IMU measurement or covariance update (sec)
+ float dtIMU; // time lapsed since the last IMU measurement or covariance update (sec), this may have significant jitter
+ float dtIMUfilt; // average time between IMU measurements (sec)
+ float dtVelPos; // time lapsed since the last position / velocity fusion (seconds), this may have significant jitter
+ float dtVelPosFilt; // average time between position / velocity fusion steps
+ float dtHgtFilt; // average time between height measurement updates
+ float dtGpsFilt; // average time between gps measurement updates
+ float windSpdFiltNorth; // average wind speed north component
+ float windSpdFiltEast; // average wind speed east component
+ float windSpdFiltAltitude; // the last altitude used to filter wind speed
+ float windSpdFiltClimb; // filtered climb rate
uint8_t fusionModeGPS; // 0 = GPS outputs 3D velocity, 1 = GPS outputs 2D velocity, 2 = GPS outputs no velocity
float innovVelPos[6]; // innovation output
float varInnovVelPos[6]; // innovation variance output
@@ -192,7 +212,8 @@ public:
bool inhibitWindStates; // true when wind states and covariances are to remain constant
bool inhibitMagStates; // true when magnetic field states and covariances are to remain constant
- bool inhibitGndHgtState; // true when the terrain ground height offset state and covariances are to remain constant
+ bool inhibitGndState; // true when the terrain ground height offset state and covariances are to remain constant
+ bool inhibitScaleState; // true when the focal length scale factor state and covariances are to remain constant
bool onGround; ///< boolean true when the flight vehicle is on the ground (not flying)
bool staticMode; ///< boolean true if no position feedback is fused
@@ -211,6 +232,30 @@ public:
unsigned storeIndex;
+ // Optical Flow error estimation
+ float storedOmega[3][data_buffer_size]; // angular rate vector stored for the last 50 time steps used by optical flow eror estimators
+
+ // Two state EKF used to estimate focal length scale factor and terrain position
+ float Popt[2][2]; // state covariance matrix
+ float flowStates[2]; // flow states [scale factor, terrain position]
+ float prevPosN; // north position at last measurement
+ float prevPosE; // east position at last measurement
+ float auxFlowObsInnov[2]; // optical flow observation innovations from focal length scale factor estimator
+ float auxFlowObsInnovVar[2]; // innovation variance for optical flow observations from focal length scale factor estimator
+ float fScaleFactorVar; // optical flow sensor focal length scale factor variance
+ Mat3f Tnb_flow; // Transformation matrix from nav to body at the time fo the optical flow measurement
+ float R_LOS; // Optical flow observation noise variance (rad/sec)^2
+ float auxFlowTestRatio[2]; // ratio of X and Y flow observation innovations to fault threshold
+ float auxRngTestRatio; // ratio of range observation innovations to fault threshold
+ float flowInnovGate; // number of standard deviations used for the innovation consistency check
+ float auxFlowInnovGate; // number of standard deviations applied to the optical flow innovation consistency check
+ float rngInnovGate; // number of standard deviations used for the innovation consistency check
+ float minFlowRng; // minimum range over which to fuse optical flow measurements
+ float moCompR_LOS; // scaler from sensor gyro rate to uncertainty in LOS rate
+
+void updateDtGpsFilt(float dt);
+
+void updateDtHgtFilt(float dt);
void UpdateStrapdownEquationsNED();
@@ -226,6 +271,8 @@ void FuseRangeFinder();
void FuseOptFlow();
+void GroundEKF();
+
void zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
void zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
@@ -268,6 +315,10 @@ static void quat2Tnb(Mat3f &Tnb, const float (&quat)[4]);
static float sq(float valIn);
+static float maxf(float valIn1, float valIn2);
+
+static float min(float valIn1, float valIn2);
+
void OnGroundCheck();
void CovarianceInit();
@@ -300,6 +351,8 @@ void InitializeDynamic(float (&initvelNED)[3], float declination);
protected:
+void updateDtVelPosFilt(float dt);
+
bool FilterHealthy();
bool GyroOffsetsDiverged();
@@ -314,3 +367,5 @@ void AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, fl
uint32_t millis();
+uint64_t getMicros();
+
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index 0cea13cc4..e770c11a2 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -63,6 +63,7 @@
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_status.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <systemlib/pid/pid.h>
@@ -124,6 +125,7 @@ private:
int _params_sub; /**< notification of parameter updates */
int _manual_sub; /**< notification of manual control updates */
int _global_pos_sub; /**< global position subscription */
+ int _vehicle_status_sub; /**< vehicle status subscription */
orb_advert_t _rate_sp_pub; /**< rate setpoint publication */
orb_advert_t _attitude_sp_pub; /**< attitude setpoint point */
@@ -139,12 +141,14 @@ private:
struct actuator_controls_s _actuators; /**< actuator control inputs */
struct actuator_controls_s _actuators_airframe; /**< actuator control inputs */
struct vehicle_global_position_s _global_pos; /**< global position */
+ struct vehicle_status_s _vehicle_status; /**< vehicle status */
perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _nonfinite_input_perf; /**< performance counter for non finite input */
perf_counter_t _nonfinite_output_perf; /**< performance counter for non finite output */
bool _setpoint_valid; /**< flag if the position control setpoint is valid */
+ bool _debug; /**< if set to true, print debug output */
struct {
float tconst;
@@ -275,6 +279,11 @@ private:
void global_pos_poll();
/**
+ * Check for vehicle status updates.
+ */
+ void vehicle_status_poll();
+
+ /**
* Shim for calling task_main from task_create.
*/
static void task_main_trampoline(int argc, char *argv[]);
@@ -312,6 +321,7 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_params_sub(-1),
_manual_sub(-1),
_global_pos_sub(-1),
+ _vehicle_status_sub(-1),
/* publications */
_rate_sp_pub(-1),
@@ -324,7 +334,8 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_nonfinite_input_perf(perf_alloc(PC_COUNT, "fw att control nonfinite input")),
_nonfinite_output_perf(perf_alloc(PC_COUNT, "fw att control nonfinite output")),
/* states */
- _setpoint_valid(false)
+ _setpoint_valid(false),
+ _debug(false)
{
/* safely initialize structs */
_att = {};
@@ -336,6 +347,7 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_actuators = {};
_actuators_airframe = {};
_global_pos = {};
+ _vehicle_status = {};
_parameter_handles.tconst = param_find("FW_ATT_TC");
@@ -559,6 +571,18 @@ FixedwingAttitudeControl::global_pos_poll()
}
void
+FixedwingAttitudeControl::vehicle_status_poll()
+{
+ /* check if there is new status information */
+ bool vehicle_status_updated;
+ orb_check(_vehicle_status_sub, &vehicle_status_updated);
+
+ if (vehicle_status_updated) {
+ orb_copy(ORB_ID(vehicle_status), _vehicle_status_sub, &_vehicle_status);
+ }
+}
+
+void
FixedwingAttitudeControl::task_main_trampoline(int argc, char *argv[])
{
att_control::g_control->task_main();
@@ -583,6 +607,7 @@ FixedwingAttitudeControl::task_main()
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ _vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_vcontrol_mode_sub, 200);
@@ -597,6 +622,7 @@ FixedwingAttitudeControl::task_main()
vehicle_accel_poll();
vehicle_control_mode_poll();
vehicle_manual_poll();
+ vehicle_status_poll();
/* wakeup source(s) */
struct pollfd fds[2];
@@ -665,6 +691,8 @@ FixedwingAttitudeControl::task_main()
global_pos_poll();
+ vehicle_status_poll();
+
/* lock integrator until control is started */
bool lock_integrator;
@@ -700,7 +728,8 @@ FixedwingAttitudeControl::task_main()
perf_count(_nonfinite_input_perf);
}
} else {
- airspeed = _airspeed.true_airspeed_m_s;
+ /* prevent numerical drama by requiring 0.5 m/s minimal speed */
+ airspeed = math::max(0.5f, _airspeed.true_airspeed_m_s);
}
/*
@@ -717,7 +746,14 @@ FixedwingAttitudeControl::task_main()
float pitch_sp = _parameters.pitchsp_offset_rad;
float throttle_sp = 0.0f;
- if (_vcontrol_mode.flag_control_velocity_enabled || _vcontrol_mode.flag_control_position_enabled) {
+ /* Read attitude setpoint from uorb if
+ * - velocity control or position control is enabled (pos controller is running)
+ * - manual control is disabled (another app may send the setpoint, but it should
+ * for sure not be set from the remote control values)
+ */
+ if (_vcontrol_mode.flag_control_velocity_enabled ||
+ _vcontrol_mode.flag_control_position_enabled ||
+ !_vcontrol_mode.flag_control_manual_enabled) {
/* read in attitude setpoint from attitude setpoint uorb topic */
roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad;
pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad;
@@ -776,6 +812,13 @@ FixedwingAttitudeControl::task_main()
}
}
+ /* If the aircraft is on ground reset the integrators */
+ if (_vehicle_status.condition_landed) {
+ _roll_ctrl.reset_integrator();
+ _pitch_ctrl.reset_integrator();
+ _yaw_ctrl.reset_integrator();
+ }
+
/* Prepare speed_body_u and speed_body_w */
float speed_body_u = 0.0f;
float speed_body_v = 0.0f;
@@ -785,7 +828,7 @@ FixedwingAttitudeControl::task_main()
speed_body_v = _att.R[0][1] * _global_pos.vel_n + _att.R[1][1] * _global_pos.vel_e + _att.R[2][1] * _global_pos.vel_d;
speed_body_w = _att.R[0][2] * _global_pos.vel_n + _att.R[1][2] * _global_pos.vel_e + _att.R[2][2] * _global_pos.vel_d;
} else {
- if (loop_counter % 10 == 0) {
+ if (_debug && loop_counter % 10 == 0) {
warnx("Did not get a valid R\n");
}
}
@@ -808,7 +851,7 @@ FixedwingAttitudeControl::task_main()
_roll_ctrl.reset_integrator();
perf_count(_nonfinite_output_perf);
- if (loop_counter % 10 == 0) {
+ if (_debug && loop_counter % 10 == 0) {
warnx("roll_u %.4f", (double)roll_u);
}
}
@@ -821,7 +864,7 @@ FixedwingAttitudeControl::task_main()
if (!isfinite(pitch_u)) {
_pitch_ctrl.reset_integrator();
perf_count(_nonfinite_output_perf);
- if (loop_counter % 10 == 0) {
+ if (_debug && loop_counter % 10 == 0) {
warnx("pitch_u %.4f, _yaw_ctrl.get_desired_rate() %.4f,"
" airspeed %.4f, airspeed_scaling %.4f,"
" roll_sp %.4f, pitch_sp %.4f,"
@@ -845,21 +888,25 @@ FixedwingAttitudeControl::task_main()
if (!isfinite(yaw_u)) {
_yaw_ctrl.reset_integrator();
perf_count(_nonfinite_output_perf);
- if (loop_counter % 10 == 0) {
+ if (_debug && loop_counter % 10 == 0) {
warnx("yaw_u %.4f", (double)yaw_u);
}
}
- /* throttle passed through */
- _actuators.control[3] = (isfinite(throttle_sp)) ? throttle_sp : 0.0f;
+ /* throttle passed through if it is finite and if no engine failure was
+ * detected */
+ _actuators.control[3] = (isfinite(throttle_sp) &&
+ !(_vehicle_status.engine_failure ||
+ _vehicle_status.engine_failure_cmd)) ?
+ throttle_sp : 0.0f;
if (!isfinite(throttle_sp)) {
- if (loop_counter % 10 == 0) {
+ if (_debug && loop_counter % 10 == 0) {
warnx("throttle_sp %.4f", (double)throttle_sp);
}
}
} else {
perf_count(_nonfinite_input_perf);
- if (loop_counter % 10 == 0) {
+ if (_debug && loop_counter % 10 == 0) {
warnx("Non-finite setpoint roll_sp: %.4f, pitch_sp %.4f", (double)roll_sp, (double)pitch_sp);
}
}
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index eadb63f40..6017369aa 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -88,7 +88,6 @@
#include <launchdetection/LaunchDetector.h>
#include <ecl/l1/ecl_l1_pos_controller.h>
#include <external_lgpl/tecs/tecs.h>
-#include <drivers/drv_range_finder.h>
#include "landingslope.h"
#include "mtecs/mTecs.h"
@@ -102,6 +101,8 @@ static int _control_task = -1; /**< task handle for sensor task */
*/
extern "C" __EXPORT int fw_pos_control_l1_main(int argc, char *argv[]);
+using namespace launchdetection;
+
class FixedwingPositionControl
{
public:
@@ -139,13 +140,14 @@ private:
int _pos_sp_triplet_sub;
int _att_sub; /**< vehicle attitude subscription */
int _airspeed_sub; /**< airspeed subscription */
- int _control_mode_sub; /**< vehicle status subscription */
+ int _control_mode_sub; /**< control mode subscription */
+ int _vehicle_status_sub; /**< vehicle status subscription */
int _params_sub; /**< notification of parameter updates */
int _manual_control_sub; /**< notification of manual control updates */
int _sensor_combined_sub; /**< for body frame accelerations */
- int _range_finder_sub; /**< range finder subscription */
orb_advert_t _attitude_sp_pub; /**< attitude setpoint */
+ orb_advert_t _tecs_status_pub; /**< TECS status publication */
orb_advert_t _nav_capabilities_pub; /**< navigation capabilities publication */
struct vehicle_attitude_s _att; /**< vehicle attitude */
@@ -153,25 +155,24 @@ private:
struct navigation_capabilities_s _nav_capabilities; /**< navigation capabilities */
struct manual_control_setpoint_s _manual; /**< r/c channel data */
struct airspeed_s _airspeed; /**< airspeed */
- struct vehicle_control_mode_s _control_mode; /**< vehicle status */
+ struct vehicle_control_mode_s _control_mode; /**< control mode */
+ struct vehicle_status_s _vehicle_status; /**< vehicle status */
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
struct position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of mission items */
struct sensor_combined_s _sensor_combined; /**< for body frame accelerations */
- struct range_finder_report _range_finder; /**< range finder report */
perf_counter_t _loop_perf; /**< loop performance counter */
/* land states */
- /* not in non-abort mode for landing yet */
bool land_noreturn_horizontal;
bool land_noreturn_vertical;
bool land_stayonground;
bool land_motor_lim;
bool land_onslope;
+ bool land_useterrain;
/* takeoff/launch states */
- bool launch_detected;
- bool usePreTakeoffThrust;
+ LaunchDetectionResult launch_detection_state;
bool last_manual; ///< true if the last iteration was in manual mode (used to determine when a reset is needed)
@@ -203,10 +204,13 @@ private:
float l1_damping;
float time_const;
+ float time_const_throt;
float min_sink_rate;
float max_sink_rate;
float max_climb_rate;
+ float climbout_diff;
float heightrate_p;
+ float heightrate_ff;
float speedrate_p;
float throttle_damp;
float integrator_gain;
@@ -227,6 +231,7 @@ private:
float throttle_min;
float throttle_max;
float throttle_cruise;
+ float throttle_slew_max;
float throttle_land_max;
@@ -235,7 +240,9 @@ private:
float land_flare_alt_relative;
float land_thrust_lim_alt_relative;
float land_heading_hold_horizontal_distance;
- float range_finder_rel_alt;
+ float land_flare_pitch_min_deg;
+ float land_flare_pitch_max_deg;
+ int land_use_terrain_estimate;
} _parameters; /**< local copies of interesting parameters */
@@ -245,10 +252,13 @@ private:
param_t l1_damping;
param_t time_const;
+ param_t time_const_throt;
param_t min_sink_rate;
param_t max_sink_rate;
param_t max_climb_rate;
+ param_t climbout_diff;
param_t heightrate_p;
+ param_t heightrate_ff;
param_t speedrate_p;
param_t throttle_damp;
param_t integrator_gain;
@@ -269,6 +279,7 @@ private:
param_t throttle_min;
param_t throttle_max;
param_t throttle_cruise;
+ param_t throttle_slew_max;
param_t throttle_land_max;
@@ -277,7 +288,9 @@ private:
param_t land_flare_alt_relative;
param_t land_thrust_lim_alt_relative;
param_t land_heading_hold_horizontal_distance;
- param_t range_finder_rel_alt;
+ param_t land_flare_pitch_min_deg;
+ param_t land_flare_pitch_max_deg;
+ param_t land_use_terrain_estimate;
} _parameter_handles; /**< handles for interesting parameters */
@@ -294,20 +307,19 @@ private:
void control_update();
/**
- * Check for changes in vehicle status.
+ * Check for changes in control mode
*/
void vehicle_control_mode_poll();
/**
- * Check for airspeed updates.
+ * Check for changes in vehicle status.
*/
- bool vehicle_airspeed_poll();
+ void vehicle_status_poll();
/**
- * Check for range finder updates.
+ * Check for airspeed updates.
*/
- bool range_finder_poll();
-
+ bool vehicle_airspeed_poll();
/**
* Check for position updates.
@@ -330,9 +342,9 @@ private:
void navigation_capabilities_publish();
/**
- * Get the relative alt either from the difference between estimate and waypoint or from the laser range finder
+ * Return the terrain estimate during landing: uses the wp altitude value or the terrain estimate if available
*/
- float get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt);
+ float get_terrain_altitude_landing(float land_setpoint_alt, const struct vehicle_global_position_s &global_pos);
/**
* Control position.
@@ -373,7 +385,8 @@ private:
bool climbout_mode, float climbout_pitch_min_rad,
float altitude,
const math::Vector<3> &ground_speed,
- tecs_mode mode = TECS_MODE_NORMAL);
+ tecs_mode mode = TECS_MODE_NORMAL,
+ bool pitch_max_special = false);
};
@@ -401,13 +414,14 @@ FixedwingPositionControl::FixedwingPositionControl() :
_att_sub(-1),
_airspeed_sub(-1),
_control_mode_sub(-1),
+ _vehicle_status_sub(-1),
_params_sub(-1),
_manual_control_sub(-1),
_sensor_combined_sub(-1),
- _range_finder_sub(-1),
/* publications */
_attitude_sp_pub(-1),
+ _tecs_status_pub(-1),
_nav_capabilities_pub(-1),
/* states */
@@ -417,10 +431,10 @@ FixedwingPositionControl::FixedwingPositionControl() :
_manual(),
_airspeed(),
_control_mode(),
+ _vehicle_status(),
_global_pos(),
_pos_sp_triplet(),
_sensor_combined(),
- _range_finder(),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
@@ -430,8 +444,8 @@ FixedwingPositionControl::FixedwingPositionControl() :
land_stayonground(false),
land_motor_lim(false),
land_onslope(false),
- launch_detected(false),
- usePreTakeoffThrust(false),
+ land_useterrain(false),
+ launch_detection_state(LAUNCHDETECTION_RES_NONE),
last_manual(false),
landingslope(),
flare_curve_alt_rel_last(0.0f),
@@ -460,6 +474,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.roll_limit = param_find("FW_R_LIM");
_parameter_handles.throttle_min = param_find("FW_THR_MIN");
_parameter_handles.throttle_max = param_find("FW_THR_MAX");
+ _parameter_handles.throttle_slew_max = param_find("FW_THR_SLEW_MAX");
_parameter_handles.throttle_cruise = param_find("FW_THR_CRUISE");
_parameter_handles.throttle_land_max = param_find("FW_THR_LND_MAX");
@@ -468,12 +483,16 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.land_flare_alt_relative = param_find("FW_LND_FLALT");
_parameter_handles.land_thrust_lim_alt_relative = param_find("FW_LND_TLALT");
_parameter_handles.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST");
- _parameter_handles.range_finder_rel_alt = param_find("FW_LND_RFRALT");
+ _parameter_handles.land_flare_pitch_min_deg = param_find("FW_FLARE_PMIN");
+ _parameter_handles.land_flare_pitch_max_deg = param_find("FW_FLARE_PMAX");
+ _parameter_handles.land_use_terrain_estimate= param_find("FW_LND_USETER");
_parameter_handles.time_const = param_find("FW_T_TIME_CONST");
+ _parameter_handles.time_const_throt = param_find("FW_T_THRO_CONST");
_parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN");
_parameter_handles.max_sink_rate = param_find("FW_T_SINK_MAX");
_parameter_handles.max_climb_rate = param_find("FW_T_CLMB_MAX");
+ _parameter_handles.climbout_diff = param_find("FW_CLMBOUT_DIFF");
_parameter_handles.throttle_damp = param_find("FW_T_THR_DAMP");
_parameter_handles.integrator_gain = param_find("FW_T_INTEG_GAIN");
_parameter_handles.vertical_accel_limit = param_find("FW_T_VERT_ACC");
@@ -483,6 +502,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT");
_parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP");
_parameter_handles.heightrate_p = param_find("FW_T_HRATE_P");
+ _parameter_handles.heightrate_ff = param_find("FW_T_HRATE_FF");
_parameter_handles.speedrate_p = param_find("FW_T_SRATE_P");
/* fetch initial parameter values */
@@ -532,10 +552,12 @@ FixedwingPositionControl::parameters_update()
param_get(_parameter_handles.throttle_min, &(_parameters.throttle_min));
param_get(_parameter_handles.throttle_max, &(_parameters.throttle_max));
param_get(_parameter_handles.throttle_cruise, &(_parameters.throttle_cruise));
+ param_get(_parameter_handles.throttle_slew_max, &(_parameters.throttle_slew_max));
param_get(_parameter_handles.throttle_land_max, &(_parameters.throttle_land_max));
param_get(_parameter_handles.time_const, &(_parameters.time_const));
+ param_get(_parameter_handles.time_const_throt, &(_parameters.time_const_throt));
param_get(_parameter_handles.min_sink_rate, &(_parameters.min_sink_rate));
param_get(_parameter_handles.max_sink_rate, &(_parameters.max_sink_rate));
param_get(_parameter_handles.throttle_damp, &(_parameters.throttle_damp));
@@ -547,26 +569,37 @@ FixedwingPositionControl::parameters_update()
param_get(_parameter_handles.speed_weight, &(_parameters.speed_weight));
param_get(_parameter_handles.pitch_damping, &(_parameters.pitch_damping));
param_get(_parameter_handles.max_climb_rate, &(_parameters.max_climb_rate));
+ param_get(_parameter_handles.climbout_diff, &(_parameters.climbout_diff));
param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p));
+ param_get(_parameter_handles.heightrate_ff, &(_parameters.heightrate_ff));
param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p));
param_get(_parameter_handles.land_slope_angle, &(_parameters.land_slope_angle));
param_get(_parameter_handles.land_H1_virt, &(_parameters.land_H1_virt));
param_get(_parameter_handles.land_flare_alt_relative, &(_parameters.land_flare_alt_relative));
param_get(_parameter_handles.land_thrust_lim_alt_relative, &(_parameters.land_thrust_lim_alt_relative));
- param_get(_parameter_handles.land_heading_hold_horizontal_distance, &(_parameters.land_heading_hold_horizontal_distance));
- param_get(_parameter_handles.range_finder_rel_alt, &(_parameters.range_finder_rel_alt));
+ /* check if negative value for 2/3 of flare altitude is set for throttle cut */
+ if (_parameters.land_thrust_lim_alt_relative < 0.0f) {
+ _parameters.land_thrust_lim_alt_relative = 0.66f * _parameters.land_flare_alt_relative;
+ }
+
+ param_get(_parameter_handles.land_heading_hold_horizontal_distance, &(_parameters.land_heading_hold_horizontal_distance));
+ param_get(_parameter_handles.land_flare_pitch_min_deg, &(_parameters.land_flare_pitch_min_deg));
+ param_get(_parameter_handles.land_flare_pitch_max_deg, &(_parameters.land_flare_pitch_max_deg));
+ param_get(_parameter_handles.land_use_terrain_estimate, &(_parameters.land_use_terrain_estimate));
_l1_control.set_l1_damping(_parameters.l1_damping);
_l1_control.set_l1_period(_parameters.l1_period);
_l1_control.set_l1_roll_limit(math::radians(_parameters.roll_limit));
_tecs.set_time_const(_parameters.time_const);
+ _tecs.set_time_const_throt(_parameters.time_const_throt);
_tecs.set_min_sink_rate(_parameters.min_sink_rate);
_tecs.set_max_sink_rate(_parameters.max_sink_rate);
_tecs.set_throttle_damp(_parameters.throttle_damp);
+ _tecs.set_throttle_slewrate(_parameters.throttle_slew_max);
_tecs.set_integrator_gain(_parameters.integrator_gain);
_tecs.set_vertical_accel_limit(_parameters.vertical_accel_limit);
_tecs.set_height_comp_filter_omega(_parameters.height_comp_filter_omega);
@@ -578,6 +611,7 @@ FixedwingPositionControl::parameters_update()
_tecs.set_indicated_airspeed_max(_parameters.airspeed_max);
_tecs.set_max_climb_rate(_parameters.max_climb_rate);
_tecs.set_heightrate_p(_parameters.heightrate_p);
+ _tecs.set_heightrate_ff(_parameters.heightrate_ff);
_tecs.set_speedrate_p(_parameters.speedrate_p);
/* sanity check parameters */
@@ -611,16 +645,27 @@ FixedwingPositionControl::parameters_update()
void
FixedwingPositionControl::vehicle_control_mode_poll()
{
- bool vstatus_updated;
+ bool updated;
- /* Check HIL state if vehicle status has changed */
- orb_check(_control_mode_sub, &vstatus_updated);
+ orb_check(_control_mode_sub, &updated);
- if (vstatus_updated) {
+ if (updated) {
orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
}
}
+void
+FixedwingPositionControl::vehicle_status_poll()
+{
+ bool updated;
+
+ orb_check(_vehicle_status_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_status), _vehicle_status_sub, &_vehicle_status);
+ }
+}
+
bool
FixedwingPositionControl::vehicle_airspeed_poll()
{
@@ -647,20 +692,6 @@ FixedwingPositionControl::vehicle_airspeed_poll()
return airspeed_updated;
}
-bool
-FixedwingPositionControl::range_finder_poll()
-{
- /* check if there is a range finder measurement */
- bool range_finder_updated;
- orb_check(_range_finder_sub, &range_finder_updated);
-
- if (range_finder_updated) {
- orb_copy(ORB_ID(sensor_range_finder), _range_finder_sub, &_range_finder);
- }
-
- return range_finder_updated;
-}
-
void
FixedwingPositionControl::vehicle_attitude_poll()
{
@@ -798,21 +829,23 @@ void FixedwingPositionControl::navigation_capabilities_publish()
}
}
-float FixedwingPositionControl::get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt)
+float FixedwingPositionControl::get_terrain_altitude_landing(float land_setpoint_alt, const struct vehicle_global_position_s &global_pos)
{
- float rel_alt_estimated = current_alt - land_setpoint_alt;
-
- /* only use range finder if:
- * parameter (range_finder_use_relative_alt) > 0
- * the measurement is valid
- * the estimated relative altitude (from global altitude estimate and landing waypoint) <= range_finder_use_relative_alt
- */
- if (range_finder_use_relative_alt < 0 || !range_finder.valid || rel_alt_estimated > range_finder_use_relative_alt ) {
- return rel_alt_estimated;
+ if (!isfinite(global_pos.terrain_alt)) {
+ return land_setpoint_alt;
}
- return range_finder.distance;
-
+ /* Decide if the terrain estimation can be used, once we switched to using the terrain we stick with it
+ * for the whole landing */
+ if (_parameters.land_use_terrain_estimate && (global_pos.terrain_alt_valid || land_useterrain)) {
+ if(!land_useterrain) {
+ mavlink_log_info(_mavlink_fd, "#audio: Landing, using terrain estimate");
+ land_useterrain = true;
+ }
+ return global_pos.terrain_alt;
+ } else {
+ return land_setpoint_alt;
+ }
}
bool
@@ -917,10 +950,17 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_LAND) {
float bearing_lastwp_currwp = get_bearing_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
+ float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
/* Horizontal landing control */
/* switch to heading hold for the last meters, continue heading hold after */
float wp_distance = get_distance_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
+ /* calculate a waypoint distance value which is 0 when the aircraft is behind the waypoint */
+ float wp_distance_save = wp_distance;
+ if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) >= math::radians(90.0f)) {
+ wp_distance_save = 0.0f;
+ }
+
//warnx("wp dist: %d, alt err: %d, noret: %s", (int)wp_distance, (int)altitude_error, (land_noreturn) ? "YES" : "NO");
if (wp_distance < _parameters.land_heading_hold_horizontal_distance || land_noreturn_horizontal) {
@@ -956,29 +996,30 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* Vertical landing control */
//xxx: using the tecs altitude controller for slope control for now
-
-// /* do not go down too early */
-// if (wp_distance > 50.0f) {
-// altitude_error = (_global_triplet.current.alt + 25.0f) - _global_pos.alt;
-// }
/* apply minimum pitch (flare) and limit roll if close to touch down, altitude error is negative (going down) */
// XXX this could make a great param
- float flare_pitch_angle_rad = -math::radians(5.0f);//math::radians(pos_sp_triplet.current.param1)
float throttle_land = _parameters.throttle_min + (_parameters.throttle_max - _parameters.throttle_min) * 0.1f;
float airspeed_land = 1.3f * _parameters.airspeed_min;
float airspeed_approach = 1.3f * _parameters.airspeed_min;
+ /* Get an estimate of the terrain altitude if available, otherwise terrain_alt will be
+ * equal to _pos_sp_triplet.current.alt */
+ float terrain_alt = get_terrain_altitude_landing(_pos_sp_triplet.current.alt, _global_pos);
+
/* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
- float L_altitude_rel = _pos_sp_triplet.previous.valid ? _pos_sp_triplet.previous.alt - _pos_sp_triplet.current.alt : 0.0f;
+ float L_altitude_rel = _pos_sp_triplet.previous.valid ?
+ _pos_sp_triplet.previous.alt - terrain_alt : 0.0f;
- float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
float landing_slope_alt_rel_desired = landingslope.getLandingSlopeRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
- float relative_alt = get_relative_landingalt(_pos_sp_triplet.current.alt, _global_pos.alt, _range_finder, _parameters.range_finder_rel_alt);
-
- if ( (relative_alt < landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
-
+ /* Check if we should start flaring with a vertical and a
+ * horizontal limit (with some tolerance)
+ * The horizontal limit is only applied when we are in front of the wp
+ */
+ if (((_global_pos.alt < terrain_alt + landingslope.flare_relative_alt()) &&
+ (wp_distance_save < landingslope.flare_length() + 5.0f)) ||
+ land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
/* land with minimal speed */
// /* force TECS to only control speed with pitch, altitude is only implicitely controlled now */
@@ -987,7 +1028,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* kill the throttle if param requests it */
throttle_max = _parameters.throttle_max;
- if (relative_alt < landingslope.motor_lim_relative_alt() || land_motor_lim) {
+ if (_global_pos.alt < terrain_alt + landingslope.motor_lim_relative_alt() || land_motor_lim) {
throttle_max = math::min(throttle_max, _parameters.throttle_land_max);
if (!land_motor_lim) {
land_motor_lim = true;
@@ -1005,12 +1046,13 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
land_stayonground = true;
}
- tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + flare_curve_alt_rel,
+ tecs_update_pitch_throttle(terrain_alt + flare_curve_alt_rel,
calculate_target_airspeed(airspeed_land), eas2tas,
- flare_pitch_angle_rad, math::radians(15.0f),
+ math::radians(_parameters.land_flare_pitch_min_deg),
+ math::radians(_parameters.land_flare_pitch_max_deg),
0.0f, throttle_max, throttle_land,
- false, flare_pitch_angle_rad,
- _pos_sp_triplet.current.alt + relative_alt, ground_speed,
+ false, land_motor_lim ? math::radians(_parameters.land_flare_pitch_min_deg) : math::radians(_parameters.pitch_limit_min),
+ _global_pos.alt, ground_speed,
land_motor_lim ? TECS_MODE_LAND_THROTTLELIM : TECS_MODE_LAND);
if (!land_noreturn_vertical) {
@@ -1031,8 +1073,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
* if current position is below the slope continue at previous wp altitude
* until the intersection with slope
* */
- float altitude_desired_rel = relative_alt;
- if (relative_alt > landing_slope_alt_rel_desired || land_onslope) {
+ float altitude_desired_rel;
+ if (_global_pos.alt > terrain_alt + landing_slope_alt_rel_desired || land_onslope) {
/* stay on slope */
altitude_desired_rel = landing_slope_alt_rel_desired;
if (!land_onslope) {
@@ -1041,10 +1083,11 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
} else {
/* continue horizontally */
- altitude_desired_rel = _pos_sp_triplet.previous.valid ? L_altitude_rel : relative_alt;
+ altitude_desired_rel = _pos_sp_triplet.previous.valid ? L_altitude_rel :
+ _global_pos.alt - terrain_alt;
}
- tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + altitude_desired_rel,
+ tecs_update_pitch_throttle(terrain_alt + altitude_desired_rel,
calculate_target_airspeed(airspeed_approach), eas2tas,
math::radians(_parameters.pitch_limit_min),
math::radians(_parameters.pitch_limit_max),
@@ -1053,67 +1096,74 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
_parameters.throttle_cruise,
false,
math::radians(_parameters.pitch_limit_min),
- _pos_sp_triplet.current.alt + relative_alt,
+ _global_pos.alt,
ground_speed);
}
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF) {
/* Perform launch detection */
- if(!launch_detected) { //do not do further checks once a launch was detected
- if (launchDetector.launchDetectionEnabled()) {
- static hrt_abstime last_sent = 0;
- if(hrt_absolute_time() - last_sent > 4e6) {
- mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running");
- last_sent = hrt_absolute_time();
- }
-
- /* Tell the attitude controller to stop integrating while we are waiting
- * for the launch */
- _att_sp.roll_reset_integral = true;
- _att_sp.pitch_reset_integral = true;
- _att_sp.yaw_reset_integral = true;
-
- /* Detect launch */
- launchDetector.update(_sensor_combined.accelerometer_m_s2[0]);
- if (launchDetector.getLaunchDetected()) {
- launch_detected = true;
- mavlink_log_info(_mavlink_fd, "#audio: Takeoff");
- }
- } else {
- /* no takeoff detection --> fly */
- launch_detected = true;
- warnx("launchdetection off");
+ if (launchDetector.launchDetectionEnabled() &&
+ launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) {
+ /* Inform user that launchdetection is running */
+ static hrt_abstime last_sent = 0;
+ if(hrt_absolute_time() - last_sent > 4e6) {
+ mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running");
+ last_sent = hrt_absolute_time();
}
+
+ /* Detect launch */
+ launchDetector.update(_sensor_combined.accelerometer_m_s2[0]);
+
+ /* update our copy of the laucn detection state */
+ launch_detection_state = launchDetector.getLaunchDetected();
+ } else {
+ /* no takeoff detection --> fly */
+ launch_detection_state = LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS;
}
- _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d);
- _att_sp.roll_body = _l1_control.nav_roll();
- _att_sp.yaw_body = _l1_control.nav_bearing();
+ /* Set control values depending on the detection state */
+ if (launch_detection_state != LAUNCHDETECTION_RES_NONE) {
+ /* Launch has been detected, hence we have to control the plane. */
+
+ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
- if (launch_detected) {
- usePreTakeoffThrust = false;
+ /* Select throttle: only in LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS we want to use
+ * full throttle, otherwise we use the preTakeOff Throttle */
+ float takeoff_throttle = launch_detection_state !=
+ LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS ?
+ launchDetector.getThrottlePreTakeoff() : _parameters.throttle_max;
- /* apply minimum pitch and limit roll if target altitude is not within 10 meters */
- if (altitude_error > 15.0f) {
+ /* select maximum pitch: the launchdetector may impose another limit for the pitch
+ * depending on the state of the launch */
+ float takeoff_pitch_max_deg = launchDetector.getPitchMax(_parameters.pitch_limit_max);
+ float takeoff_pitch_max_rad = math::radians(takeoff_pitch_max_deg);
+
+ /* apply minimum pitch and limit roll if target altitude is not within climbout_diff
+ * meters */
+ if (_parameters.climbout_diff > 0.001f && altitude_error > _parameters.climbout_diff) {
/* enforce a minimum of 10 degrees pitch up on takeoff, or take parameter */
tecs_update_pitch_throttle(_pos_sp_triplet.current.alt,
calculate_target_airspeed(1.3f * _parameters.airspeed_min),
eas2tas,
math::radians(_parameters.pitch_limit_min),
- math::radians(_parameters.pitch_limit_max),
- _parameters.throttle_min, _parameters.throttle_max,
+ takeoff_pitch_max_rad,
+ _parameters.throttle_min, takeoff_throttle,
_parameters.throttle_cruise,
true,
math::max(math::radians(pos_sp_triplet.current.pitch_min),
math::radians(10.0f)),
_global_pos.alt,
ground_speed,
- TECS_MODE_TAKEOFF);
+ TECS_MODE_TAKEOFF,
+ takeoff_pitch_max_deg != _parameters.pitch_limit_max);
/* limit roll motion to ensure enough lift */
- _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f), math::radians(15.0f));
+ _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f),
+ math::radians(15.0f));
} else {
tecs_update_pitch_throttle(_pos_sp_triplet.current.alt,
@@ -1122,17 +1172,26 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
math::radians(_parameters.pitch_limit_min),
math::radians(_parameters.pitch_limit_max),
_parameters.throttle_min,
- _parameters.throttle_max,
+ takeoff_throttle,
_parameters.throttle_cruise,
false,
math::radians(_parameters.pitch_limit_min),
_global_pos.alt,
ground_speed);
}
-
} else {
- usePreTakeoffThrust = true;
+ /* Tell the attitude controller to stop integrating while we are waiting
+ * for the launch */
+ _att_sp.roll_reset_integral = true;
+ _att_sp.pitch_reset_integral = true;
+ _att_sp.yaw_reset_integral = true;
+
+ /* Set default roll and pitch setpoints during detection phase */
+ _att_sp.roll_body = 0.0f;
+ _att_sp.pitch_body = math::max(math::radians(pos_sp_triplet.current.pitch_min),
+ math::radians(10.0f));
}
+
}
/* reset landing state */
@@ -1166,13 +1225,26 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
}
- if (usePreTakeoffThrust) {
+ if (_vehicle_status.engine_failure || _vehicle_status.engine_failure_cmd) {
+ /* Set thrust to 0 to minimize damage */
+ _att_sp.thrust = 0.0f;
+ } else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
+ launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) {
+ /* making sure again that the correct thrust is used,
+ * without depending on library calls for safety reasons */
_att_sp.thrust = launchDetector.getThrottlePreTakeoff();
+ } else {
+ /* Copy thrust and pitch values from tecs */
+ _att_sp.thrust = math::min(_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() :
+ _tecs.get_throttle_demand(), throttle_max);
}
- else {
- _att_sp.thrust = math::min(_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() : _tecs.get_throttle_demand(), throttle_max);
+
+ /* During a takeoff waypoint while waiting for launch the pitch sp is set
+ * already (not by tecs) */
+ if (!(pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
+ launch_detection_state == LAUNCHDETECTION_RES_NONE)) {
+ _att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand();
}
- _att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand();
if (_control_mode.flag_control_position_enabled) {
last_manual = false;
@@ -1196,13 +1268,15 @@ FixedwingPositionControl::task_main()
_att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
_sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ _vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- _range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
- /* rate limit vehicle status updates to 5Hz */
+ /* rate limit control mode updates to 5Hz */
orb_set_interval(_control_mode_sub, 200);
+ /* rate limit vehicle status updates to 5Hz */
+ orb_set_interval(_vehicle_status_sub, 200);
/* rate limit position updates to 50 Hz */
orb_set_interval(_global_pos_sub, 20);
@@ -1241,9 +1315,12 @@ FixedwingPositionControl::task_main()
perf_begin(_loop_perf);
- /* check vehicle status for changes to publication state */
+ /* check vehicle control mode for changes to publication state */
vehicle_control_mode_poll();
+ /* check vehicle status for changes to publication state */
+ vehicle_status_poll();
+
/* only update parameters if they changed */
if (fds[0].revents & POLLIN) {
/* read from param to clear updated flag */
@@ -1273,7 +1350,6 @@ FixedwingPositionControl::task_main()
vehicle_setpoint_poll();
vehicle_sensor_combined_poll();
vehicle_airspeed_poll();
- range_finder_poll();
// vehicle_baro_poll();
math::Vector<3> ground_speed(_global_pos.vel_n, _global_pos.vel_e, _global_pos.vel_d);
@@ -1326,8 +1402,7 @@ FixedwingPositionControl::task_main()
void FixedwingPositionControl::reset_takeoff_state()
{
- launch_detected = false;
- usePreTakeoffThrust = false;
+ launch_detection_state = LAUNCHDETECTION_RES_NONE;
launchDetector.reset();
}
@@ -1338,6 +1413,7 @@ void FixedwingPositionControl::reset_landing_state()
land_stayonground = false;
land_motor_lim = false;
land_onslope = false;
+ land_useterrain = false;
}
void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_sp, float eas2tas,
@@ -1346,7 +1422,7 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_
bool climbout_mode, float climbout_pitch_min_rad,
float altitude,
const math::Vector<3> &ground_speed,
- tecs_mode mode)
+ tecs_mode mode, bool pitch_max_special)
{
if (_mTecs.getEnabled()) {
/* Using mtecs library: prepare arguments for mtecs call */
@@ -1356,20 +1432,87 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_
flightPathAngle = -asinf(ground_speed(2)/ground_speed_length);
}
fwPosctrl::LimitOverride limitOverride;
- if (climbout_mode) {
+ if (_vehicle_status.engine_failure || _vehicle_status.engine_failure_cmd) {
+ /* Force the slow downwards spiral */
+ limitOverride.enablePitchMinOverride(-1.0f);
+ limitOverride.enablePitchMaxOverride(5.0f);
+
+ } else if (climbout_mode) {
limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad);
} else {
limitOverride.disablePitchMinOverride();
}
+
+ if (pitch_max_special) {
+ /* Use the maximum pitch from the argument */
+ limitOverride.enablePitchMaxOverride(M_RAD_TO_DEG_F * pitch_max_rad);
+ } else {
+ /* use pitch max set by MT param */
+ limitOverride.disablePitchMaxOverride();
+ }
_mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode,
limitOverride);
} else {
+ if (_vehicle_status.engine_failure || _vehicle_status.engine_failure_cmd) {
+ /* Force the slow downwards spiral */
+ pitch_min_rad = M_DEG_TO_RAD_F * -1.0f;
+ pitch_max_rad = M_DEG_TO_RAD_F * 5.0f;
+ }
+
+/* No underspeed protection in landing mode */
+ _tecs.set_detect_underspeed_enabled(!(mode == TECS_MODE_LAND || mode == TECS_MODE_LAND_THROTTLELIM));
+
/* Using tecs library */
_tecs.update_pitch_throttle(_R_nb, _att.pitch, altitude, alt_sp, v_sp,
_airspeed.indicated_airspeed_m_s, eas2tas,
climbout_mode, climbout_pitch_min_rad,
throttle_min, throttle_max, throttle_cruise,
pitch_min_rad, pitch_max_rad);
+
+ struct TECS::tecs_state s;
+ _tecs.get_tecs_state(s);
+
+ struct tecs_status_s t;
+
+ t.timestamp = s.timestamp;
+
+ switch (s.mode) {
+ case TECS::ECL_TECS_MODE_NORMAL:
+ t.mode = TECS_MODE_NORMAL;
+ break;
+ case TECS::ECL_TECS_MODE_UNDERSPEED:
+ t.mode = TECS_MODE_UNDERSPEED;
+ break;
+ case TECS::ECL_TECS_MODE_BAD_DESCENT:
+ t.mode = TECS_MODE_BAD_DESCENT;
+ break;
+ case TECS::ECL_TECS_MODE_CLIMBOUT:
+ t.mode = TECS_MODE_CLIMBOUT;
+ break;
+ }
+
+ t.altitudeSp = s.hgt_dem;
+ t.altitude_filtered = s.hgt;
+ t.airspeedSp = s.spd_dem;
+ t.airspeed_filtered = s.spd;
+
+ t.flightPathAngleSp = s.dhgt_dem;
+ t.flightPathAngle = s.dhgt;
+ t.flightPathAngleFiltered = s.dhgt;
+
+ t.airspeedDerivativeSp = s.dspd_dem;
+ t.airspeedDerivative = s.dspd;
+
+ t.totalEnergyRateSp = s.thr;
+ t.totalEnergyRate = s.ithr;
+ t.energyDistributionRateSp = s.ptch;
+ t.energyDistributionRate = s.iptch;
+
+ if (_tecs_status_pub > 0) {
+ orb_publish(ORB_ID(tecs_status), _tecs_status_pub, &t);
+ } else {
+ _tecs_status_pub = orb_advertise(ORB_ID(tecs_status), &t);
+ }
}
}
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
index 52128e1b7..c00d82232 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -83,6 +83,17 @@ PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.7f);
/**
+ * Throttle max slew rate
+ *
+ * Maximum slew rate for the commanded throttle
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group L1 Control
+ */
+PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f);
+
+/**
* Negative pitch limit
*
* The minimum negative pitch the controller will output.
@@ -120,8 +131,8 @@ PARAM_DEFINE_FLOAT(FW_R_LIM, 45.0f);
/**
* Throttle limit max
*
- * This is the maximum throttle % that can be used by the controller.
- * For overpowered aircraft, this should be reduced to a value that
+ * This is the maximum throttle % that can be used by the controller.
+ * For overpowered aircraft, this should be reduced to a value that
* provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX.
*
* @group L1 Control
@@ -131,10 +142,10 @@ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
/**
* Throttle limit min
*
- * This is the minimum throttle % that can be used by the controller.
- * For electric aircraft this will normally be set to zero, but can be set
- * to a small non-zero value if a folding prop is fitted to prevent the
- * prop from folding and unfolding repeatedly in-flight or to provide
+ * This is the minimum throttle % that can be used by the controller.
+ * For electric aircraft this will normally be set to zero, but can be set
+ * to a small non-zero value if a folding prop is fitted to prevent the
+ * prop from folding and unfolding repeatedly in-flight or to provide
* some aerodynamic drag from a turning prop to improve the descent rate.
*
* For aircraft with internal combustion engine this parameter should be set
@@ -147,7 +158,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
/**
* Throttle limit value before flare
*
- * This throttle value will be set as throttle limit at FW_LND_TLALT,
+ * This throttle value will be set as throttle limit at FW_LND_TLALT,
* before arcraft will flare.
*
* @group L1 Control
@@ -155,19 +166,31 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f);
/**
+ * Climbout Altitude difference
+ *
+ * If the altitude error exceeds this parameter, the system will climb out
+ * with maximum throttle and minimum airspeed until it is closer than this
+ * distance to the desired altitude. Mostly used for takeoff waypoints / modes.
+ * Set to zero to disable climbout mode (not recommended).
+ *
+ * @group L1 Control
+ */
+PARAM_DEFINE_FLOAT(FW_CLMBOUT_DIFF, 25.0f);
+
+/**
* Maximum climb rate
*
- * This is the best climb rate that the aircraft can achieve with
- * the throttle set to THR_MAX and the airspeed set to the
- * default value. For electric aircraft make sure this number can be
- * achieved towards the end of flight when the battery voltage has reduced.
- * The setting of this parameter can be checked by commanding a positive
- * altitude change of 100m in loiter, RTL or guided mode. If the throttle
- * required to climb is close to THR_MAX and the aircraft is maintaining
- * airspeed, then this parameter is set correctly. If the airspeed starts
- * to reduce, then the parameter is set to high, and if the throttle
- * demand required to climb and maintain speed is noticeably less than
- * FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or
+ * This is the best climb rate that the aircraft can achieve with
+ * the throttle set to THR_MAX and the airspeed set to the
+ * default value. For electric aircraft make sure this number can be
+ * achieved towards the end of flight when the battery voltage has reduced.
+ * The setting of this parameter can be checked by commanding a positive
+ * altitude change of 100m in loiter, RTL or guided mode. If the throttle
+ * required to climb is close to THR_MAX and the aircraft is maintaining
+ * airspeed, then this parameter is set correctly. If the airspeed starts
+ * to reduce, then the parameter is set to high, and if the throttle
+ * demand required to climb and maintain speed is noticeably less than
+ * FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or
* FW_THR_MAX reduced.
*
* @group L1 Control
@@ -177,57 +200,68 @@ PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
/**
* Minimum descent rate
*
- * This is the sink rate of the aircraft with the throttle
- * set to THR_MIN and flown at the same airspeed as used
+ * This is the sink rate of the aircraft with the throttle
+ * set to THR_MIN and flown at the same airspeed as used
* to measure FW_T_CLMB_MAX.
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f);
/**
* Maximum descent rate
*
- * This sets the maximum descent rate that the controller will use.
- * If this value is too large, the aircraft can over-speed on descent.
- * This should be set to a value that can be achieved without
- * exceeding the lower pitch angle limit and without over-speeding
+ * This sets the maximum descent rate that the controller will use.
+ * If this value is too large, the aircraft can over-speed on descent.
+ * This should be set to a value that can be achieved without
+ * exceeding the lower pitch angle limit and without over-speeding
* the aircraft.
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
/**
* TECS time constant
*
- * This is the time constant of the TECS control algorithm (in seconds).
+ * This is the time constant of the TECS control algorithm (in seconds).
* Smaller values make it faster to respond, larger values make it slower
* to respond.
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
/**
+ * TECS Throttle time constant
+ *
+ * This is the time constant of the TECS throttle control algorithm (in seconds).
+ * Smaller values make it faster to respond, larger values make it slower
+ * to respond.
+ *
+ * @group Fixed Wing TECS
+ */
+PARAM_DEFINE_FLOAT(FW_T_THRO_CONST, 8.0f);
+
+/**
* Throttle damping factor
*
- * This is the damping gain for the throttle demand loop.
+ * This is the damping gain for the throttle demand loop.
* Increase to add damping to correct for oscillations in speed and height.
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
/**
* Integrator gain
*
- * This is the integrator gain on the control loop.
- * Increasing this gain increases the speed at which speed
- * and height offsets are trimmed out, but reduces damping and
+ * This is the integrator gain on the control loop.
+ * Increasing this gain increases the speed at which speed
+ * and height offsets are trimmed out, but reduces damping and
* increases overshoot.
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
@@ -235,98 +269,105 @@ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
* Maximum vertical acceleration
*
* This is the maximum vertical acceleration (in metres/second square)
- * either up or down that the controller will use to correct speed
- * or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g)
- * allows for reasonably aggressive pitch changes if required to recover
+ * either up or down that the controller will use to correct speed
+ * or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g)
+ * allows for reasonably aggressive pitch changes if required to recover
* from under-speed conditions.
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
/**
* Complementary filter "omega" parameter for height
*
- * This is the cross-over frequency (in radians/second) of the complementary
- * filter used to fuse vertical acceleration and barometric height to obtain
- * an estimate of height rate and height. Increasing this frequency weights
- * the solution more towards use of the barometer, whilst reducing it weights
+ * This is the cross-over frequency (in radians/second) of the complementary
+ * filter used to fuse vertical acceleration and barometric height to obtain
+ * an estimate of height rate and height. Increasing this frequency weights
+ * the solution more towards use of the barometer, whilst reducing it weights
* the solution more towards use of the accelerometer data.
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
/**
* Complementary filter "omega" parameter for speed
*
- * This is the cross-over frequency (in radians/second) of the complementary
- * filter used to fuse longitudinal acceleration and airspeed to obtain an
+ * This is the cross-over frequency (in radians/second) of the complementary
+ * filter used to fuse longitudinal acceleration and airspeed to obtain an
* improved airspeed estimate. Increasing this frequency weights the solution
- * more towards use of the arispeed sensor, whilst reducing it weights the
+ * more towards use of the arispeed sensor, whilst reducing it weights the
* solution more towards use of the accelerometer data.
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
/**
* Roll -> Throttle feedforward
*
- * Increasing this gain turn increases the amount of throttle that will
- * be used to compensate for the additional drag created by turning.
- * Ideally this should be set to approximately 10 x the extra sink rate
- * in m/s created by a 45 degree bank turn. Increase this gain if
- * the aircraft initially loses energy in turns and reduce if the
- * aircraft initially gains energy in turns. Efficient high aspect-ratio
- * aircraft (eg powered sailplanes) can use a lower value, whereas
+ * Increasing this gain turn increases the amount of throttle that will
+ * be used to compensate for the additional drag created by turning.
+ * Ideally this should be set to approximately 10 x the extra sink rate
+ * in m/s created by a 45 degree bank turn. Increase this gain if
+ * the aircraft initially loses energy in turns and reduce if the
+ * aircraft initially gains energy in turns. Efficient high aspect-ratio
+ * aircraft (eg powered sailplanes) can use a lower value, whereas
* inefficient low aspect-ratio models (eg delta wings) can use a higher value.
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f);
/**
* Speed <--> Altitude priority
*
- * This parameter adjusts the amount of weighting that the pitch control
- * applies to speed vs height errors. Setting it to 0.0 will cause the
- * pitch control to control height and ignore speed errors. This will
- * normally improve height accuracy but give larger airspeed errors.
- * Setting it to 2.0 will cause the pitch control loop to control speed
- * and ignore height errors. This will normally reduce airspeed errors,
- * but give larger height errors. The default value of 1.0 allows the pitch
- * control to simultaneously control height and speed.
- * Note to Glider Pilots - set this parameter to 2.0 (The glider will
+ * This parameter adjusts the amount of weighting that the pitch control
+ * applies to speed vs height errors. Setting it to 0.0 will cause the
+ * pitch control to control height and ignore speed errors. This will
+ * normally improve height accuracy but give larger airspeed errors.
+ * Setting it to 2.0 will cause the pitch control loop to control speed
+ * and ignore height errors. This will normally reduce airspeed errors,
+ * but give larger height errors. The default value of 1.0 allows the pitch
+ * control to simultaneously control height and speed.
+ * Note to Glider Pilots - set this parameter to 2.0 (The glider will
* adjust its pitch angle to maintain airspeed, ignoring changes in height).
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
/**
* Pitch damping factor
*
- * This is the damping gain for the pitch demand loop. Increase to add
- * damping to correct for oscillations in height. The default value of 0.0
- * will work well provided the pitch to servo controller has been tuned
+ * This is the damping gain for the pitch demand loop. Increase to add
+ * damping to correct for oscillations in height. The default value of 0.0
+ * will work well provided the pitch to servo controller has been tuned
* properly.
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
/**
* Height rate P factor
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
/**
+ * Height rate FF factor
+ *
+ * @group Fixed Wing TECS
+ */
+PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.0f);
+
+/**
* Speed rate P factor
*
- * @group L1 Control
+ * @group Fixed Wing TECS
*/
PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f);
@@ -345,18 +386,23 @@ PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f);
PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f);
/**
- * Landing flare altitude (relative)
+ * Landing flare altitude (relative to landing altitude)
*
+ * @unit meter
* @group L1 Control
*/
-PARAM_DEFINE_FLOAT(FW_LND_FLALT, 15.0f);
+PARAM_DEFINE_FLOAT(FW_LND_FLALT, 8.0f);
/**
- * Landing throttle limit altitude (relative)
+ * Landing throttle limit altitude (relative landing altitude)
+ *
+ * Default of -1.0f lets the system default to applying throttle
+ * limiting at 2/3 of the flare altitude.
*
+ * @unit meter
* @group L1 Control
*/
-PARAM_DEFINE_FLOAT(FW_LND_TLALT, 5.0f);
+PARAM_DEFINE_FLOAT(FW_LND_TLALT, -1.0f);
/**
* Landing heading hold horizontal distance
@@ -366,12 +412,28 @@ PARAM_DEFINE_FLOAT(FW_LND_TLALT, 5.0f);
PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
/**
- * Relative altitude threshold for range finder measurements for use during landing
+ * Enable or disable usage of terrain estimate during landing
*
- * range finder measurements will only be used if the estimated relative altitude (gobal_pos.alt - landing_waypoint.alt) is < FW_LND_RFRALT
- * set to < 0 to disable
- * the correct value of this parameter depends on your range measuring device as well as on the terrain at the landing location
+ * 0: disabled, 1: enabled
*
* @group L1 Control
*/
-PARAM_DEFINE_FLOAT(FW_LND_RFRALT, -1.0f);
+PARAM_DEFINE_INT32(FW_LND_USETER, 0);
+
+/**
+ * Flare, minimum pitch
+ *
+ * Minimum pitch during flare, a positive sign means nose up
+ * Applied once FW_LND_TLALT is reached
+ *
+ */
+PARAM_DEFINE_FLOAT(FW_FLARE_PMIN, 2.5f);
+
+/**
+ * Flare, maximum pitch
+ *
+ * Maximum pitch during flare, a positive sign means nose up
+ * Applied once FW_LND_TLALT is reached
+ *
+ */
+PARAM_DEFINE_FLOAT(FW_FLARE_PMAX, 15.0f);
diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
index afc411a60..bffeefc1f 100644
--- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
+++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
@@ -76,7 +76,6 @@ mTecs::mTecs() :
_counter(0),
_debug(false)
{
- warnx("starting");
}
mTecs::~mTecs()
@@ -110,8 +109,7 @@ int mTecs::updateAltitudeSpeed(float flightPathAngle, float altitude, float alti
/* Write part of the status message */
_status.altitudeSp = altitudeSp;
- _status.altitude = altitude;
- _status.altitudeFiltered = altitudeFiltered;
+ _status.altitude_filtered = altitudeFiltered;
/* use flightpath angle setpoint for total energy control */
@@ -147,8 +145,7 @@ int mTecs::updateFlightPathAngleSpeed(float flightPathAngle, float flightPathAng
/* Write part of the status message */
_status.airspeedSp = airspeedSp;
- _status.airspeed = airspeed;
- _status.airspeedFiltered = airspeedFiltered;
+ _status.airspeed_filtered = airspeedFiltered;
/* use longitudinal acceleration setpoint for total energy control */
diff --git a/src/modules/gpio_led/module.mk b/src/modules/gpio_led/module.mk
index 3b8553489..70c75b10c 100644
--- a/src/modules/gpio_led/module.mk
+++ b/src/modules/gpio_led/module.mk
@@ -37,3 +37,5 @@
MODULE_COMMAND = gpio_led
SRCS = gpio_led.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index e49288a74..9afe74af1 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -68,14 +68,17 @@ PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING);
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_USEHILGPS, 0);
+/**
+ * Forward external setpoint messages
+ * If set to 1 incomming external setpoint messages will be directly forwarded to the controllers if in offboard
+ * control mode
+ * @group MAVLink
+ */
+PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1);
mavlink_system_t mavlink_system = {
100,
- 50,
- MAV_TYPE_FIXED_WING,
- 0,
- 0,
- 0
+ 50
}; // System ID, 1-255, Component/Subsystem ID, 1-255
/*
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index 6a2c900af..f17497aa8 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -31,34 +31,39 @@
*
****************************************************************************/
+/// @file mavlink_ftp.cpp
+/// @author px4dev, Don Gagne <don@thegagnes.com>
+
#include <crc32.h>
#include <unistd.h>
#include <stdio.h>
#include <fcntl.h>
+#include <sys/stat.h>
+#include <errno.h>
#include "mavlink_ftp.h"
+#include "mavlink_tests/mavlink_ftp_test.h"
-MavlinkFTP *MavlinkFTP::_server;
+// Uncomment the line below to get better debug output. Never commit with this left on.
+//#define MAVLINK_FTP_DEBUG
MavlinkFTP *
-MavlinkFTP::getServer()
+MavlinkFTP::get_server(void)
{
- // XXX this really cries out for some locking...
- if (_server == nullptr) {
- _server = new MavlinkFTP;
- }
- return _server;
+ static MavlinkFTP server;
+ return &server;
}
MavlinkFTP::MavlinkFTP() :
- _session_fds{},
- _workBufs{},
- _workFree{},
- _lock{}
+ _request_bufs{},
+ _request_queue{},
+ _request_queue_sem{},
+ _utRcvMsgFunc{},
+ _ftp_test{}
{
// initialise the request freelist
- dq_init(&_workFree);
- sem_init(&_lock, 0, 1);
+ dq_init(&_request_queue);
+ sem_init(&_request_queue_sem, 0, 1);
// initialize session list
for (size_t i=0; i<kMaxSession; i++) {
@@ -67,173 +72,278 @@ MavlinkFTP::MavlinkFTP() :
// drop work entries onto the free list
for (unsigned i = 0; i < kRequestQueueSize; i++) {
- _qFree(&_workBufs[i]);
+ _return_request(&_request_bufs[i]);
}
}
+#ifdef MAVLINK_FTP_UNIT_TEST
+void
+MavlinkFTP::set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, MavlinkFtpTest *ftp_test)
+{
+ _utRcvMsgFunc = rcvMsgFunc;
+ _ftp_test = ftp_test;
+}
+#endif
+
void
MavlinkFTP::handle_message(Mavlink* mavlink, mavlink_message_t *msg)
{
// get a free request
- auto req = _dqFree();
+ struct Request* req = _get_request();
// if we couldn't get a request slot, just drop it
- if (req != nullptr) {
-
- // decode the request
- if (req->decode(mavlink, msg)) {
+ if (req == nullptr) {
+ warnx("Dropping FTP request: queue full\n");
+ return;
+ }
- // and queue it for the worker
- work_queue(LPWORK, &req->work, &MavlinkFTP::_workerTrampoline, req, 0);
- } else {
- _qFree(req);
+ if (msg->msgid == MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
+ mavlink_msg_file_transfer_protocol_decode(msg, &req->message);
+
+#ifdef MAVLINK_FTP_UNIT_TEST
+ if (!_utRcvMsgFunc) {
+ warnx("Incorrectly written unit test\n");
+ return;
+ }
+ // We use fake ids when unit testing
+ req->serverSystemId = MavlinkFtpTest::serverSystemId;
+ req->serverComponentId = MavlinkFtpTest::serverComponentId;
+ req->serverChannel = MavlinkFtpTest::serverChannel;
+#else
+ // Not unit testing, use the real thing
+ req->serverSystemId = mavlink->get_system_id();
+ req->serverComponentId = mavlink->get_component_id();
+ req->serverChannel = mavlink->get_channel();
+#endif
+
+ // This is the system id we want to target when sending
+ req->targetSystemId = msg->sysid;
+
+ if (req->message.target_system == req->serverSystemId) {
+ req->mavlink = mavlink;
+#ifdef MAVLINK_FTP_UNIT_TEST
+ // We are running in Unit Test mode. Don't queue, just call _worket directly.
+ _process_request(req);
+#else
+ // We are running in normal mode. Queue the request to the worker
+ work_queue(LPWORK, &req->work, &MavlinkFTP::_worker_trampoline, req, 0);
+#endif
+ return;
}
}
+
+ _return_request(req);
}
+/// @brief Queued static work queue routine to handle mavlink messages
void
-MavlinkFTP::_workerTrampoline(void *arg)
+MavlinkFTP::_worker_trampoline(void *arg)
{
- auto req = reinterpret_cast<Request *>(arg);
- auto server = MavlinkFTP::getServer();
+ Request* req = reinterpret_cast<Request *>(arg);
+ MavlinkFTP* server = MavlinkFTP::get_server();
// call the server worker with the work item
- server->_worker(req);
+ server->_process_request(req);
}
+/// @brief Processes an FTP message
void
-MavlinkFTP::_worker(Request *req)
+MavlinkFTP::_process_request(Request *req)
{
- auto hdr = req->header();
+ PayloadHeader *payload = reinterpret_cast<PayloadHeader *>(&req->message.payload[0]);
+
ErrorCode errorCode = kErrNone;
- uint32_t messageCRC;
// basic sanity checks; must validate length before use
- if ((hdr->magic != kProtocolMagic) || (hdr->size > kMaxDataLength)) {
- errorCode = kErrNoRequest;
+ if (payload->size > kMaxDataLength) {
+ errorCode = kErrInvalidDataSize;
goto out;
}
- // check request CRC to make sure this is one of ours
- messageCRC = hdr->crc32;
- hdr->crc32 = 0;
- if (crc32(req->rawData(), req->dataSize()) != messageCRC) {
- errorCode = kErrNoRequest;
- goto out;
- warnx("ftp: bad crc");
- }
-
- //printf("ftp: channel %u opc %u size %u offset %u\n", req->channel(), hdr->opcode, hdr->size, hdr->offset);
+#ifdef MAVLINK_FTP_DEBUG
+ printf("ftp: channel %u opc %u size %u offset %u\n", req->serverChannel, payload->opcode, payload->size, payload->offset);
+#endif
- switch (hdr->opcode) {
+ switch (payload->opcode) {
case kCmdNone:
break;
- case kCmdTerminate:
- errorCode = _workTerminate(req);
+ case kCmdTerminateSession:
+ errorCode = _workTerminate(payload);
break;
- case kCmdReset:
- errorCode = _workReset();
+ case kCmdResetSessions:
+ errorCode = _workReset(payload);
break;
- case kCmdList:
- errorCode = _workList(req);
+ case kCmdListDirectory:
+ errorCode = _workList(payload);
break;
- case kCmdOpen:
- errorCode = _workOpen(req, false);
+ case kCmdOpenFileRO:
+ errorCode = _workOpen(payload, O_RDONLY);
break;
- case kCmdCreate:
- errorCode = _workOpen(req, true);
+ case kCmdCreateFile:
+ errorCode = _workOpen(payload, O_CREAT | O_EXCL | O_WRONLY);
break;
- case kCmdRead:
- errorCode = _workRead(req);
+ case kCmdOpenFileWO:
+ errorCode = _workOpen(payload, O_CREAT | O_WRONLY);
break;
- case kCmdWrite:
- errorCode = _workWrite(req);
+ case kCmdReadFile:
+ errorCode = _workRead(payload);
break;
- case kCmdRemove:
- errorCode = _workRemove(req);
+ case kCmdWriteFile:
+ errorCode = _workWrite(payload);
+ break;
+
+ case kCmdRemoveFile:
+ errorCode = _workRemoveFile(payload);
+ break;
+
+ case kCmdRename:
+ errorCode = _workRename(payload);
+ break;
+
+ case kCmdTruncateFile:
+ errorCode = _workTruncateFile(payload);
+ break;
+
+ case kCmdCreateDirectory:
+ errorCode = _workCreateDirectory(payload);
+ break;
+
+ case kCmdRemoveDirectory:
+ errorCode = _workRemoveDirectory(payload);
+ break;
+
+
+ case kCmdCalcFileCRC32:
+ errorCode = _workCalcFileCRC32(payload);
break;
default:
- errorCode = kErrNoRequest;
+ errorCode = kErrUnknownCommand;
break;
}
out:
// handle success vs. error
if (errorCode == kErrNone) {
- hdr->opcode = kRspAck;
- //warnx("FTP: ack\n");
+ payload->req_opcode = payload->opcode;
+ payload->opcode = kRspAck;
+#ifdef MAVLINK_FTP_DEBUG
+ warnx("FTP: ack\n");
+#endif
} else {
+ int r_errno = errno;
warnx("FTP: nak %u", errorCode);
- hdr->opcode = kRspNak;
- hdr->size = 1;
- hdr->data[0] = errorCode;
+ payload->req_opcode = payload->opcode;
+ payload->opcode = kRspNak;
+ payload->size = 1;
+ payload->data[0] = errorCode;
+ if (errorCode == kErrFailErrno) {
+ payload->size = 2;
+ payload->data[1] = r_errno;
+ }
}
+
// respond to the request
_reply(req);
- // free the request buffer back to the freelist
- _qFree(req);
+ _return_request(req);
}
+/// @brief Sends the specified FTP reponse message out through mavlink
void
MavlinkFTP::_reply(Request *req)
{
- auto hdr = req->header();
-
- // message is assumed to be already constructed in the request buffer, so generate the CRC
- hdr->crc32 = 0;
- hdr->crc32 = crc32(req->rawData(), req->dataSize());
+ PayloadHeader *payload = reinterpret_cast<PayloadHeader *>(&req->message.payload[0]);
+
+ payload->seqNumber = payload->seqNumber + 1;
+
+ mavlink_message_t msg;
+ msg.checksum = 0;
+#ifndef MAVLINK_FTP_UNIT_TEST
+ uint16_t len =
+#endif
+ mavlink_msg_file_transfer_protocol_pack_chan(req->serverSystemId, // Sender system id
+ req->serverComponentId, // Sender component id
+ req->serverChannel, // Channel to send on
+ &msg, // Message to pack payload into
+ 0, // Target network
+ req->targetSystemId, // Target system id
+ 0, // Target component id
+ (const uint8_t*)payload); // Payload to pack into message
+
+ bool success = true;
+#ifdef MAVLINK_FTP_UNIT_TEST
+ // Unit test hook is set, call that instead
+ _utRcvMsgFunc(&msg, _ftp_test);
+#else
+ Mavlink *mavlink = req->mavlink;
+
+ mavlink->lockMessageBufferMutex();
+ success = mavlink->message_buffer_write(&msg, len);
+ mavlink->unlockMessageBufferMutex();
+
+#endif
- // then pack and send the reply back to the request source
- req->reply();
+ if (!success) {
+ warnx("FTP TX ERR");
+ }
+#ifdef MAVLINK_FTP_DEBUG
+ else {
+ warnx("wrote: sys: %d, comp: %d, chan: %d, checksum: %d",
+ req->serverSystemId,
+ req->serverComponentId,
+ req->serverChannel,
+ msg.checksum);
+ }
+#endif
}
+/// @brief Responds to a List command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workList(Request *req)
+MavlinkFTP::_workList(PayloadHeader* payload)
{
- auto hdr = req->header();
-
char dirPath[kMaxDataLength];
- strncpy(dirPath, req->dataAsCString(), kMaxDataLength);
+ strncpy(dirPath, _data_as_cstring(payload), kMaxDataLength);
DIR *dp = opendir(dirPath);
if (dp == nullptr) {
warnx("FTP: can't open path '%s'", dirPath);
- return kErrNotDir;
+ return kErrFailErrno;
}
- //warnx("FTP: list %s offset %d", dirPath, hdr->offset);
+#ifdef MAVLINK_FTP_DEBUG
+ warnx("FTP: list %s offset %d", dirPath, payload->offset);
+#endif
ErrorCode errorCode = kErrNone;
struct dirent entry, *result = nullptr;
unsigned offset = 0;
// move to the requested offset
- seekdir(dp, hdr->offset);
+ seekdir(dp, payload->offset);
for (;;) {
// read the directory entry
if (readdir_r(dp, &entry, &result)) {
warnx("FTP: list %s readdir_r failure\n", dirPath);
- errorCode = kErrIO;
+ errorCode = kErrFailErrno;
break;
}
// no more entries?
if (result == nullptr) {
- if (hdr->offset != 0 && offset == 0) {
+ if (payload->offset != 0 && offset == 0) {
// User is requesting subsequent dir entries but there were none. This means the user asked
// to seek past EOF.
errorCode = kErrEOF;
@@ -242,144 +352,277 @@ MavlinkFTP::_workList(Request *req)
break;
}
- // name too big to fit?
- if ((strlen(entry.d_name) + offset + 2) > kMaxDataLength) {
- break;
- }
+ uint32_t fileSize = 0;
+ char buf[256];
+ char direntType;
- // store the type marker
+ // Determine the directory entry type
switch (entry.d_type) {
case DTYPE_FILE:
- hdr->data[offset++] = kDirentFile;
+ // For files we get the file size as well
+ direntType = kDirentFile;
+ snprintf(buf, sizeof(buf), "%s/%s", dirPath, entry.d_name);
+ struct stat st;
+ if (stat(buf, &st) == 0) {
+ fileSize = st.st_size;
+ }
break;
case DTYPE_DIRECTORY:
- hdr->data[offset++] = kDirentDir;
+ if (strcmp(entry.d_name, ".") == 0 || strcmp(entry.d_name, "..") == 0) {
+ // Don't bother sending these back
+ direntType = kDirentSkip;
+ } else {
+ direntType = kDirentDir;
+ }
break;
default:
- hdr->data[offset++] = kDirentUnknown;
- break;
+ // We only send back file and diretory entries, skip everything else
+ direntType = kDirentSkip;
}
+
+ if (direntType == kDirentSkip) {
+ // Skip send only dirent identifier
+ buf[0] = '\0';
+ } else if (direntType == kDirentFile) {
+ // Files send filename and file length
+ snprintf(buf, sizeof(buf), "%s\t%d", entry.d_name, fileSize);
+ } else {
+ // Everything else just sends name
+ strncpy(buf, entry.d_name, sizeof(buf));
+ buf[sizeof(buf)-1] = 0;
+ }
+ size_t nameLen = strlen(buf);
- // copy the name, which we know will fit
- strcpy((char *)&hdr->data[offset], entry.d_name);
- //printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]);
- offset += strlen(entry.d_name) + 1;
+ // Do we have room for the name, the one char directory identifier and the null terminator?
+ if ((offset + nameLen + 2) > kMaxDataLength) {
+ break;
+ }
+
+ // Move the data into the buffer
+ payload->data[offset++] = direntType;
+ strcpy((char *)&payload->data[offset], buf);
+#ifdef MAVLINK_FTP_DEBUG
+ printf("FTP: list %s %s\n", dirPath, (char *)&payload->data[offset-1]);
+#endif
+ offset += nameLen + 1;
}
closedir(dp);
- hdr->size = offset;
+ payload->size = offset;
return errorCode;
}
+/// @brief Responds to an Open command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workOpen(Request *req, bool create)
+MavlinkFTP::_workOpen(PayloadHeader* payload, int oflag)
{
- auto hdr = req->header();
-
- int session_index = _findUnusedSession();
+ int session_index = _find_unused_session();
if (session_index < 0) {
- return kErrNoSession;
+ warnx("FTP: Open failed - out of sessions\n");
+ return kErrNoSessionsAvailable;
}
- int oflag = create ? (O_CREAT | O_EXCL | O_APPEND) : O_RDONLY;
-
- int fd = ::open(req->dataAsCString(), oflag);
+ char *filename = _data_as_cstring(payload);
+
+ uint32_t fileSize = 0;
+ struct stat st;
+ if (stat(filename, &st) != 0) {
+ // fail only if requested open for read
+ if (oflag & O_RDONLY)
+ return kErrFailErrno;
+ else
+ st.st_size = 0;
+ }
+ fileSize = st.st_size;
+
+ int fd = ::open(filename, oflag);
if (fd < 0) {
- return create ? kErrPerm : kErrNotFile;
+ return kErrFailErrno;
}
_session_fds[session_index] = fd;
- hdr->session = session_index;
- hdr->size = 0;
+ payload->session = session_index;
+ payload->size = sizeof(uint32_t);
+ *((uint32_t*)payload->data) = fileSize;
return kErrNone;
}
+/// @brief Responds to a Read command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workRead(Request *req)
+MavlinkFTP::_workRead(PayloadHeader* payload)
{
- auto hdr = req->header();
-
- int session_index = hdr->session;
+ int session_index = payload->session;
- if (!_validSession(session_index)) {
- return kErrNoSession;
+ if (!_valid_session(session_index)) {
+ return kErrInvalidSession;
}
// Seek to the specified position
- //warnx("seek %d", hdr->offset);
- if (lseek(_session_fds[session_index], hdr->offset, SEEK_SET) < 0) {
+#ifdef MAVLINK_FTP_DEBUG
+ warnx("seek %d", payload->offset);
+#endif
+ if (lseek(_session_fds[session_index], payload->offset, SEEK_SET) < 0) {
// Unable to see to the specified location
warnx("seek fail");
return kErrEOF;
}
- int bytes_read = ::read(_session_fds[session_index], &hdr->data[0], kMaxDataLength);
+ int bytes_read = ::read(_session_fds[session_index], &payload->data[0], kMaxDataLength);
if (bytes_read < 0) {
// Negative return indicates error other than eof
warnx("read fail %d", bytes_read);
- return kErrIO;
+ return kErrFailErrno;
}
- hdr->size = bytes_read;
+ payload->size = bytes_read;
return kErrNone;
}
+/// @brief Responds to a Write command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workWrite(Request *req)
+MavlinkFTP::_workWrite(PayloadHeader* payload)
{
-#if 0
- // NYI: Coming soon
- auto hdr = req->header();
+ int session_index = payload->session;
- // look up session
- auto session = getSession(hdr->session);
- if (session == nullptr) {
- return kErrNoSession;
+ if (!_valid_session(session_index)) {
+ return kErrInvalidSession;
}
- // append to file
- int result = session->append(hdr->offset, &hdr->data[0], hdr->size);
+ // Seek to the specified position
+#ifdef MAVLINK_FTP_DEBUG
+ warnx("seek %d", payload->offset);
+#endif
+ if (lseek(_session_fds[session_index], payload->offset, SEEK_SET) < 0) {
+ // Unable to see to the specified location
+ warnx("seek fail");
+ return kErrFailErrno;
+ }
- if (result < 0) {
- // XXX might also be no space, I/O, etc.
- return kErrNotAppend;
+ int bytes_written = ::write(_session_fds[session_index], &payload->data[0], payload->size);
+ if (bytes_written < 0) {
+ // Negative return indicates error other than eof
+ warnx("write fail %d", bytes_written);
+ return kErrFailErrno;
}
- hdr->size = result;
+ payload->size = sizeof(uint32_t);
+ *((uint32_t*)payload->data) = bytes_written;
+
return kErrNone;
-#else
- return kErrPerm;
-#endif
}
+/// @brief Responds to a RemoveFile command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workRemoveFile(PayloadHeader* payload)
+{
+ char file[kMaxDataLength];
+ strncpy(file, _data_as_cstring(payload), kMaxDataLength);
+
+ if (unlink(file) == 0) {
+ payload->size = 0;
+ return kErrNone;
+ } else {
+ return kErrFailErrno;
+ }
+}
+
+/// @brief Responds to a TruncateFile command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workRemove(Request *req)
+MavlinkFTP::_workTruncateFile(PayloadHeader* payload)
{
- //auto hdr = req->header();
+ char file[kMaxDataLength];
+ const char temp_file[] = "/fs/microsd/.trunc.tmp";
+ strncpy(file, _data_as_cstring(payload), kMaxDataLength);
+ payload->size = 0;
+
+ // emulate truncate(file, payload->offset) by
+ // copying to temp and overwrite with O_TRUNC flag.
+
+ struct stat st;
+ if (stat(file, &st) != 0) {
+ return kErrFailErrno;
+ }
+
+ if (!S_ISREG(st.st_mode)) {
+ errno = EISDIR;
+ return kErrFailErrno;
+ }
+
+ // check perms allow us to write (not romfs)
+ if (!(st.st_mode & (S_IWUSR | S_IWGRP | S_IWOTH))) {
+ errno = EROFS;
+ return kErrFailErrno;
+ }
+
+ if (payload->offset == (unsigned)st.st_size) {
+ // nothing to do
+ return kErrNone;
+ }
+ else if (payload->offset == 0) {
+ // 1: truncate all data
+ int fd = ::open(file, O_TRUNC | O_WRONLY);
+ if (fd < 0) {
+ return kErrFailErrno;
+ }
- // for now, send error reply
- return kErrPerm;
+ ::close(fd);
+ return kErrNone;
+ }
+ else if (payload->offset > (unsigned)st.st_size) {
+ // 2: extend file
+ int fd = ::open(file, O_WRONLY);
+ if (fd < 0) {
+ return kErrFailErrno;
+ }
+
+ if (lseek(fd, payload->offset - 1, SEEK_SET) < 0) {
+ ::close(fd);
+ return kErrFailErrno;
+ }
+
+ bool ok = 1 == ::write(fd, "", 1);
+ ::close(fd);
+
+ return (ok)? kErrNone : kErrFailErrno;
+ }
+ else {
+ // 3: truncate
+ if (_copy_file(file, temp_file, payload->offset) != 0) {
+ return kErrFailErrno;
+ }
+ if (_copy_file(temp_file, file, payload->offset) != 0) {
+ return kErrFailErrno;
+ }
+ if (::unlink(temp_file) != 0) {
+ return kErrFailErrno;
+ }
+
+ return kErrNone;
+ }
}
+/// @brief Responds to a Terminate command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workTerminate(Request *req)
+MavlinkFTP::_workTerminate(PayloadHeader* payload)
{
- auto hdr = req->header();
-
- if (!_validSession(hdr->session)) {
- return kErrNoSession;
+ if (!_valid_session(payload->session)) {
+ return kErrInvalidSession;
}
- ::close(_session_fds[hdr->session]);
+ ::close(_session_fds[payload->session]);
+ _session_fds[payload->session] = -1;
+
+ payload->size = 0;
return kErrNone;
}
+/// @brief Responds to a Reset command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workReset(void)
+MavlinkFTP::_workReset(PayloadHeader* payload)
{
for (size_t i=0; i<kMaxSession; i++) {
if (_session_fds[i] != -1) {
@@ -388,11 +631,104 @@ MavlinkFTP::_workReset(void)
}
}
+ payload->size = 0;
+
return kErrNone;
}
+/// @brief Responds to a Rename command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workRename(PayloadHeader* payload)
+{
+ char oldpath[kMaxDataLength];
+ char newpath[kMaxDataLength];
+
+ char *ptr = _data_as_cstring(payload);
+ size_t oldpath_sz = strlen(ptr);
+
+ if (oldpath_sz == payload->size) {
+ // no newpath
+ errno = EINVAL;
+ return kErrFailErrno;
+ }
+
+ strncpy(oldpath, ptr, kMaxDataLength);
+ strncpy(newpath, ptr + oldpath_sz + 1, kMaxDataLength);
+
+ if (rename(oldpath, newpath) == 0) {
+ payload->size = 0;
+ return kErrNone;
+ } else {
+ return kErrFailErrno;
+ }
+}
+
+/// @brief Responds to a RemoveDirectory command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workRemoveDirectory(PayloadHeader* payload)
+{
+ char dir[kMaxDataLength];
+ strncpy(dir, _data_as_cstring(payload), kMaxDataLength);
+
+ if (rmdir(dir) == 0) {
+ payload->size = 0;
+ return kErrNone;
+ } else {
+ return kErrFailErrno;
+ }
+}
+
+/// @brief Responds to a CreateDirectory command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workCreateDirectory(PayloadHeader* payload)
+{
+ char dir[kMaxDataLength];
+ strncpy(dir, _data_as_cstring(payload), kMaxDataLength);
+
+ if (mkdir(dir, S_IRWXU | S_IRWXG | S_IRWXO) == 0) {
+ payload->size = 0;
+ return kErrNone;
+ } else {
+ return kErrFailErrno;
+ }
+}
+
+/// @brief Responds to a CalcFileCRC32 command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workCalcFileCRC32(PayloadHeader* payload)
+{
+ char file_buf[256];
+ uint32_t checksum = 0;
+ ssize_t bytes_read;
+ strncpy(file_buf, _data_as_cstring(payload), kMaxDataLength);
+
+ int fd = ::open(file_buf, O_RDONLY);
+ if (fd < 0) {
+ return kErrFailErrno;
+ }
+
+ do {
+ bytes_read = ::read(fd, file_buf, sizeof(file_buf));
+ if (bytes_read < 0) {
+ int r_errno = errno;
+ ::close(fd);
+ errno = r_errno;
+ return kErrFailErrno;
+ }
+
+ checksum = crc32part((uint8_t*)file_buf, bytes_read, checksum);
+ } while (bytes_read == sizeof(file_buf));
+
+ ::close(fd);
+
+ payload->size = sizeof(uint32_t);
+ *((uint32_t*)payload->data) = checksum;
+ return kErrNone;
+}
+
+/// @brief Returns true if the specified session is a valid open session
bool
-MavlinkFTP::_validSession(unsigned index)
+MavlinkFTP::_valid_session(unsigned index)
{
if ((index >= kMaxSession) || (_session_fds[index] < 0)) {
return false;
@@ -400,8 +736,9 @@ MavlinkFTP::_validSession(unsigned index)
return true;
}
+/// @brief Returns an unused session index
int
-MavlinkFTP::_findUnusedSession(void)
+MavlinkFTP::_find_unused_session(void)
{
for (size_t i=0; i<kMaxSession; i++) {
if (_session_fds[i] == -1) {
@@ -412,16 +749,105 @@ MavlinkFTP::_findUnusedSession(void)
return -1;
}
+/// @brief Guarantees that the payload data is null terminated.
+/// @return Returns a pointer to the payload data as a char *
char *
-MavlinkFTP::Request::dataAsCString()
+MavlinkFTP::_data_as_cstring(PayloadHeader* payload)
{
// guarantee nul termination
- if (header()->size < kMaxDataLength) {
- requestData()[header()->size] = '\0';
+ if (payload->size < kMaxDataLength) {
+ payload->data[payload->size] = '\0';
} else {
- requestData()[kMaxDataLength - 1] = '\0';
+ payload->data[kMaxDataLength - 1] = '\0';
}
// and return data
- return (char *)&(header()->data[0]);
+ return (char *)&(payload->data[0]);
+}
+
+/// @brief Returns a unused Request entry. NULL if none available.
+MavlinkFTP::Request *
+MavlinkFTP::_get_request(void)
+{
+ _lock_request_queue();
+ Request* req = reinterpret_cast<Request *>(dq_remfirst(&_request_queue));
+ _unlock_request_queue();
+ return req;
+}
+
+/// @brief Locks a semaphore to provide exclusive access to the request queue
+void
+MavlinkFTP::_lock_request_queue(void)
+{
+ do {}
+ while (sem_wait(&_request_queue_sem) != 0);
+}
+
+/// @brief Unlocks the semaphore providing exclusive access to the request queue
+void
+MavlinkFTP::_unlock_request_queue(void)
+{
+ sem_post(&_request_queue_sem);
+}
+
+/// @brief Returns a no longer needed request to the queue
+void
+MavlinkFTP::_return_request(Request *req)
+{
+ _lock_request_queue();
+ dq_addlast(&req->work.dq, &_request_queue);
+ _unlock_request_queue();
+}
+
+/// @brief Copy file (with limited space)
+int
+MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, ssize_t length)
+{
+ char buff[512];
+ int src_fd = -1, dst_fd = -1;
+ int op_errno = 0;
+
+ src_fd = ::open(src_path, O_RDONLY);
+ if (src_fd < 0) {
+ return -1;
+ }
+
+ dst_fd = ::open(dst_path, O_CREAT | O_TRUNC | O_WRONLY);
+ if (dst_fd < 0) {
+ op_errno = errno;
+ ::close(src_fd);
+ errno = op_errno;
+ return -1;
+ }
+
+ while (length > 0) {
+ ssize_t bytes_read, bytes_written;
+ size_t blen = (length > sizeof(buff))? sizeof(buff) : length;
+
+ bytes_read = ::read(src_fd, buff, blen);
+ if (bytes_read == 0) {
+ // EOF
+ break;
+ }
+ else if (bytes_read < 0) {
+ warnx("cp: read");
+ op_errno = errno;
+ break;
+ }
+
+ bytes_written = ::write(dst_fd, buff, bytes_read);
+ if (bytes_written != bytes_read) {
+ warnx("cp: short write");
+ op_errno = errno;
+ break;
+ }
+
+ length -= bytes_written;
+ }
+
+ ::close(src_fd);
+ ::close(dst_fd);
+
+ errno = op_errno;
+ return (length > 0)? -1 : 0;
}
diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h
index 1bd1158fb..bef6775a9 100644
--- a/src/modules/mavlink/mavlink_ftp.h
+++ b/src/modules/mavlink/mavlink_ftp.h
@@ -33,20 +33,8 @@
#pragma once
-/**
- * @file mavlink_ftp.h
- *
- * MAVLink remote file server.
- *
- * Messages are wrapped in ENCAPSULATED_DATA messages. Every message includes
- * a session ID and sequence number.
- *
- * A limited number of requests (currently 2) may be outstanding at a time.
- * Additional messages will be discarded.
- *
- * Messages consist of a fixed header, followed by a data area.
- *
- */
+/// @file mavlink_ftp.h
+/// @author px4dev, Don Gagne <don@thegagnes.com>
#include <dirent.h>
#include <queue.h>
@@ -57,172 +45,136 @@
#include "mavlink_messages.h"
#include "mavlink_main.h"
+class MavlinkFtpTest;
+
+/// @brief MAVLink remote file server. Support FTP like commands using MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL message.
+/// A limited number of requests (kRequestQueueSize) may be outstanding at a time. Additional messages will be discarded.
class MavlinkFTP
{
public:
+ /// @brief Returns the one Mavlink FTP server in the system.
+ static MavlinkFTP* get_server(void);
+
+ /// @brief Contructor is only public so unit test code can new objects.
MavlinkFTP();
-
- static MavlinkFTP *getServer();
-
- // static interface
- void handle_message(Mavlink* mavlink,
- mavlink_message_t *msg);
-
-private:
-
- static const unsigned kRequestQueueSize = 2;
-
- static MavlinkFTP *_server;
-
- struct RequestHeader
- {
- uint8_t magic;
- uint8_t session;
- uint8_t opcode;
- uint8_t size;
- uint32_t crc32;
- uint32_t offset;
- uint8_t data[];
- };
-
+
+ /// @brief Adds the specified message to the work queue.
+ void handle_message(Mavlink* mavlink, mavlink_message_t *msg);
+
+ typedef void (*ReceiveMessageFunc_t)(const mavlink_message_t *msg, MavlinkFtpTest* ftpTest);
+
+ /// @brief Sets up the server to run in unit test mode.
+ /// @param rcvmsgFunc Function which will be called to handle outgoing mavlink messages.
+ /// @param ftp_test MavlinkFtpTest object which the function is associated with
+ void set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, MavlinkFtpTest *ftp_test);
+
+ /// @brief This is the payload which is in mavlink_file_transfer_protocol_t.payload. We pad the structure ourselves to
+ /// 32 bit alignment to avoid usage of any pack pragmas.
+ struct PayloadHeader
+ {
+ uint16_t seqNumber; ///< sequence number for message
+ uint8_t session; ///< Session id for read and write commands
+ uint8_t opcode; ///< Command opcode
+ uint8_t size; ///< Size of data
+ uint8_t req_opcode; ///< Request opcode returned in kRspAck, kRspNak message
+ uint8_t padding[2]; ///< 32 bit aligment padding
+ uint32_t offset; ///< Offsets for List and Read commands
+ uint8_t data[]; ///< command data, varies by Opcode
+ };
+
+ /// @brief Command opcodes
enum Opcode : uint8_t
{
- kCmdNone, // ignored, always acked
- kCmdTerminate, // releases sessionID, closes file
- kCmdReset, // terminates all sessions
- kCmdList, // list files in <path> from <offset>
- kCmdOpen, // opens <path> for reading, returns <session>
- kCmdRead, // reads <size> bytes from <offset> in <session>
- kCmdCreate, // creates <path> for writing, returns <session>
- kCmdWrite, // appends <size> bytes at <offset> in <session>
- kCmdRemove, // remove file (only if created by server?)
-
- kRspAck,
- kRspNak
+ kCmdNone, ///< ignored, always acked
+ kCmdTerminateSession, ///< Terminates open Read session
+ kCmdResetSessions, ///< Terminates all open Read sessions
+ kCmdListDirectory, ///< List files in <path> from <offset>
+ kCmdOpenFileRO, ///< Opens file at <path> for reading, returns <session>
+ kCmdReadFile, ///< Reads <size> bytes from <offset> in <session>
+ kCmdCreateFile, ///< Creates file at <path> for writing, returns <session>
+ kCmdWriteFile, ///< Writes <size> bytes to <offset> in <session>
+ kCmdRemoveFile, ///< Remove file at <path>
+ kCmdCreateDirectory, ///< Creates directory at <path>
+ kCmdRemoveDirectory, ///< Removes Directory at <path>, must be empty
+ kCmdOpenFileWO, ///< Opens file at <path> for writing, returns <session>
+ kCmdTruncateFile, ///< Truncate file at <path> to <offset> length
+ kCmdRename, ///< Rename <path1> to <path2>
+ kCmdCalcFileCRC32, ///< Calculate CRC32 for file at <path>
+
+ kRspAck = 128, ///< Ack response
+ kRspNak ///< Nak response
};
-
+
+ /// @brief Error codes returned in Nak response PayloadHeader.data[0].
enum ErrorCode : uint8_t
- {
+ {
kErrNone,
- kErrNoRequest,
- kErrNoSession,
- kErrSequence,
- kErrNotDir,
- kErrNotFile,
- kErrEOF,
- kErrNotAppend,
- kErrTooBig,
- kErrIO,
- kErrPerm
- };
-
- int _findUnusedSession(void);
- bool _validSession(unsigned index);
-
- static const unsigned kMaxSession = 2;
- int _session_fds[kMaxSession];
-
- class Request
+ kErrFail, ///< Unknown failure
+ kErrFailErrno, ///< Command failed, errno sent back in PayloadHeader.data[1]
+ kErrInvalidDataSize, ///< PayloadHeader.size is invalid
+ kErrInvalidSession, ///< Session is not currently open
+ kErrNoSessionsAvailable, ///< All available Sessions in use
+ kErrEOF, ///< Offset past end of file for List and Read commands
+ kErrUnknownCommand ///< Unknown command opcode
+ };
+
+private:
+ /// @brief Unit of work which is queued to work_queue
+ struct Request
{
- public:
- union {
- dq_entry_t entry;
- work_s work;
- };
-
- bool decode(Mavlink *mavlink, mavlink_message_t *fromMessage) {
- if (fromMessage->msgid == MAVLINK_MSG_ID_ENCAPSULATED_DATA) {
- _mavlink = mavlink;
- mavlink_msg_encapsulated_data_decode(fromMessage, &_message);
- return true;
- }
- return false;
- }
-
- void reply() {
-
- // XXX the proper way would be an IOCTL / uORB call, rather than exploiting the
- // flat memory architecture, as we're operating between threads here.
- mavlink_message_t msg;
- msg.checksum = 0;
- unsigned len = mavlink_msg_encapsulated_data_pack_chan(_mavlink->get_system_id(), _mavlink->get_component_id(),
- _mavlink->get_channel(), &msg, sequence(), rawData());
-
- _mavlink->lockMessageBufferMutex();
- bool success = _mavlink->message_buffer_write(&msg, len);
- _mavlink->unlockMessageBufferMutex();
-
- if (!success) {
- warnx("FTP TX ERR");
- }
- // else {
- // warnx("wrote: sys: %d, comp: %d, chan: %d, len: %d, checksum: %d",
- // _mavlink->get_system_id(),
- // _mavlink->get_component_id(),
- // _mavlink->get_channel(),
- // len,
- // msg.checksum);
- // }
- }
-
- uint8_t *rawData() { return &_message.data[0]; }
- RequestHeader *header() { return reinterpret_cast<RequestHeader *>(&_message.data[0]); }
- uint8_t *requestData() { return &(header()->data[0]); }
- unsigned dataSize() { return header()->size + sizeof(RequestHeader); }
- uint16_t sequence() const { return _message.seqnr; }
- mavlink_channel_t channel() { return _mavlink->get_channel(); }
-
- char *dataAsCString();
-
- private:
- Mavlink *_mavlink;
- mavlink_encapsulated_data_t _message;
-
+ work_s work; ///< work queue entry
+ Mavlink *mavlink; ///< Mavlink to reply to
+ uint8_t serverSystemId; ///< System ID to send from
+ uint8_t serverComponentId; ///< Component ID to send from
+ uint8_t serverChannel; ///< Channel to send to
+ uint8_t targetSystemId; ///< System ID to target reply to
+
+ mavlink_file_transfer_protocol_t message; ///< Protocol message
};
-
- static const uint8_t kProtocolMagic = 'f';
- static const char kDirentFile = 'F';
- static const char kDirentDir = 'D';
- static const char kDirentUnknown = 'U';
- static const uint8_t kMaxDataLength = MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN - sizeof(RequestHeader);
-
- /// Request worker; runs on the low-priority work queue to service
- /// remote requests.
- ///
- static void _workerTrampoline(void *arg);
- void _worker(Request *req);
-
- /// Reply to a request (XXX should be a Request method)
- ///
- void _reply(Request *req);
-
- ErrorCode _workList(Request *req);
- ErrorCode _workOpen(Request *req, bool create);
- ErrorCode _workRead(Request *req);
- ErrorCode _workWrite(Request *req);
- ErrorCode _workRemove(Request *req);
- ErrorCode _workTerminate(Request *req);
- ErrorCode _workReset();
-
- // work freelist
- Request _workBufs[kRequestQueueSize];
- dq_queue_t _workFree;
- sem_t _lock;
-
- void _qLock() { do {} while (sem_wait(&_lock) != 0); }
- void _qUnlock() { sem_post(&_lock); }
-
- void _qFree(Request *req) {
- _qLock();
- dq_addlast(&req->entry, &_workFree);
- _qUnlock();
- }
-
- Request *_dqFree() {
- _qLock();
- auto req = reinterpret_cast<Request *>(dq_remfirst(&_workFree));
- _qUnlock();
- return req;
- }
-
+
+ Request *_get_request(void);
+ void _return_request(Request *req);
+ void _lock_request_queue(void);
+ void _unlock_request_queue(void);
+
+ char *_data_as_cstring(PayloadHeader* payload);
+
+ static void _worker_trampoline(void *arg);
+ void _process_request(Request *req);
+ void _reply(Request *req);
+ int _copy_file(const char *src_path, const char *dst_path, ssize_t length);
+
+ ErrorCode _workList(PayloadHeader *payload);
+ ErrorCode _workOpen(PayloadHeader *payload, int oflag);
+ ErrorCode _workRead(PayloadHeader *payload);
+ ErrorCode _workWrite(PayloadHeader *payload);
+ ErrorCode _workTerminate(PayloadHeader *payload);
+ ErrorCode _workReset(PayloadHeader* payload);
+ ErrorCode _workRemoveDirectory(PayloadHeader *payload);
+ ErrorCode _workCreateDirectory(PayloadHeader *payload);
+ ErrorCode _workRemoveFile(PayloadHeader *payload);
+ ErrorCode _workTruncateFile(PayloadHeader *payload);
+ ErrorCode _workRename(PayloadHeader *payload);
+ ErrorCode _workCalcFileCRC32(PayloadHeader *payload);
+
+ static const unsigned kRequestQueueSize = 2; ///< Max number of queued requests
+ Request _request_bufs[kRequestQueueSize]; ///< Request buffers which hold work
+ dq_queue_t _request_queue; ///< Queue of available Request buffers
+ sem_t _request_queue_sem; ///< Semaphore for locking access to _request_queue
+
+ int _find_unused_session(void);
+ bool _valid_session(unsigned index);
+
+ static const char kDirentFile = 'F'; ///< Identifies File returned from List command
+ static const char kDirentDir = 'D'; ///< Identifies Directory returned from List command
+ static const char kDirentSkip = 'S'; ///< Identifies Skipped entry from List command
+
+ /// @brief Maximum data size in RequestHeader::data
+ static const uint8_t kMaxDataLength = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(PayloadHeader);
+
+ static const unsigned kMaxSession = 2; ///< Max number of active sessions
+ int _session_fds[kMaxSession]; ///< Session file descriptors, 0 for empty slot
+
+ ReceiveMessageFunc_t _utRcvMsgFunc; ///< Unit test override for mavlink message sending
+ MavlinkFtpTest *_ftp_test; ///< Additional parameter to _utRcvMsgFunc;
};
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 5589738c1..c251dd3b2 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -90,7 +90,7 @@
static const int ERROR = -1;
#define DEFAULT_DEVICE_NAME "/dev/ttyS1"
-#define MAX_DATA_RATE 10000 // max data rate in bytes/s
+#define MAX_DATA_RATE 20000 // max data rate in bytes/s
#define MAIN_LOOP_DELAY 10000 // 100 Hz @ 1000 bytes/s data rate
#define TX_BUFFER_GAP MAVLINK_MAX_PACKET_LEN
@@ -123,6 +123,7 @@ Mavlink::Mavlink() :
_task_running(false),
_hil_enabled(false),
_use_hil_gps(false),
+ _forward_externalsp(false),
_is_usb_uart(false),
_wait_to_transmit(false),
_received_messages(false),
@@ -134,44 +135,46 @@ Mavlink::Mavlink() :
_mode(MAVLINK_MODE_NORMAL),
_channel(MAVLINK_COMM_0),
_logbuffer {},
- _total_counter(0),
- _receive_thread {},
- _verbose(false),
- _forwarding_on(false),
- _passing_on(false),
- _ftp_on(false),
- _uart_fd(-1),
- _baudrate(57600),
- _datarate(1000),
- _datarate_events(500),
- _rate_mult(1.0f),
- _mavlink_param_queue_index(0),
- mavlink_link_termination_allowed(false),
- _subscribe_to_stream(nullptr),
- _subscribe_to_stream_rate(0.0f),
- _flow_control_enabled(true),
- _last_write_success_time(0),
- _last_write_try_time(0),
- _bytes_tx(0),
- _bytes_txerr(0),
- _bytes_rx(0),
- _bytes_timestamp(0),
- _rate_tx(0.0f),
- _rate_txerr(0.0f),
- _rate_rx(0.0f),
- _rstatus {},
- _message_buffer {},
- _message_buffer_mutex {},
- _send_mutex {},
- _param_initialized(false),
- _param_system_id(0),
- _param_component_id(0),
- _param_system_type(0),
- _param_use_hil_gps(0),
-
- /* performance counters */
- _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")),
- _txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe"))
+ _total_counter(0),
+ _receive_thread {},
+ _verbose(false),
+ _forwarding_on(false),
+ _passing_on(false),
+ _ftp_on(false),
+ _uart_fd(-1),
+ _baudrate(57600),
+ _datarate(1000),
+ _datarate_events(500),
+ _rate_mult(1.0f),
+ _mavlink_param_queue_index(0),
+ mavlink_link_termination_allowed(false),
+ _subscribe_to_stream(nullptr),
+ _subscribe_to_stream_rate(0.0f),
+ _flow_control_enabled(true),
+ _last_write_success_time(0),
+ _last_write_try_time(0),
+ _bytes_tx(0),
+ _bytes_txerr(0),
+ _bytes_rx(0),
+ _bytes_timestamp(0),
+ _rate_tx(0.0f),
+ _rate_txerr(0.0f),
+ _rate_rx(0.0f),
+ _rstatus {},
+ _message_buffer {},
+ _message_buffer_mutex {},
+ _send_mutex {},
+ _param_initialized(false),
+ _param_system_id(0),
+ _param_component_id(0),
+ _param_system_type(MAV_TYPE_FIXED_WING),
+ _param_use_hil_gps(0),
+ _param_forward_externalsp(0),
+ _system_type(0),
+
+ /* performance counters */
+ _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")),
+ _txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe"))
{
fops.ioctl = (int (*)(file *, int, long unsigned int))&mavlink_dev_ioctl;
@@ -217,6 +220,8 @@ Mavlink::Mavlink() :
errx(1, "instance ID is out of range");
break;
}
+
+ _rstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC;
}
Mavlink::~Mavlink()
@@ -481,6 +486,7 @@ void Mavlink::mavlink_update_system(void)
_param_component_id = param_find("MAV_COMP_ID");
_param_system_type = param_find("MAV_TYPE");
_param_use_hil_gps = param_find("MAV_USEHILGPS");
+ _param_forward_externalsp = param_find("MAV_FWDEXTSP");
}
/* update system and component id */
@@ -520,13 +526,18 @@ void Mavlink::mavlink_update_system(void)
param_get(_param_system_type, &system_type);
if (system_type >= 0 && system_type < MAV_TYPE_ENUM_END) {
- mavlink_system.type = system_type;
+ _system_type = system_type;
}
int32_t use_hil_gps;
param_get(_param_use_hil_gps, &use_hil_gps);
_use_hil_gps = (bool)use_hil_gps;
+
+ int32_t forward_externalsp;
+ param_get(_param_forward_externalsp, &forward_externalsp);
+
+ _forward_externalsp = (bool)forward_externalsp;
}
int Mavlink::get_system_id()
@@ -694,7 +705,7 @@ Mavlink::set_hil_enabled(bool hil_enabled)
/* enable HIL */
if (hil_enabled && !_hil_enabled) {
_hil_enabled = true;
- configure_stream("HIL_CONTROLS", 150.0f);
+ configure_stream("HIL_CONTROLS", 200.0f);
}
/* disable HIL */
@@ -746,7 +757,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg)
pthread_mutex_lock(&_send_mutex);
- int buf_free = get_free_tx_buf();
+ unsigned buf_free = get_free_tx_buf();
uint8_t payload_len = mavlink_message_lengths[msgid];
unsigned packet_len = payload_len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
@@ -754,7 +765,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg)
_last_write_try_time = hrt_absolute_time();
/* check if there is space in the buffer, let it overflow else */
- if (buf_free < TX_BUFFER_GAP) {
+ if ((buf_free < TX_BUFFER_GAP) || (buf_free < packet_len)) {
/* no enough space in buffer to send */
count_txerr();
count_txerrbytes(packet_len);
@@ -811,14 +822,14 @@ Mavlink::resend_message(mavlink_message_t *msg)
pthread_mutex_lock(&_send_mutex);
- int buf_free = get_free_tx_buf();
+ unsigned buf_free = get_free_tx_buf();
_last_write_try_time = hrt_absolute_time();
unsigned packet_len = msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
/* check if there is space in the buffer, let it overflow else */
- if (buf_free < TX_BUFFER_GAP) {
+ if ((buf_free < TX_BUFFER_GAP) || (buf_free < packet_len)) {
/* no enough space in buffer to send */
count_txerr();
count_txerrbytes(packet_len);
@@ -1227,7 +1238,10 @@ Mavlink::task_main(int argc, char *argv[])
_mode = MAVLINK_MODE_CUSTOM;
} else if (strcmp(optarg, "camera") == 0) {
- _mode = MAVLINK_MODE_CAMERA;
+ // left in here for compatibility
+ _mode = MAVLINK_MODE_ONBOARD;
+ } else if (strcmp(optarg, "onboard") == 0) {
+ _mode = MAVLINK_MODE_ONBOARD;
}
break;
@@ -1287,8 +1301,8 @@ Mavlink::task_main(int argc, char *argv[])
warnx("mode: CUSTOM");
break;
- case MAVLINK_MODE_CAMERA:
- warnx("mode: CAMERA");
+ case MAVLINK_MODE_ONBOARD:
+ warnx("mode: ONBOARD");
break;
default:
@@ -1388,16 +1402,20 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("GLOBAL_POSITION_INT", 3.0f);
configure_stream("LOCAL_POSITION_NED", 3.0f);
configure_stream("RC_CHANNELS_RAW", 1.0f);
- configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f);
- configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f);
+ configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
+ configure_stream("ATTITUDE_TARGET", 3.0f);
configure_stream("DISTANCE_SENSOR", 0.5f);
+ configure_stream("OPTICAL_FLOW", 5.0f);
break;
- case MAVLINK_MODE_CAMERA:
+ case MAVLINK_MODE_ONBOARD:
configure_stream("SYS_STATUS", 1.0f);
- configure_stream("ATTITUDE", 15.0f);
- configure_stream("GLOBAL_POSITION_INT", 15.0f);
- configure_stream("CAMERA_CAPTURE", 1.0f);
+ configure_stream("ATTITUDE", 50.0f);
+ configure_stream("GLOBAL_POSITION_INT", 50.0f);
+ configure_stream("CAMERA_CAPTURE", 2.0f);
+ configure_stream("ATTITUDE_TARGET", 10.0f);
+ configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
+ configure_stream("VFR_HUD", 10.0f);
break;
default:
@@ -1618,7 +1636,7 @@ Mavlink::start(int argc, char *argv[])
task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2700,
+ 2900,
(main_t)&Mavlink::start_helper,
(const char **)argv);
@@ -1653,6 +1671,8 @@ Mavlink::display_status()
printf("\tGCS heartbeat:\t%llu us ago\n", hrt_elapsed_time(&_rstatus.heartbeat_time));
}
+ printf("\tmavlink chan: #%u\n", _channel);
+
if (_rstatus.timestamp > 0) {
printf("\ttype:\t\t");
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 1e2e94cef..ad5e5001b 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -127,7 +127,7 @@ public:
enum MAVLINK_MODE {
MAVLINK_MODE_NORMAL = 0,
MAVLINK_MODE_CUSTOM,
- MAVLINK_MODE_CAMERA
+ MAVLINK_MODE_ONBOARD
};
void set_mode(enum MAVLINK_MODE);
@@ -137,6 +137,8 @@ public:
bool get_use_hil_gps() { return _use_hil_gps; }
+ bool get_forward_externalsp() { return _forward_externalsp; }
+
bool get_flow_control_enabled() { return _flow_control_enabled; }
bool get_forwarding_on() { return _forwarding_on; }
@@ -232,7 +234,7 @@ public:
bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
bool message_buffer_write(const void *ptr, int size);
-
+
void lockMessageBufferMutex(void) { pthread_mutex_lock(&_message_buffer_mutex); }
void unlockMessageBufferMutex(void) { pthread_mutex_unlock(&_message_buffer_mutex); }
@@ -263,6 +265,8 @@ public:
struct mavlink_logbuffer *get_logbuffer() { return &_logbuffer; }
+ unsigned get_system_type() { return _system_type; }
+
protected:
Mavlink *next;
@@ -275,6 +279,7 @@ private:
/* states */
bool _hil_enabled; /**< Hardware In the Loop mode */
bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
+ bool _forward_externalsp; /**< Forward external setpoint messages to controllers directly if in offboard mode */
bool _is_usb_uart; /**< Port is USB */
bool _wait_to_transmit; /**< Wait to transmit until received messages. */
bool _received_messages; /**< Whether we've received valid mavlink messages. */
@@ -349,6 +354,9 @@ private:
param_t _param_component_id;
param_t _param_system_type;
param_t _param_use_hil_gps;
+ param_t _param_forward_externalsp;
+
+ unsigned _system_type;
perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _txerr_perf; /**< TX error counter */
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 683f0f1e8..b4911427f 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -162,6 +162,8 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
break;
case NAVIGATION_STATE_AUTO_RTL:
+ /* fallthrough */
+ case NAVIGATION_STATE_AUTO_RCRECOVER:
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
| MAV_MODE_FLAG_STABILIZE_ENABLED
| MAV_MODE_FLAG_GUIDED_ENABLED;
@@ -170,6 +172,8 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
break;
case NAVIGATION_STATE_LAND:
+ case NAVIGATION_STATE_AUTO_LANDENGFAIL:
+ case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
/* fallthrough */
case NAVIGATION_STATE_DESCEND:
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
@@ -298,7 +302,7 @@ protected:
msg.base_mode = 0;
msg.custom_mode = 0;
get_mavlink_mode_state(&status, &pos_sp_triplet, &msg.system_status, &msg.base_mode, &msg.custom_mode);
- msg.type = mavlink_system.type;
+ msg.type = _mavlink->get_system_type();
msg.autopilot = MAV_AUTOPILOT_PX4;
msg.mavlink_version = 3;
@@ -337,11 +341,18 @@ private:
/* do not allow top copying this class */
MavlinkStreamStatustext(MavlinkStreamStatustext &);
MavlinkStreamStatustext& operator = (const MavlinkStreamStatustext &);
+ FILE *fp = nullptr;
protected:
explicit MavlinkStreamStatustext(Mavlink *mavlink) : MavlinkStream(mavlink)
{}
+ ~MavlinkStreamStatustext() {
+ if (fp) {
+ fclose(fp);
+ }
+ }
+
void send(const hrt_abstime t)
{
if (!mavlink_logbuffer_is_empty(_mavlink->get_logbuffer())) {
@@ -355,6 +366,31 @@ protected:
strncpy(msg.text, logmsg.text, sizeof(msg.text));
_mavlink->send_message(MAVLINK_MSG_ID_STATUSTEXT, &msg);
+
+ /* write log messages in first instance to disk */
+ if (_mavlink->get_instance_id() == 0) {
+ if (fp) {
+ fputs(msg.text, fp);
+ fputs("\n", fp);
+ fsync(fileno(fp));
+ } else {
+ /* string to hold the path to the log */
+ char log_file_name[32] = "";
+ char log_file_path[64] = "";
+
+ timespec ts;
+ clock_gettime(CLOCK_REALTIME, &ts);
+ /* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
+ time_t gps_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
+ struct tm t;
+ gmtime_r(&gps_time_sec, &t);
+
+ // XXX we do not want to interfere here with the SD log app
+ strftime(log_file_name, sizeof(log_file_name), "msgs_%Y_%m_%d_%H_%M_%S.txt", &t);
+ snprintf(log_file_path, sizeof(log_file_path), "/fs/microsd/%s", log_file_name);
+ fp = fopen(log_file_path, "ab");
+ }
+ }
}
}
}
@@ -774,6 +810,9 @@ private:
MavlinkOrbSubscription *_airspeed_sub;
uint64_t _airspeed_time;
+ MavlinkOrbSubscription *_sensor_combined_sub;
+ uint64_t _sensor_combined_time;
+
/* do not allow top copying this class */
MavlinkStreamVFRHUD(MavlinkStreamVFRHUD &);
MavlinkStreamVFRHUD& operator = (const MavlinkStreamVFRHUD &);
@@ -789,7 +828,9 @@ protected:
_act_sub(_mavlink->add_orb_subscription(ORB_ID(actuator_controls_0))),
_act_time(0),
_airspeed_sub(_mavlink->add_orb_subscription(ORB_ID(airspeed))),
- _airspeed_time(0)
+ _airspeed_time(0),
+ _sensor_combined_sub(_mavlink->add_orb_subscription(ORB_ID(sensor_combined))),
+ _sensor_combined_time(0)
{}
void send(const hrt_abstime t)
@@ -799,12 +840,14 @@ protected:
struct actuator_armed_s armed;
struct actuator_controls_s act;
struct airspeed_s airspeed;
+ struct sensor_combined_s sensor_combined;
bool updated = _att_sub->update(&_att_time, &att);
updated |= _pos_sub->update(&_pos_time, &pos);
updated |= _armed_sub->update(&_armed_time, &armed);
updated |= _act_sub->update(&_act_time, &act);
updated |= _airspeed_sub->update(&_airspeed_time, &airspeed);
+ updated |= _sensor_combined_sub->update(&_sensor_combined_time, &sensor_combined);
if (updated) {
mavlink_vfr_hud_t msg;
@@ -813,7 +856,7 @@ protected:
msg.groundspeed = sqrtf(pos.vel_n * pos.vel_n + pos.vel_e * pos.vel_e);
msg.heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F;
msg.throttle = armed.armed ? act.control[3] * 100.0f : 0.0f;
- msg.alt = pos.alt;
+ msg.alt = sensor_combined.baro_alt_meter;
msg.climb = -pos.vel_d;
_mavlink->send_message(MAVLINK_MSG_ID_VFR_HUD, &msg);
@@ -879,8 +922,8 @@ protected:
msg.eph = cm_uint16_from_m_float(gps.eph);
msg.epv = cm_uint16_from_m_float(gps.epv);
msg.vel = cm_uint16_from_m_float(gps.vel_m_s),
- msg.cog = _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f,
- msg.satellites_visible = gps.satellites_used;
+ msg.cog = _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f,
+ msg.satellites_visible = gps.satellites_used;
_mavlink->send_message(MAVLINK_MSG_ID_GPS_RAW_INT, &msg);
}
@@ -950,11 +993,11 @@ protected:
msg.lat = pos.lat * 1e7;
msg.lon = pos.lon * 1e7;
msg.alt = pos.alt * 1000.0f;
- msg.relative_alt = (pos.alt - home.alt) * 1000.0f;
- msg.vx = pos.vel_n * 100.0f;
- msg.vy = pos.vel_e * 100.0f;
- msg.vz = pos.vel_d * 100.0f;
- msg.hdg = _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f;
+ msg.relative_alt = (pos.alt - home.alt) * 1000.0f;
+ msg.vx = pos.vel_n * 100.0f;
+ msg.vy = pos.vel_e * 100.0f;
+ msg.vz = pos.vel_d * 100.0f;
+ msg.hdg = _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f;
_mavlink->send_message(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, &msg);
}
@@ -1015,9 +1058,9 @@ protected:
msg.x = pos.x;
msg.y = pos.y;
msg.z = pos.z;
- msg.vx = pos.vx;
- msg.vy = pos.vy;
- msg.vz = pos.vz;
+ msg.vx = pos.vx;
+ msg.vy = pos.vy;
+ msg.vz = pos.vz;
_mavlink->send_message(MAVLINK_MSG_ID_LOCAL_POSITION_NED, &msg);
}
@@ -1078,9 +1121,9 @@ protected:
msg.x = pos.x;
msg.y = pos.y;
msg.z = pos.z;
- msg.roll = pos.roll;
- msg.pitch = pos.pitch;
- msg.yaw = pos.yaw;
+ msg.roll = pos.roll;
+ msg.pitch = pos.pitch;
+ msg.yaw = pos.yaw;
_mavlink->send_message(MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, &msg);
}
@@ -1310,15 +1353,17 @@ protected:
const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2;
+ unsigned system_type = _mavlink->get_system_type();
+
/* scale outputs depending on system type */
- if (mavlink_system.type == MAV_TYPE_QUADROTOR ||
- mavlink_system.type == MAV_TYPE_HEXAROTOR ||
- mavlink_system.type == MAV_TYPE_OCTOROTOR) {
+ if (system_type == MAV_TYPE_QUADROTOR ||
+ system_type == MAV_TYPE_HEXAROTOR ||
+ system_type == MAV_TYPE_OCTOROTOR) {
/* multirotors: set number of rotor outputs depending on type */
unsigned n;
- switch (mavlink_system.type) {
+ switch (system_type) {
case MAV_TYPE_QUADROTOR:
n = 4;
break;
@@ -1333,7 +1378,7 @@ protected:
}
for (unsigned i = 0; i < 8; i++) {
- if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
+ if (act.output[i] > PWM_LOWEST_MIN / 2) {
if (i < n) {
/* scale PWM out 900..2100 us to 0..1 for rotors */
out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
@@ -1344,7 +1389,7 @@ protected:
}
} else {
- /* send 0 when disarmed */
+ /* send 0 when disarmed and for disabled channels */
out[i] = 0.0f;
}
}
@@ -1353,15 +1398,20 @@ protected:
/* fixed wing: scale throttle to 0..1 and other channels to -1..1 */
for (unsigned i = 0; i < 8; i++) {
- if (i != 3) {
- /* scale PWM out 900..2100 us to -1..1 for normal channels */
- out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2);
+ if (act.output[i] > PWM_LOWEST_MIN / 2) {
+ if (i != 3) {
+ /* scale PWM out 900..2100 us to -1..1 for normal channels */
+ out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2);
+
+ } else {
+ /* scale PWM out 900..2100 us to 0..1 for throttle */
+ out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
+ }
} else {
- /* scale PWM out 900..2100 us to 0..1 for throttle */
- out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
+ /* set 0 for disabled channels */
+ out[i] = 0.0f;
}
-
}
}
@@ -1385,43 +1435,43 @@ protected:
};
-class MavlinkStreamGlobalPositionSetpointInt : public MavlinkStream
+class MavlinkStreamPositionTargetGlobalInt : public MavlinkStream
{
public:
const char *get_name() const
{
- return MavlinkStreamGlobalPositionSetpointInt::get_name_static();
+ return MavlinkStreamPositionTargetGlobalInt::get_name_static();
}
static const char *get_name_static()
{
- return "GLOBAL_POSITION_SETPOINT_INT";
+ return "POSITION_TARGET_GLOBAL_INT";
}
uint8_t get_id()
{
- return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT;
+ return MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
}
static MavlinkStream *new_instance(Mavlink *mavlink)
{
- return new MavlinkStreamGlobalPositionSetpointInt(mavlink);
+ return new MavlinkStreamPositionTargetGlobalInt(mavlink);
}
unsigned get_size()
{
- return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ return MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
MavlinkOrbSubscription *_pos_sp_triplet_sub;
/* do not allow top copying this class */
- MavlinkStreamGlobalPositionSetpointInt(MavlinkStreamGlobalPositionSetpointInt &);
- MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &);
+ MavlinkStreamPositionTargetGlobalInt(MavlinkStreamPositionTargetGlobalInt &);
+ MavlinkStreamPositionTargetGlobalInt& operator = (const MavlinkStreamPositionTargetGlobalInt &);
protected:
- explicit MavlinkStreamGlobalPositionSetpointInt(Mavlink *mavlink) : MavlinkStream(mavlink),
+ explicit MavlinkStreamPositionTargetGlobalInt(Mavlink *mavlink) : MavlinkStream(mavlink),
_pos_sp_triplet_sub(_mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)))
{}
@@ -1430,15 +1480,14 @@ protected:
struct position_setpoint_triplet_s pos_sp_triplet;
if (_pos_sp_triplet_sub->update(&pos_sp_triplet)) {
- mavlink_global_position_setpoint_int_t msg;
+ mavlink_position_target_global_int_t msg{};
msg.coordinate_frame = MAV_FRAME_GLOBAL;
- msg.latitude = pos_sp_triplet.current.lat * 1e7;
- msg.longitude = pos_sp_triplet.current.lon * 1e7;
- msg.altitude = pos_sp_triplet.current.alt * 1000;
- msg.yaw = pos_sp_triplet.current.yaw * M_RAD_TO_DEG_F * 100.0f;
+ msg.lat_int = pos_sp_triplet.current.lat * 1e7;
+ msg.lon_int = pos_sp_triplet.current.lon * 1e7;
+ msg.alt = pos_sp_triplet.current.alt;
- _mavlink->send_message(MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, &msg);
+ _mavlink->send_message(MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, &msg);
}
}
};
@@ -1454,12 +1503,12 @@ public:
static const char *get_name_static()
{
- return "LOCAL_POSITION_SETPOINT";
+ return "POSITION_TARGET_LOCAL_NED";
}
uint8_t get_id()
{
- return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
+ return MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
}
static MavlinkStream *new_instance(Mavlink *mavlink)
@@ -1469,7 +1518,7 @@ public:
unsigned get_size()
{
- return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ return MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
@@ -1491,137 +1540,87 @@ protected:
struct vehicle_local_position_setpoint_s pos_sp;
if (_pos_sp_sub->update(&_pos_sp_time, &pos_sp)) {
- mavlink_local_position_setpoint_t msg;
+ mavlink_position_target_local_ned_t msg{};
+ msg.time_boot_ms = pos_sp.timestamp / 1000;
msg.coordinate_frame = MAV_FRAME_LOCAL_NED;
msg.x = pos_sp.x;
msg.y = pos_sp.y;
msg.z = pos_sp.z;
- msg.yaw = pos_sp.yaw;
- _mavlink->send_message(MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, &msg);
+ _mavlink->send_message(MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, &msg);
}
}
};
-class MavlinkStreamRollPitchYawThrustSetpoint : public MavlinkStream
+class MavlinkStreamAttitudeTarget : public MavlinkStream
{
public:
const char *get_name() const
{
- return MavlinkStreamRollPitchYawThrustSetpoint::get_name_static();
+ return MavlinkStreamAttitudeTarget::get_name_static();
}
static const char *get_name_static()
{
- return "ROLL_PITCH_YAW_THRUST_SETPOINT";
+ return "ATTITUDE_TARGET";
}
uint8_t get_id()
{
- return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
+ return MAVLINK_MSG_ID_ATTITUDE_TARGET;
}
static MavlinkStream *new_instance(Mavlink *mavlink)
{
- return new MavlinkStreamRollPitchYawThrustSetpoint(mavlink);
+ return new MavlinkStreamAttitudeTarget(mavlink);
}
unsigned get_size()
{
- return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
+ return MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
private:
- MavlinkOrbSubscription *att_sp_sub;
- uint64_t att_sp_time;
+ MavlinkOrbSubscription *_att_sp_sub;
+ MavlinkOrbSubscription *_att_rates_sp_sub;
+ uint64_t _att_sp_time;
+ uint64_t _att_rates_sp_time;
/* do not allow top copying this class */
- MavlinkStreamRollPitchYawThrustSetpoint(MavlinkStreamRollPitchYawThrustSetpoint &);
- MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &);
+ MavlinkStreamAttitudeTarget(MavlinkStreamAttitudeTarget &);
+ MavlinkStreamAttitudeTarget& operator = (const MavlinkStreamAttitudeTarget &);
protected:
- explicit MavlinkStreamRollPitchYawThrustSetpoint(Mavlink *mavlink) : MavlinkStream(mavlink),
- att_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint))),
- att_sp_time(0)
+ explicit MavlinkStreamAttitudeTarget(Mavlink *mavlink) : MavlinkStream(mavlink),
+ _att_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint))),
+ _att_rates_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint))),
+ _att_sp_time(0),
+ _att_rates_sp_time(0)
{}
void send(const hrt_abstime t)
{
struct vehicle_attitude_setpoint_s att_sp;
- if (att_sp_sub->update(&att_sp_time, &att_sp)) {
- mavlink_roll_pitch_yaw_thrust_setpoint_t msg;
-
- msg.time_boot_ms = att_sp.timestamp / 1000;
- msg.roll = att_sp.roll_body;
- msg.pitch = att_sp.pitch_body;
- msg.yaw = att_sp.yaw_body;
- msg.thrust = att_sp.thrust;
-
- _mavlink->send_message(MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, &msg);
- }
- }
-};
-
-
-class MavlinkStreamRollPitchYawRatesThrustSetpoint : public MavlinkStream
-{
-public:
- const char *get_name() const
- {
- return MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static();
- }
-
- static const char *get_name_static()
- {
- return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT";
- }
-
- uint8_t get_id()
- {
- return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT;
- }
-
- static MavlinkStream *new_instance(Mavlink *mavlink)
- {
- return new MavlinkStreamRollPitchYawRatesThrustSetpoint(mavlink);
- }
-
- unsigned get_size()
- {
- return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
- }
-
-private:
- MavlinkOrbSubscription *_att_rates_sp_sub;
- uint64_t _att_rates_sp_time;
+ if (_att_sp_sub->update(&_att_sp_time, &att_sp)) {
- /* do not allow top copying this class */
- MavlinkStreamRollPitchYawRatesThrustSetpoint(MavlinkStreamRollPitchYawRatesThrustSetpoint &);
- MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &);
+ struct vehicle_rates_setpoint_s att_rates_sp;
+ (void)_att_rates_sp_sub->update(&_att_rates_sp_time, &att_rates_sp);
-protected:
- explicit MavlinkStreamRollPitchYawRatesThrustSetpoint(Mavlink *mavlink) : MavlinkStream(mavlink),
- _att_rates_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint))),
- _att_rates_sp_time(0)
- {}
+ mavlink_attitude_target_t msg{};
- void send(const hrt_abstime t)
- {
- struct vehicle_rates_setpoint_s att_rates_sp;
+ msg.time_boot_ms = att_sp.timestamp / 1000;
+ mavlink_euler_to_quaternion(att_sp.roll_body, att_sp.pitch_body, att_sp.yaw_body, msg.q);
- if (_att_rates_sp_sub->update(&_att_rates_sp_time, &att_rates_sp)) {
- mavlink_roll_pitch_yaw_rates_thrust_setpoint_t msg;
+ msg.body_roll_rate = att_rates_sp.roll;
+ msg.body_pitch_rate = att_rates_sp.pitch;
+ msg.body_yaw_rate = att_rates_sp.yaw;
- msg.time_boot_ms = att_rates_sp.timestamp / 1000;
- msg.roll_rate = att_rates_sp.roll;
- msg.pitch_rate = att_rates_sp.pitch;
- msg.yaw_rate = att_rates_sp.yaw;
- msg.thrust = att_rates_sp.thrust;
+ msg.thrust = att_sp.thrust;
- _mavlink->send_message(MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, &msg);
+ _mavlink->send_message(MAVLINK_MSG_ID_ATTITUDE_TARGET, &msg);
}
}
};
@@ -1688,10 +1687,10 @@ protected:
msg.chan2_raw = (rc.channel_count > (i * port_width) + 1) ? rc.values[(i * port_width) + 1] : UINT16_MAX;
msg.chan3_raw = (rc.channel_count > (i * port_width) + 2) ? rc.values[(i * port_width) + 2] : UINT16_MAX;
msg.chan4_raw = (rc.channel_count > (i * port_width) + 3) ? rc.values[(i * port_width) + 3] : UINT16_MAX;
- msg.chan4_raw = (rc.channel_count > (i * port_width) + 4) ? rc.values[(i * port_width) + 4] : UINT16_MAX;
- msg.chan4_raw = (rc.channel_count > (i * port_width) + 5) ? rc.values[(i * port_width) + 5] : UINT16_MAX;
- msg.chan4_raw = (rc.channel_count > (i * port_width) + 6) ? rc.values[(i * port_width) + 6] : UINT16_MAX;
- msg.chan4_raw = (rc.channel_count > (i * port_width) + 7) ? rc.values[(i * port_width) + 7] : UINT16_MAX;
+ msg.chan5_raw = (rc.channel_count > (i * port_width) + 4) ? rc.values[(i * port_width) + 4] : UINT16_MAX;
+ msg.chan6_raw = (rc.channel_count > (i * port_width) + 5) ? rc.values[(i * port_width) + 5] : UINT16_MAX;
+ msg.chan7_raw = (rc.channel_count > (i * port_width) + 6) ? rc.values[(i * port_width) + 6] : UINT16_MAX;
+ msg.chan8_raw = (rc.channel_count > (i * port_width) + 7) ? rc.values[(i * port_width) + 7] : UINT16_MAX;
msg.rssi = rc.rssi;
_mavlink->send_message(MAVLINK_MSG_ID_RC_CHANNELS_RAW, &msg);
@@ -2149,10 +2148,9 @@ StreamListItem *streams_list[] = {
new StreamListItem(&MavlinkStreamServoOutputRaw<2>::new_instance, &MavlinkStreamServoOutputRaw<2>::get_name_static),
new StreamListItem(&MavlinkStreamServoOutputRaw<3>::new_instance, &MavlinkStreamServoOutputRaw<3>::get_name_static),
new StreamListItem(&MavlinkStreamHILControls::new_instance, &MavlinkStreamHILControls::get_name_static),
- new StreamListItem(&MavlinkStreamGlobalPositionSetpointInt::new_instance, &MavlinkStreamGlobalPositionSetpointInt::get_name_static),
+ new StreamListItem(&MavlinkStreamPositionTargetGlobalInt::new_instance, &MavlinkStreamPositionTargetGlobalInt::get_name_static),
new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static),
- new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static),
- new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static),
+ new StreamListItem(&MavlinkStreamAttitudeTarget::new_instance, &MavlinkStreamAttitudeTarget::get_name_static),
new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static),
new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static),
new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static),
diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp
index 7a761588a..a3c127cdc 100644
--- a/src/modules/mavlink/mavlink_mission.cpp
+++ b/src/modules/mavlink/mavlink_mission.cpp
@@ -58,6 +58,10 @@
#endif
static const int ERROR = -1;
+#define CHECK_SYSID_COMPID_MISSION(_msg) (_msg.target_system == mavlink_system.sysid && \
+ ((_msg.target_component == mavlink_system.compid) || \
+ (_msg.target_component == MAV_COMP_ID_MISSIONPLANNER) || \
+ (_msg.target_component == MAV_COMP_ID_ALL)))
MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : MavlinkStream(mavlink),
_state(MAVLINK_WPM_STATE_IDLE),
@@ -79,8 +83,7 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : MavlinkStream(m
_mission_result_sub(-1),
_offboard_mission_pub(-1),
_slow_rate_limiter(_interval / 10.0f),
- _verbose(false),
- _comp_id(MAV_COMP_ID_MISSIONPLANNER)
+ _verbose(false)
{
_offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
_mission_result_sub = orb_subscribe(ORB_ID(mission_result));
@@ -384,7 +387,7 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg)
mavlink_mission_ack_t wpa;
mavlink_msg_mission_ack_decode(msg, &wpa);
- if (wpa.target_system == mavlink_system.sysid /*&& wpa.target_component == mavlink_wpm_comp_id*/) {
+ if (CHECK_SYSID_COMPID_MISSION(wpa)) {
if ((msg->sysid == _transfer_partner_sysid && msg->compid == _transfer_partner_compid)) {
if (_state == MAVLINK_WPM_STATE_SENDLIST) {
_time_last_recv = hrt_absolute_time();
@@ -416,7 +419,7 @@ MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg)
mavlink_mission_set_current_t wpc;
mavlink_msg_mission_set_current_decode(msg, &wpc);
- if (wpc.target_system == mavlink_system.sysid /*&& wpc.target_component == mavlink_wpm_comp_id*/) {
+ if (CHECK_SYSID_COMPID_MISSION(wpc)) {
if (_state == MAVLINK_WPM_STATE_IDLE) {
_time_last_recv = hrt_absolute_time();
@@ -451,7 +454,7 @@ MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg)
mavlink_mission_request_list_t wprl;
mavlink_msg_mission_request_list_decode(msg, &wprl);
- if (wprl.target_system == mavlink_system.sysid /*&& wprl.target_component == mavlink_wpm_comp_id*/) {
+ if (CHECK_SYSID_COMPID_MISSION(wprl)) {
if (_state == MAVLINK_WPM_STATE_IDLE || _state == MAVLINK_WPM_STATE_SENDLIST) {
_time_last_recv = hrt_absolute_time();
@@ -487,7 +490,7 @@ MavlinkMissionManager::handle_mission_request(const mavlink_message_t *msg)
mavlink_mission_request_t wpr;
mavlink_msg_mission_request_decode(msg, &wpr);
- if (wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) {
+ if (CHECK_SYSID_COMPID_MISSION(wpr)) {
if (msg->sysid == _transfer_partner_sysid && msg->compid == _transfer_partner_compid) {
if (_state == MAVLINK_WPM_STATE_SENDLIST) {
_time_last_recv = hrt_absolute_time();
@@ -558,7 +561,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
mavlink_mission_count_t wpc;
mavlink_msg_mission_count_decode(msg, &wpc);
- if (wpc.target_system == mavlink_system.sysid/* && wpc.target_component == mavlink_wpm_comp_id*/) {
+ if (CHECK_SYSID_COMPID_MISSION(wpc)) {
if (_state == MAVLINK_WPM_STATE_IDLE) {
_time_last_recv = hrt_absolute_time();
@@ -624,7 +627,7 @@ MavlinkMissionManager::handle_mission_item(const mavlink_message_t *msg)
mavlink_mission_item_t wp;
mavlink_msg_mission_item_decode(msg, &wp);
- if (wp.target_system == mavlink_system.sysid && wp.target_component == _comp_id) {
+ if (CHECK_SYSID_COMPID_MISSION(wp)) {
if (_state == MAVLINK_WPM_STATE_GETLIST) {
_time_last_recv = hrt_absolute_time();
@@ -710,7 +713,7 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg)
mavlink_mission_clear_all_t wpca;
mavlink_msg_mission_clear_all_decode(msg, &wpca);
- if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */) {
+ if (CHECK_SYSID_COMPID_MISSION(wpca)) {
if (_state == MAVLINK_WPM_STATE_IDLE) {
/* don't touch mission items storage itself, but only items count in mission state */
@@ -795,10 +798,10 @@ int
MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item)
{
if (mission_item->altitude_is_relative) {
- mavlink_mission_item->frame = MAV_FRAME_GLOBAL;
+ mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
} else {
- mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
+ mavlink_mission_item->frame = MAV_FRAME_GLOBAL;
}
switch (mission_item->nav_cmd) {
diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h
index 8ff27f87d..a7bb94c22 100644
--- a/src/modules/mavlink/mavlink_mission.h
+++ b/src/modules/mavlink/mavlink_mission.h
@@ -126,8 +126,6 @@ private:
bool _verbose;
- uint8_t _comp_id;
-
/* do not allow top copying this class */
MavlinkMissionManager(MavlinkMissionManager &);
MavlinkMissionManager& operator = (const MavlinkMissionManager &);
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 69e3ef31d..bc092c7e9 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -37,6 +37,7 @@
*
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
/* XXX trim includes */
@@ -54,6 +55,7 @@
#include <drivers/drv_gyro.h>
#include <drivers/drv_mag.h>
#include <drivers/drv_baro.h>
+#include <drivers/drv_range_finder.h>
#include <time.h>
#include <float.h>
#include <unistd.h>
@@ -102,16 +104,18 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_battery_pub(-1),
_cmd_pub(-1),
_flow_pub(-1),
+ _range_pub(-1),
_offboard_control_sp_pub(-1),
- _local_pos_sp_pub(-1),
_global_vel_sp_pub(-1),
_att_sp_pub(-1),
_rates_sp_pub(-1),
+ _force_sp_pub(-1),
+ _pos_sp_triplet_pub(-1),
_vicon_position_pub(-1),
+ _vision_position_pub(-1),
_telemetry_status_pub(-1),
_rc_pub(-1),
_manual_pub(-1),
- _radio_status_available(false),
_control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))),
_hil_frames(0),
_old_timestamp(0),
@@ -121,7 +125,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
{
// make sure the FTP server is started
- (void)MavlinkFTP::getServer();
+ (void)MavlinkFTP::get_server();
}
MavlinkReceiver::~MavlinkReceiver()
@@ -136,6 +140,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_command_long(msg);
break;
+ case MAVLINK_MSG_ID_COMMAND_INT:
+ handle_message_command_int(msg);
+ break;
+
case MAVLINK_MSG_ID_OPTICAL_FLOW:
handle_message_optical_flow(msg);
break;
@@ -148,8 +156,16 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_vicon_position_estimate(msg);
break;
- case MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST:
- handle_message_quad_swarm_roll_pitch_yaw_thrust(msg);
+ case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
+ handle_message_set_position_target_local_ned(msg);
+ break;
+
+ case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
+ handle_message_set_attitude_target(msg);
+ break;
+
+ case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
+ handle_message_vision_position_estimate(msg);
break;
case MAVLINK_MSG_ID_RADIO_STATUS:
@@ -168,8 +184,8 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_request_data_stream(msg);
break;
- case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
- MavlinkFTP::getServer()->handle_message(_mavlink, msg);
+ case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
+ MavlinkFTP::get_server()->handle_message(_mavlink, msg);
break;
default:
@@ -196,6 +212,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_hil_state_quaternion(msg);
break;
+ case MAVLINK_MSG_ID_HIL_OPTICAL_FLOW:
+ handle_message_hil_optical_flow(msg);
+ break;
+
default:
break;
}
@@ -276,6 +296,62 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
}
void
+MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
+{
+ /* command */
+ mavlink_command_int_t cmd_mavlink;
+ mavlink_msg_command_int_decode(msg, &cmd_mavlink);
+
+ if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
+ || (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
+ //check for MAVLINK terminate command
+ if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
+ /* This is the link shutdown command, terminate mavlink */
+ warnx("terminated by remote command");
+ fflush(stdout);
+ usleep(50000);
+
+ /* terminate other threads and this thread */
+ _mavlink->_task_should_exit = true;
+
+ } else {
+
+ if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) {
+ warnx("ignoring CMD spoofed with same SYS/COMP (%d/%d) ID",
+ mavlink_system.sysid, mavlink_system.compid);
+ return;
+ }
+
+ struct vehicle_command_s vcmd;
+ memset(&vcmd, 0, sizeof(vcmd));
+
+ /* Copy the content of mavlink_command_int_t cmd_mavlink into command_t cmd */
+ vcmd.param1 = cmd_mavlink.param1;
+ vcmd.param2 = cmd_mavlink.param2;
+ vcmd.param3 = cmd_mavlink.param3;
+ vcmd.param4 = cmd_mavlink.param4;
+ /* these are coordinates as 1e7 scaled integers to work around the 32 bit floating point limits */
+ vcmd.param5 = ((double)cmd_mavlink.x) / 1e7;
+ vcmd.param6 = ((double)cmd_mavlink.y) / 1e7;
+ vcmd.param7 = cmd_mavlink.z;
+ // XXX do proper translation
+ vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command;
+ vcmd.target_system = cmd_mavlink.target_system;
+ vcmd.target_component = cmd_mavlink.target_component;
+ vcmd.source_system = msg->sysid;
+ vcmd.source_component = msg->compid;
+
+ if (_cmd_pub < 0) {
+ _cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
+
+ } else {
+ orb_publish(ORB_ID(vehicle_command), _cmd_pub, &vcmd);
+ }
+ }
+ }
+}
+
+void
MavlinkReceiver::handle_message_optical_flow(mavlink_message_t *msg)
{
/* optical flow */
@@ -304,6 +380,50 @@ MavlinkReceiver::handle_message_optical_flow(mavlink_message_t *msg)
}
void
+MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
+{
+ /* optical flow */
+ mavlink_hil_optical_flow_t flow;
+ mavlink_msg_hil_optical_flow_decode(msg, &flow);
+
+ struct optical_flow_s f;
+ memset(&f, 0, sizeof(f));
+
+ f.timestamp = hrt_absolute_time();
+ f.flow_timestamp = flow.time_usec;
+ f.flow_raw_x = flow.integrated_x;
+ f.flow_raw_y = flow.integrated_y;
+ f.ground_distance_m = flow.distance;
+ f.quality = flow.quality;
+ f.sensor_id = flow.sensor_id;
+
+ if (_flow_pub < 0) {
+ _flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
+
+ } else {
+ orb_publish(ORB_ID(optical_flow), _flow_pub, &f);
+ }
+
+ /* Use distance value for range finder report */
+ struct range_finder_report r;
+ memset(&r, 0, sizeof(f));
+
+ r.timestamp = hrt_absolute_time();
+ r.error_count = 0;
+ r.type = RANGE_FINDER_TYPE_LASER;
+ r.distance = flow.distance;
+ r.minimum_distance = 0.0f;
+ r.maximum_distance = 40.0f; // this is set to match the typical range of real sensors, could be made configurable
+ r.valid = (r.distance > r.minimum_distance) && (r.distance < r.maximum_distance);
+
+ if (_range_pub < 0) {
+ _range_pub = orb_advertise(ORB_ID(sensor_range_finder), &r);
+ } else {
+ orb_publish(ORB_ID(sensor_range_finder), _range_pub, &r);
+ }
+}
+
+void
MavlinkReceiver::handle_message_set_mode(mavlink_message_t *msg)
{
mavlink_set_mode_t new_mode;
@@ -363,25 +483,263 @@ MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg)
}
void
-MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg)
+MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t *msg)
{
- mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t swarm_offboard_control;
- mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &swarm_offboard_control);
+ mavlink_set_position_target_local_ned_t set_position_target_local_ned;
+ mavlink_msg_set_position_target_local_ned_decode(msg, &set_position_target_local_ned);
+
+ struct offboard_control_setpoint_s offboard_control_sp;
+ memset(&offboard_control_sp, 0, sizeof(offboard_control_sp));//XXX breaks compatibility with multiple setpoints
+
+ /* Only accept messages which are intended for this system */
+ if ((mavlink_system.sysid == set_position_target_local_ned.target_system ||
+ set_position_target_local_ned.target_system == 0) &&
+ (mavlink_system.compid == set_position_target_local_ned.target_component ||
+ set_position_target_local_ned.target_component == 0)) {
+
+ /* convert mavlink type (local, NED) to uORB offboard control struct */
+ switch (set_position_target_local_ned.coordinate_frame) {
+ case MAV_FRAME_LOCAL_NED:
+ offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED;
+ break;
+ case MAV_FRAME_LOCAL_OFFSET_NED:
+ offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED;
+ break;
+ case MAV_FRAME_BODY_NED:
+ offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED;
+ break;
+ case MAV_FRAME_BODY_OFFSET_NED:
+ offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED;
+ break;
+ default:
+ /* invalid setpoint, avoid publishing */
+ return;
+ }
+ offboard_control_sp.position[0] = set_position_target_local_ned.x;
+ offboard_control_sp.position[1] = set_position_target_local_ned.y;
+ offboard_control_sp.position[2] = set_position_target_local_ned.z;
+ offboard_control_sp.velocity[0] = set_position_target_local_ned.vx;
+ offboard_control_sp.velocity[1] = set_position_target_local_ned.vy;
+ offboard_control_sp.velocity[2] = set_position_target_local_ned.vz;
+ offboard_control_sp.acceleration[0] = set_position_target_local_ned.afx;
+ offboard_control_sp.acceleration[1] = set_position_target_local_ned.afy;
+ offboard_control_sp.acceleration[2] = set_position_target_local_ned.afz;
+ offboard_control_sp.yaw = set_position_target_local_ned.yaw;
+ offboard_control_sp.yaw_rate = set_position_target_local_ned.yaw_rate;
+ offboard_control_sp.isForceSetpoint = (bool)(set_position_target_local_ned.type_mask & (1 << 9));
+
+ /* If we are in force control mode, for now set offboard mode to force control */
+ if (offboard_control_sp.isForceSetpoint) {
+ offboard_control_sp.mode = OFFBOARD_CONTROL_MODE_DIRECT_FORCE;
+ }
- /* Only accept system IDs from 1 to 4 */
- if (mavlink_system.sysid >= 1 && mavlink_system.sysid <= 4) {
- struct offboard_control_setpoint_s offboard_control_sp;
- memset(&offboard_control_sp, 0, sizeof(offboard_control_sp));
+ /* set ignore flags */
+ for (int i = 0; i < 9; i++) {
+ offboard_control_sp.ignore &= ~(1 << i);
+ offboard_control_sp.ignore |= (set_position_target_local_ned.type_mask & (1 << i));
+ }
+ offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_YAW);
+ offboard_control_sp.ignore |= (set_position_target_local_ned.type_mask & (1 << 10)) <<
+ OFB_IGN_BIT_YAW;
+ offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_YAWRATE);
+ offboard_control_sp.ignore |= (set_position_target_local_ned.type_mask & (1 << 11)) <<
+ OFB_IGN_BIT_YAWRATE;
- /* Convert values * 1000 back */
- offboard_control_sp.p1 = (float)swarm_offboard_control.roll[mavlink_system.sysid - 1] / 1000.0f;
- offboard_control_sp.p2 = (float)swarm_offboard_control.pitch[mavlink_system.sysid - 1] / 1000.0f;
- offboard_control_sp.p3 = (float)swarm_offboard_control.yaw[mavlink_system.sysid - 1] / 1000.0f;
- offboard_control_sp.p4 = (float)swarm_offboard_control.thrust[mavlink_system.sysid - 1] / 1000.0f;
+ offboard_control_sp.timestamp = hrt_absolute_time();
+
+ if (_offboard_control_sp_pub < 0) {
+ _offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);
+
+ } else {
+ orb_publish(ORB_ID(offboard_control_setpoint), _offboard_control_sp_pub, &offboard_control_sp);
+ }
+
+ /* If we are in offboard control mode and offboard control loop through is enabled
+ * also publish the setpoint topic which is read by the controller */
+ if (_mavlink->get_forward_externalsp()) {
+ bool updated;
+ orb_check(_control_mode_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
+ }
+ if (_control_mode.flag_control_offboard_enabled) {
+ if (offboard_control_sp.isForceSetpoint &&
+ offboard_control_sp_ignore_position_all(offboard_control_sp) &&
+ offboard_control_sp_ignore_velocity_all(offboard_control_sp)) {
+ /* The offboard setpoint is a force setpoint only, directly writing to the force
+ * setpoint topic and not publishing the setpoint triplet topic */
+ struct vehicle_force_setpoint_s force_sp;
+ force_sp.x = offboard_control_sp.acceleration[0];
+ force_sp.y = offboard_control_sp.acceleration[1];
+ force_sp.z = offboard_control_sp.acceleration[2];
+ //XXX: yaw
+ if (_force_sp_pub < 0) {
+ _force_sp_pub = orb_advertise(ORB_ID(vehicle_force_setpoint), &force_sp);
+ } else {
+ orb_publish(ORB_ID(vehicle_force_setpoint), _force_sp_pub, &force_sp);
+ }
+ } else {
+ /* It's not a pure force setpoint: publish to setpoint triplet topic */
+ struct position_setpoint_triplet_s pos_sp_triplet;
+ pos_sp_triplet.previous.valid = false;
+ pos_sp_triplet.next.valid = false;
+ pos_sp_triplet.current.valid = true;
+ pos_sp_triplet.current.type = SETPOINT_TYPE_POSITION; //XXX support others
+
+ /* set the local pos values if the setpoint type is 'local pos' and none
+ * of the local pos fields is set to 'ignore' */
+ if (offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED &&
+ !offboard_control_sp_ignore_position_some(offboard_control_sp)) {
+ pos_sp_triplet.current.position_valid = true;
+ pos_sp_triplet.current.x = offboard_control_sp.position[0];
+ pos_sp_triplet.current.y = offboard_control_sp.position[1];
+ pos_sp_triplet.current.z = offboard_control_sp.position[2];
+ } else {
+ pos_sp_triplet.current.position_valid = false;
+ }
+
+ /* set the local vel values if the setpoint type is 'local pos' and none
+ * of the local vel fields is set to 'ignore' */
+ if (offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED &&
+ !offboard_control_sp_ignore_velocity_some(offboard_control_sp)) {
+ pos_sp_triplet.current.velocity_valid = true;
+ pos_sp_triplet.current.vx = offboard_control_sp.velocity[0];
+ pos_sp_triplet.current.vy = offboard_control_sp.velocity[1];
+ pos_sp_triplet.current.vz = offboard_control_sp.velocity[2];
+ } else {
+ pos_sp_triplet.current.velocity_valid = false;
+ }
+
+ /* set the local acceleration values if the setpoint type is 'local pos' and none
+ * of the accelerations fields is set to 'ignore' */
+ if (offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED &&
+ !offboard_control_sp_ignore_acceleration_some(offboard_control_sp)) {
+ pos_sp_triplet.current.acceleration_valid = true;
+ pos_sp_triplet.current.a_x = offboard_control_sp.acceleration[0];
+ pos_sp_triplet.current.a_y = offboard_control_sp.acceleration[1];
+ pos_sp_triplet.current.a_z = offboard_control_sp.acceleration[2];
+ pos_sp_triplet.current.acceleration_is_force =
+ offboard_control_sp.isForceSetpoint;
+
+ } else {
+ pos_sp_triplet.current.acceleration_valid = false;
+ }
+
+ /* set the yaw sp value if the setpoint type is 'local pos' and the yaw
+ * field is not set to 'ignore' */
+ if (offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED &&
+ !offboard_control_sp_ignore_yaw(offboard_control_sp)) {
+ pos_sp_triplet.current.yaw_valid = true;
+ pos_sp_triplet.current.yaw = offboard_control_sp.yaw;
+
+ } else {
+ pos_sp_triplet.current.yaw_valid = false;
+ }
+
+ /* set the yawrate sp value if the setpoint type is 'local pos' and the yawrate
+ * field is not set to 'ignore' */
+ if (offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED &&
+ !offboard_control_sp_ignore_yawrate(offboard_control_sp)) {
+ pos_sp_triplet.current.yawspeed_valid = true;
+ pos_sp_triplet.current.yawspeed = offboard_control_sp.yaw_rate;
+
+ } else {
+ pos_sp_triplet.current.yawspeed_valid = false;
+ }
+ //XXX handle global pos setpoints (different MAV frames)
+
+
+ if (_pos_sp_triplet_pub < 0) {
+ _pos_sp_triplet_pub = orb_advertise(ORB_ID(position_setpoint_triplet),
+ &pos_sp_triplet);
+ } else {
+ orb_publish(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_pub,
+ &pos_sp_triplet);
+ }
+
+ }
+
+ }
+
+ }
+ }
+}
+
+void
+MavlinkReceiver::handle_message_vision_position_estimate(mavlink_message_t *msg)
+{
+ mavlink_vision_position_estimate_t pos;
+ mavlink_msg_vision_position_estimate_decode(msg, &pos);
+
+ struct vision_position_estimate vision_position;
+ memset(&vision_position, 0, sizeof(vision_position));
+
+ // Use the component ID to identify the vision sensor
+ vision_position.id = msg->compid;
+
+ vision_position.timestamp_boot = hrt_absolute_time();
+ vision_position.timestamp_computer = pos.usec;
+ vision_position.x = pos.x;
+ vision_position.y = pos.y;
+ vision_position.z = pos.z;
+
+ // XXX fix this
+ vision_position.vx = 0.0f;
+ vision_position.vy = 0.0f;
+ vision_position.vz = 0.0f;
+
+ math::Quaternion q;
+ q.from_euler(pos.roll, pos.pitch, pos.yaw);
+
+ vision_position.q[0] = q(0);
+ vision_position.q[1] = q(1);
+ vision_position.q[2] = q(2);
+ vision_position.q[3] = q(3);
+
+ if (_vision_position_pub < 0) {
+ _vision_position_pub = orb_advertise(ORB_ID(vision_position_estimate), &vision_position);
+
+ } else {
+ orb_publish(ORB_ID(vision_position_estimate), _vision_position_pub, &vision_position);
+ }
+}
+
+void
+MavlinkReceiver::handle_message_set_attitude_target(mavlink_message_t *msg)
+{
+ mavlink_set_attitude_target_t set_attitude_target;
+ mavlink_msg_set_attitude_target_decode(msg, &set_attitude_target);
+
+ struct offboard_control_setpoint_s offboard_control_sp;
+ memset(&offboard_control_sp, 0, sizeof(offboard_control_sp)); //XXX breaks compatibility with multiple setpoints
+
+ /* Only accept messages which are intended for this system */
+ if ((mavlink_system.sysid == set_attitude_target.target_system ||
+ set_attitude_target.target_system == 0) &&
+ (mavlink_system.compid == set_attitude_target.target_component ||
+ set_attitude_target.target_component == 0)) {
+ for (int i = 0; i < 4; i++) {
+ offboard_control_sp.attitude[i] = set_attitude_target.q[i];
+ }
+ offboard_control_sp.attitude_rate[0] = set_attitude_target.body_roll_rate;
+ offboard_control_sp.attitude_rate[1] = set_attitude_target.body_pitch_rate;
+ offboard_control_sp.attitude_rate[2] = set_attitude_target.body_yaw_rate;
+
+ /* set correct ignore flags for body rate fields: copy from mavlink message */
+ for (int i = 0; i < 3; i++) {
+ offboard_control_sp.ignore &= ~(1 << (i + OFB_IGN_BIT_BODYRATE_X));
+ offboard_control_sp.ignore |= (set_attitude_target.type_mask & (1 << i)) << OFB_IGN_BIT_BODYRATE_X;
+ }
+ /* set correct ignore flags for thrust field: copy from mavlink message */
+ offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_THRUST);
+ offboard_control_sp.ignore |= ((set_attitude_target.type_mask & (1 << 6)) << OFB_IGN_BIT_THRUST);
+ /* set correct ignore flags for attitude field: copy from mavlink message */
+ offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_ATT);
+ offboard_control_sp.ignore |= ((set_attitude_target.type_mask & (1 << 7)) << OFB_IGN_BIT_ATT);
- offboard_control_sp.mode = (enum OFFBOARD_CONTROL_MODE)swarm_offboard_control.mode;
offboard_control_sp.timestamp = hrt_absolute_time();
+ offboard_control_sp.mode =OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; //XXX handle rate control mode
if (_offboard_control_sp_pub < 0) {
_offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);
@@ -389,6 +747,57 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
} else {
orb_publish(ORB_ID(offboard_control_setpoint), _offboard_control_sp_pub, &offboard_control_sp);
}
+
+ /* If we are in offboard control mode and offboard control loop through is enabled
+ * also publish the setpoint topic which is read by the controller */
+ if (_mavlink->get_forward_externalsp()) {
+ bool updated;
+ orb_check(_control_mode_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
+ }
+
+ if (_control_mode.flag_control_offboard_enabled) {
+
+ /* Publish attitude setpoint if attitude and thrust ignore bits are not set */
+ if (!(offboard_control_sp_ignore_attitude(offboard_control_sp) ||
+ offboard_control_sp_ignore_thrust(offboard_control_sp))) {
+ struct vehicle_attitude_setpoint_s att_sp;
+ att_sp.timestamp = hrt_absolute_time();
+ mavlink_quaternion_to_euler(set_attitude_target.q,
+ &att_sp.roll_body, &att_sp.pitch_body, &att_sp.yaw_body);
+ mavlink_quaternion_to_dcm(set_attitude_target.q, att_sp.R_body);
+ att_sp.R_valid = true;
+ att_sp.thrust = set_attitude_target.thrust;
+ memcpy(att_sp.q_d, set_attitude_target.q, sizeof(att_sp.q_d));
+ att_sp.q_d_valid = true;
+ if (_att_sp_pub < 0) {
+ _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
+ } else {
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &att_sp);
+ }
+ }
+
+ /* Publish attitude rate setpoint if bodyrate and thrust ignore bits are not set */
+ ///XXX add support for ignoring individual axes
+ if (!(offboard_control_sp_ignore_bodyrates_some(offboard_control_sp) ||
+ offboard_control_sp_ignore_thrust(offboard_control_sp))) {
+ struct vehicle_rates_setpoint_s rates_sp;
+ rates_sp.timestamp = hrt_absolute_time();
+ rates_sp.roll = set_attitude_target.body_roll_rate;
+ rates_sp.pitch = set_attitude_target.body_pitch_rate;
+ rates_sp.yaw = set_attitude_target.body_yaw_rate;
+ rates_sp.thrust = set_attitude_target.thrust;
+
+ if (_att_sp_pub < 0) {
+ _rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
+ } else {
+ orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &rates_sp);
+ }
+ }
+ }
+
+ }
}
}
@@ -413,6 +822,8 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
tstatus.remote_noise = rstatus.remnoise;
tstatus.rxerrors = rstatus.rxerrors;
tstatus.fixed = rstatus.fixed;
+ tstatus.system_id = msg->sysid;
+ tstatus.component_id = msg->compid;
if (_telemetry_status_pub < 0) {
_telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
@@ -420,9 +831,6 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
} else {
orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus);
}
-
- /* this means that heartbeats alone won't be published to the radio status no more */
- _radio_status_available = true;
}
}
@@ -464,25 +872,17 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
struct telemetry_status_s &tstatus = _mavlink->get_rx_status();
- hrt_abstime tnow = hrt_absolute_time();
-
- /* always set heartbeat, publish only if telemetry link not up */
- tstatus.heartbeat_time = tnow;
-
- /* if no radio status messages arrive, lets at least publish that heartbeats were received */
- if (!_radio_status_available) {
+ /* set heartbeat time and topic time and publish -
+ * the telem status also gets updated on telemetry events
+ */
+ tstatus.timestamp = hrt_absolute_time();
+ tstatus.heartbeat_time = tstatus.timestamp;
- tstatus.timestamp = tnow;
- /* telem_time indicates the timestamp of a telemetry status packet and we got none */
- tstatus.telem_time = 0;
- tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC;
+ if (_telemetry_status_pub < 0) {
+ _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
- if (_telemetry_status_pub < 0) {
- _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
-
- } else {
- orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus);
- }
+ } else {
+ orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus);
}
}
}
@@ -996,7 +1396,7 @@ MavlinkReceiver::receive_start(Mavlink *parent)
struct sched_param param;
(void)pthread_attr_getschedparam(&receiveloop_attr, &param);
- param.sched_priority = SCHED_PRIORITY_MAX - 40;
+ param.sched_priority = SCHED_PRIORITY_MAX - 80;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
pthread_attr_setstacksize(&receiveloop_attr, 2900);
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index f4d0c52d8..e5f2c6a73 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -58,6 +58,7 @@
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_vicon_position.h>
+#include <uORB/topics/vision_position_estimate.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/optical_flow.h>
@@ -70,6 +71,7 @@
#include <uORB/topics/debug_key_value.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/battery_status.h>
+#include <uORB/topics/vehicle_force_setpoint.h>
#include "mavlink_ftp.h"
@@ -109,10 +111,15 @@ private:
void handle_message(mavlink_message_t *msg);
void handle_message_command_long(mavlink_message_t *msg);
+ void handle_message_command_int(mavlink_message_t *msg);
void handle_message_optical_flow(mavlink_message_t *msg);
+ void handle_message_hil_optical_flow(mavlink_message_t *msg);
void handle_message_set_mode(mavlink_message_t *msg);
void handle_message_vicon_position_estimate(mavlink_message_t *msg);
+ void handle_message_vision_position_estimate(mavlink_message_t *msg);
void handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg);
+ void handle_message_set_position_target_local_ned(mavlink_message_t *msg);
+ void handle_message_set_attitude_target(mavlink_message_t *msg);
void handle_message_radio_status(mavlink_message_t *msg);
void handle_message_manual_control(mavlink_message_t *msg);
void handle_message_heartbeat(mavlink_message_t *msg);
@@ -139,16 +146,18 @@ private:
orb_advert_t _battery_pub;
orb_advert_t _cmd_pub;
orb_advert_t _flow_pub;
+ orb_advert_t _range_pub;
orb_advert_t _offboard_control_sp_pub;
- orb_advert_t _local_pos_sp_pub;
orb_advert_t _global_vel_sp_pub;
orb_advert_t _att_sp_pub;
orb_advert_t _rates_sp_pub;
+ orb_advert_t _force_sp_pub;
+ orb_advert_t _pos_sp_triplet_pub;
orb_advert_t _vicon_position_pub;
+ orb_advert_t _vision_position_pub;
orb_advert_t _telemetry_status_pub;
orb_advert_t _rc_pub;
orb_advert_t _manual_pub;
- bool _radio_status_available;
int _control_mode_sub;
int _hil_frames;
uint64_t _old_timestamp;
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
new file mode 100644
index 000000000..4caa820b6
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
@@ -0,0 +1,761 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/// @file mavlink_ftp_test.cpp
+/// @author Don Gagne <don@thegagnes.com>
+
+#include <sys/stat.h>
+#include <crc32.h>
+#include <stdio.h>
+#include <fcntl.h>
+
+#include "mavlink_ftp_test.h"
+#include "../mavlink_ftp.h"
+
+/// @brief Test case file name for Read command. File are generated using mavlink_ftp_test_data.py
+const MavlinkFtpTest::ReadTestCase MavlinkFtpTest::_rgReadTestCases[] = {
+ { "/etc/unit_test_data/mavlink_tests/test_238.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) - 1}, // Read takes less than single packet
+ { "/etc/unit_test_data/mavlink_tests/test_239.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) }, // Read completely fills single packet
+ { "/etc/unit_test_data/mavlink_tests/test_240.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) + 1 }, // Read take two packets
+};
+
+const char MavlinkFtpTest::_unittest_microsd_dir[] = "/fs/microsd/ftp_unit_test_dir";
+const char MavlinkFtpTest::_unittest_microsd_file[] = "/fs/microsd/ftp_unit_test_dir/file";
+
+MavlinkFtpTest::MavlinkFtpTest() :
+ _ftp_server{},
+ _reply_msg{},
+ _lastOutgoingSeqNumber{}
+{
+}
+
+MavlinkFtpTest::~MavlinkFtpTest()
+{
+
+}
+
+/// @brief Called before every test to initialize the FTP Server.
+void MavlinkFtpTest::_init(void)
+{
+ _ftp_server = new MavlinkFTP;;
+ _ftp_server->set_unittest_worker(MavlinkFtpTest::receive_message, this);
+
+ _cleanup_microsd();
+}
+
+/// @brief Called after every test to take down the FTP Server.
+void MavlinkFtpTest::_cleanup(void)
+{
+ delete _ftp_server;
+
+ _cleanup_microsd();
+}
+
+/// @brief Tests for correct behavior of an Ack response.
+bool MavlinkFtpTest::_ack_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ payload.opcode = MavlinkFTP::kCmdNone;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+
+ return true;
+}
+
+/// @brief Tests for correct response to an invalid opcpde.
+bool MavlinkFtpTest::_bad_opcode_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ payload.opcode = 0xFF; // bogus opcode
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 1);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrUnknownCommand);
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a payload which an invalid data size field.
+bool MavlinkFtpTest::_bad_datasize_test(void)
+{
+ mavlink_message_t msg;
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ payload.opcode = MavlinkFTP::kCmdListDirectory;
+
+ _setup_ftp_msg(&payload, 0, nullptr, &msg);
+
+ // Set the data size to be one larger than is legal
+ ((MavlinkFTP::PayloadHeader*)((mavlink_file_transfer_protocol_t*)msg.payload64)->payload)->size = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN + 1;
+
+ _ftp_server->handle_message(nullptr /* mavlink */, &msg);
+
+ if (!_decode_message(&_reply_msg, &ftp_msg, &reply)) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 1);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrInvalidDataSize);
+
+ return true;
+}
+
+bool MavlinkFtpTest::_list_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ char response1[] = "Dempty_dir|Ftest_238.data\t238|Ftest_239.data\t239|Ftest_240.data\t240";
+ char response2[] = "Ddev|Detc|Dfs|Dobj";
+
+ struct _testCase {
+ const char *dir; ///< Directory to run List command on
+ char *response; ///< Expected response entries from List command
+ int response_count; ///< Number of directories that should be returned
+ bool success; ///< true: List command should succeed, false: List command should fail
+ };
+ struct _testCase rgTestCases[] = {
+ { "/bogus", nullptr, 0, false },
+ { "/etc/unit_test_data/mavlink_tests", response1, 4, true },
+ { "/", response2, 4, true },
+ };
+
+ for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
+ const struct _testCase *test = &rgTestCases[i];
+
+ payload.opcode = MavlinkFTP::kCmdListDirectory;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->dir)+1, // size in bytes of data
+ (uint8_t*)test->dir, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ if (test->success) {
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, strlen(test->response) + 1);
+
+ // The return order of directories from the List command is not repeatable. So we can't do a direct comparison
+ // to a hardcoded return result string.
+
+ // Convert null terminators to seperator char so we can use strok to parse returned data
+ for (uint8_t j=0; j<reply->size-1; j++) {
+ if (reply->data[j] == 0) {
+ reply->data[j] = '|';
+ }
+ }
+
+ // Loop over returned directory entries trying to find then in the response list
+ char *dir;
+ int response_count = 0;
+ dir = strtok((char *)&reply->data[0], "|");
+ while (dir != nullptr) {
+ ut_assert("Returned directory not found in expected response", strstr(test->response, dir));
+ response_count++;
+ dir = strtok(nullptr, "|");
+ }
+
+ ut_compare("Incorrect number of directory entires returned", test->response_count, response_count);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a List command on a valid directory, but with an offset that
+/// is beyond the last directory entry.
+bool MavlinkFtpTest::_list_eof_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *dir = "/";
+
+ payload.opcode = MavlinkFTP::kCmdListDirectory;
+ payload.offset = 4; // offset past top level dirs
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(dir)+1, // size in bytes of data
+ (uint8_t*)dir, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 1);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrEOF);
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to an Open command on a file which does not exist.
+bool MavlinkFtpTest::_open_badfile_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *dir = "/foo"; // non-existent file
+
+ payload.opcode = MavlinkFTP::kCmdOpenFileRO;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(dir)+1, // size in bytes of data
+ (uint8_t*)dir, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to an Open command on a file, followed by Terminate
+bool MavlinkFtpTest::_open_terminate_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ for (size_t i=0; i<sizeof(_rgReadTestCases)/sizeof(_rgReadTestCases[0]); i++) {
+ struct stat st;
+ const ReadTestCase *test = &_rgReadTestCases[i];
+
+ payload.opcode = MavlinkFTP::kCmdOpenFileRO;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->file)+1, // size in bytes of data
+ (uint8_t*)test->file, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("stat failed", stat(test->file, &st), 0);
+
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, sizeof(uint32_t));
+ ut_compare("File size incorrect", *((uint32_t*)&reply->data[0]), (uint32_t)st.st_size);
+
+ payload.opcode = MavlinkFTP::kCmdTerminateSession;
+ payload.session = reply->session;
+ payload.size = 0;
+
+ success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+ }
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a Terminate command on an invalid session.
+bool MavlinkFtpTest::_terminate_badsession_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *file = _rgReadTestCases[0].file;
+
+ payload.opcode = MavlinkFTP::kCmdOpenFileRO;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(file)+1, // size in bytes of data
+ (uint8_t*)file, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+
+ payload.opcode = MavlinkFTP::kCmdTerminateSession;
+ payload.session = reply->session + 1;
+ payload.size = 0;
+
+ success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 1);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrInvalidSession);
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a Read command on an open session.
+bool MavlinkFtpTest::_read_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ for (size_t i=0; i<sizeof(_rgReadTestCases)/sizeof(_rgReadTestCases[0]); i++) {
+ struct stat st;
+ const ReadTestCase *test = &_rgReadTestCases[i];
+
+ // Read in the file so we can compare it to what we get back
+ ut_compare("stat failed", stat(test->file, &st), 0);
+ uint8_t *bytes = new uint8_t[st.st_size];
+ ut_assert("new failed", bytes != nullptr);
+ int fd = ::open(test->file, O_RDONLY);
+ ut_assert("open failed", fd != -1);
+ int bytes_read = ::read(fd, bytes, st.st_size);
+ ut_compare("read failed", bytes_read, st.st_size);
+ ::close(fd);
+
+ // Test case data files are created for specific boundary conditions
+ ut_compare("Test case data files are out of date", test->length, st.st_size);
+
+ payload.opcode = MavlinkFTP::kCmdOpenFileRO;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->file)+1, // size in bytes of data
+ (uint8_t*)test->file, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+
+ payload.opcode = MavlinkFTP::kCmdReadFile;
+ payload.session = reply->session;
+ payload.offset = 0;
+
+ success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Offset incorrect", reply->offset, 0);
+
+ if (test->length <= MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader)) {
+ ut_compare("Payload size incorrect", reply->size, (uint32_t)st.st_size);
+ ut_compare("File contents differ", memcmp(reply->data, bytes, st.st_size), 0);
+ }
+
+ payload.opcode = MavlinkFTP::kCmdTerminateSession;
+ payload.session = reply->session;
+ payload.size = 0;
+
+ success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+ }
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a Read command on an invalid session.
+bool MavlinkFtpTest::_read_badsession_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *file = _rgReadTestCases[0].file;
+
+ payload.opcode = MavlinkFTP::kCmdOpenFileRO;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(file)+1, // size in bytes of data
+ (uint8_t*)file, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+
+ payload.opcode = MavlinkFTP::kCmdReadFile;
+ payload.session = reply->session + 1; // Invalid session
+ payload.offset = 0;
+
+ success = _send_receive_msg(&payload, // FTP payload header
+ 0, // size in bytes of data
+ nullptr, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 1);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrInvalidSession);
+
+ return true;
+}
+
+bool MavlinkFtpTest::_removedirectory_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ int fd;
+
+ struct _testCase {
+ const char *dir;
+ bool success;
+ bool deleteFile;
+ };
+ static const struct _testCase rgTestCases[] = {
+ { "/bogus", false, false },
+ { "/etc/unit_test_data/mavlink_tests/empty_dir", false, false },
+ { _unittest_microsd_dir, false, false },
+ { _unittest_microsd_file, false, false },
+ { _unittest_microsd_dir, true, true },
+ };
+
+ ut_compare("mkdir failed", ::mkdir(_unittest_microsd_dir, S_IRWXU | S_IRWXG | S_IRWXO), 0);
+ ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL)) != -1);
+ ::close(fd);
+
+ for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
+ const struct _testCase *test = &rgTestCases[i];
+
+ if (test->deleteFile) {
+ ut_compare("unlink failed", ::unlink(_unittest_microsd_file), 0);
+ }
+
+ payload.opcode = MavlinkFTP::kCmdRemoveDirectory;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->dir)+1, // size in bytes of data
+ (uint8_t*)test->dir, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ if (test->success) {
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+bool MavlinkFtpTest::_createdirectory_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ struct _testCase {
+ const char *dir;
+ bool success;
+ };
+ static const struct _testCase rgTestCases[] = {
+ { "/etc/bogus", false },
+ { _unittest_microsd_dir, true },
+ { _unittest_microsd_dir, false },
+ { "/fs/microsd/bogus/bogus", false },
+ };
+
+ for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
+ const struct _testCase *test = &rgTestCases[i];
+
+ payload.opcode = MavlinkFTP::kCmdCreateDirectory;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->dir)+1, // size in bytes of data
+ (uint8_t*)test->dir, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ if (test->success) {
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+bool MavlinkFtpTest::_removefile_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ int fd;
+
+ struct _testCase {
+ const char *file;
+ bool success;
+ };
+ static const struct _testCase rgTestCases[] = {
+ { "/bogus", false },
+ { _rgReadTestCases[0].file, false },
+ { _unittest_microsd_dir, false },
+ { _unittest_microsd_file, true },
+ { _unittest_microsd_file, false },
+ };
+
+ ut_compare("mkdir failed", ::mkdir(_unittest_microsd_dir, S_IRWXU | S_IRWXG | S_IRWXO), 0);
+ ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL)) != -1);
+ ::close(fd);
+
+ for (size_t i=0; i<sizeof(rgTestCases)/sizeof(rgTestCases[0]); i++) {
+ const struct _testCase *test = &rgTestCases[i];
+
+ payload.opcode = MavlinkFTP::kCmdRemoveFile;
+ payload.offset = 0;
+
+ bool success = _send_receive_msg(&payload, // FTP payload header
+ strlen(test->file)+1, // size in bytes of data
+ (uint8_t*)test->file, // Data to start into FTP message payload
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ if (test->success) {
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Incorrect payload size", reply->size, 0);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+/// @brief Static method used as callback from MavlinkFTP. This method will be called by MavlinkFTP when
+/// it needs to send a message out on Mavlink.
+void MavlinkFtpTest::receive_message(const mavlink_message_t *msg, MavlinkFtpTest *ftp_test)
+{
+ ftp_test->_receive_message(msg);
+}
+
+/// @brief Non-Static version of receive_message
+void MavlinkFtpTest::_receive_message(const mavlink_message_t *msg)
+{
+ // Move the message into our own member variable
+ memcpy(&_reply_msg, msg, sizeof(mavlink_message_t));
+}
+
+/// @brief Decode and validate the incoming message
+bool MavlinkFtpTest::_decode_message(const mavlink_message_t *msg, ///< Mavlink message to decode
+ mavlink_file_transfer_protocol_t *ftp_msg, ///< Decoded FTP message
+ MavlinkFTP::PayloadHeader **payload) ///< Payload inside FTP message response
+{
+ mavlink_msg_file_transfer_protocol_decode(msg, ftp_msg);
+
+ // Make sure the targets are correct
+ ut_compare("Target network non-zero", ftp_msg->target_network, 0);
+ ut_compare("Target system id mismatch", ftp_msg->target_system, clientSystemId);
+ ut_compare("Target component id mismatch", ftp_msg->target_component, clientComponentId);
+
+ *payload = reinterpret_cast<MavlinkFTP::PayloadHeader *>(ftp_msg->payload);
+
+ // Make sure we have a good sequence number
+ ut_compare("Sequence number mismatch", (*payload)->seqNumber, _lastOutgoingSeqNumber + 1);
+
+ // Bump sequence number for next outgoing message
+ _lastOutgoingSeqNumber++;
+
+ return true;
+}
+
+/// @brief Initializes an FTP message into a mavlink message
+void MavlinkFtpTest::_setup_ftp_msg(MavlinkFTP::PayloadHeader *payload_header, ///< FTP payload header
+ uint8_t size, ///< size in bytes of data
+ const uint8_t *data, ///< Data to start into FTP message payload
+ mavlink_message_t *msg) ///< Returned mavlink message
+{
+ uint8_t payload_bytes[MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN];
+ MavlinkFTP::PayloadHeader *payload = reinterpret_cast<MavlinkFTP::PayloadHeader *>(payload_bytes);
+
+ memcpy(payload, payload_header, sizeof(MavlinkFTP::PayloadHeader));
+
+ payload->seqNumber = _lastOutgoingSeqNumber;
+ payload->size = size;
+ if (size != 0) {
+ memcpy(payload->data, data, size);
+ }
+
+ payload->padding[0] = 0;
+ payload->padding[1] = 0;
+
+ msg->checksum = 0;
+ mavlink_msg_file_transfer_protocol_pack(clientSystemId, // Sender system id
+ clientComponentId, // Sender component id
+ msg, // Message to pack payload into
+ 0, // Target network
+ serverSystemId, // Target system id
+ serverComponentId, // Target component id
+ payload_bytes); // Payload to pack into message
+}
+
+/// @brief Sends the specified FTP message to the server and returns response
+bool MavlinkFtpTest::_send_receive_msg(MavlinkFTP::PayloadHeader *payload_header, ///< FTP payload header
+ uint8_t size, ///< size in bytes of data
+ const uint8_t *data, ///< Data to start into FTP message payload
+ mavlink_file_transfer_protocol_t *ftp_msg_reply, ///< Response from server
+ MavlinkFTP::PayloadHeader **payload_reply) ///< Payload inside FTP message response
+{
+ mavlink_message_t msg;
+
+ _setup_ftp_msg(payload_header, size, data, &msg);
+ _ftp_server->handle_message(nullptr /* mavlink */, &msg);
+ return _decode_message(&_reply_msg, ftp_msg_reply, payload_reply);
+}
+
+/// @brief Cleans up an files created on microsd during testing
+void MavlinkFtpTest::_cleanup_microsd(void)
+{
+ ::unlink(_unittest_microsd_file);
+ ::rmdir(_unittest_microsd_dir);
+}
+
+/// @brief Runs all the unit tests
+bool MavlinkFtpTest::run_tests(void)
+{
+ ut_run_test(_ack_test);
+ ut_run_test(_bad_opcode_test);
+ ut_run_test(_bad_datasize_test);
+ ut_run_test(_list_test);
+ ut_run_test(_list_eof_test);
+ ut_run_test(_open_badfile_test);
+ ut_run_test(_open_terminate_test);
+ ut_run_test(_terminate_badsession_test);
+ ut_run_test(_read_test);
+ ut_run_test(_read_badsession_test);
+ ut_run_test(_removedirectory_test);
+ ut_run_test(_createdirectory_test);
+ ut_run_test(_removefile_test);
+
+ return (_tests_failed == 0);
+
+}
+
+ut_declare_test(mavlink_ftp_test, MavlinkFtpTest)
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
new file mode 100644
index 000000000..2696192cc
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
@@ -0,0 +1,108 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/// @file mavlink_ftp_test.h
+/// @author Don Gagne <don@thegagnes.com>
+
+#pragma once
+
+#include <unit_test/unit_test.h>
+#include "../mavlink_bridge_header.h"
+#include "../mavlink_ftp.h"
+
+class MavlinkFtpTest : public UnitTest
+{
+public:
+ MavlinkFtpTest();
+ virtual ~MavlinkFtpTest();
+
+ virtual bool run_tests(void);
+
+ static void receive_message(const mavlink_message_t *msg, MavlinkFtpTest* ftpTest);
+
+ static const uint8_t serverSystemId = 50; ///< System ID for server
+ static const uint8_t serverComponentId = 1; ///< Component ID for server
+ static const uint8_t serverChannel = 0; ///< Channel to send to
+
+ static const uint8_t clientSystemId = 1; ///< System ID for client
+ static const uint8_t clientComponentId = 0; ///< Component ID for client
+
+ // We don't want any of these
+ MavlinkFtpTest(const MavlinkFtpTest&);
+ MavlinkFtpTest& operator=(const MavlinkFtpTest&);
+
+private:
+ virtual void _init(void);
+ virtual void _cleanup(void);
+
+ bool _ack_test(void);
+ bool _bad_opcode_test(void);
+ bool _bad_datasize_test(void);
+ bool _list_test(void);
+ bool _list_eof_test(void);
+ bool _open_badfile_test(void);
+ bool _open_terminate_test(void);
+ bool _terminate_badsession_test(void);
+ bool _read_test(void);
+ bool _read_badsession_test(void);
+ bool _removedirectory_test(void);
+ bool _createdirectory_test(void);
+ bool _removefile_test(void);
+
+ void _receive_message(const mavlink_message_t *msg);
+ void _setup_ftp_msg(MavlinkFTP::PayloadHeader *payload_header, uint8_t size, const uint8_t *data, mavlink_message_t *msg);
+ bool _decode_message(const mavlink_message_t *msg, mavlink_file_transfer_protocol_t *ftp_msg, MavlinkFTP::PayloadHeader **payload);
+ bool _send_receive_msg(MavlinkFTP::PayloadHeader *payload_header,
+ uint8_t size,
+ const uint8_t *data,
+ mavlink_file_transfer_protocol_t *ftp_msg_reply,
+ MavlinkFTP::PayloadHeader **payload_reply);
+ void _cleanup_microsd(void);
+
+ MavlinkFTP *_ftp_server;
+
+ mavlink_message_t _reply_msg;
+
+ uint16_t _lastOutgoingSeqNumber;
+
+ struct ReadTestCase {
+ const char *file;
+ const uint16_t length;
+ };
+ static const ReadTestCase _rgReadTestCases[];
+
+ static const char _unittest_microsd_dir[];
+ static const char _unittest_microsd_file[];
+};
+
+bool mavlink_ftp_test(void);
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py
new file mode 100644
index 000000000..a7e68f2a3
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py
@@ -0,0 +1,7 @@
+import sys
+print 'Arguments: file - ' + sys.argv[1] + ', length - ' + sys.argv[2]
+file = open(sys.argv[1], 'w')
+for i in range(int(sys.argv[2])):
+ b = bytearray([i & 0xFF])
+ file.write(b)
+file.close() \ No newline at end of file
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp b/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp
new file mode 100644
index 000000000..10cbcb0ec
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp
@@ -0,0 +1,47 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file mavlink_ftp_tests.cpp
+ */
+
+#include <systemlib/err.h>
+
+#include "mavlink_ftp_test.h"
+
+extern "C" __EXPORT int mavlink_tests_main(int argc, char *argv[]);
+
+int mavlink_tests_main(int argc, char *argv[])
+{
+ return mavlink_ftp_test() ? 0 : -1;
+}
diff --git a/src/modules/mavlink/mavlink_tests/module.mk b/src/modules/mavlink/mavlink_tests/module.mk
new file mode 100644
index 000000000..1cc28cce1
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/module.mk
@@ -0,0 +1,50 @@
+############################################################################
+#
+# Copyright (c) 2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# System state machine tests.
+#
+
+MODULE_COMMAND = mavlink_tests
+SRCS = mavlink_tests.cpp \
+ mavlink_ftp_test.cpp \
+ ../mavlink_ftp.cpp \
+ ../mavlink.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
+
+MODULE_STACKSIZE = 5000
+
+MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Weffc++ -DMAVLINK_FTP_UNIT_TEST
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index 9b0f69226..d52138522 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -76,6 +76,7 @@
#define TILT_COS_MAX 0.7f
#define SIGMA 0.000001f
+#define MIN_DIST 0.01f
/**
* Multicopter position control app start / stop handling function
@@ -105,6 +106,7 @@ public:
int start();
private:
+ const float alt_ctl_dz = 0.2f;
bool _task_should_exit; /**< if true, task should exit */
int _control_task; /**< task handle for task */
@@ -178,12 +180,15 @@ private:
bool _reset_pos_sp;
bool _reset_alt_sp;
+ bool _mode_auto;
math::Vector<3> _pos;
math::Vector<3> _pos_sp;
math::Vector<3> _vel;
math::Vector<3> _vel_sp;
math::Vector<3> _vel_prev; /**< velocity on previous step */
+ math::Vector<3> _vel_ff;
+ math::Vector<3> _sp_move_rate;
/**
* Update our local parameter cache.
@@ -217,6 +222,29 @@ private:
void reset_alt_sp();
/**
+ * Check if position setpoint is too far from current position and adjust it if needed.
+ */
+ void limit_pos_sp_offset();
+
+ /**
+ * Set position setpoint using manual control
+ */
+ void control_manual(float dt);
+
+ /**
+ * Set position setpoint using offboard control
+ */
+ void control_offboard(float dt);
+
+ bool cross_sphere_line(const math::Vector<3>& sphere_c, float sphere_r,
+ const math::Vector<3> line_a, const math::Vector<3> line_b, math::Vector<3>& res);
+
+ /**
+ * Set position setpoint for AUTO
+ */
+ void control_auto(float dt);
+
+ /**
* Select between barometric and global (AMSL) altitudes
*/
void select_alt(bool global);
@@ -270,7 +298,8 @@ MulticopterPositionControl::MulticopterPositionControl() :
_ref_timestamp(0),
_reset_pos_sp(true),
- _reset_alt_sp(true)
+ _reset_alt_sp(true),
+ _mode_auto(false)
{
memset(&_att, 0, sizeof(_att));
memset(&_att_sp, 0, sizeof(_att_sp));
@@ -297,6 +326,8 @@ MulticopterPositionControl::MulticopterPositionControl() :
_vel.zero();
_vel_sp.zero();
_vel_prev.zero();
+ _vel_ff.zero();
+ _sp_move_rate.zero();
_params_handles.thr_min = param_find("MPC_THR_MIN");
_params_handles.thr_max = param_find("MPC_THR_MAX");
@@ -392,9 +423,11 @@ MulticopterPositionControl::parameters_update(bool force)
param_get(_params_handles.z_vel_max, &v);
_params.vel_max(2) = v;
param_get(_params_handles.xy_ff, &v);
+ v = math::constrain(v, 0.0f, 1.0f);
_params.vel_ff(0) = v;
_params.vel_ff(1) = v;
param_get(_params_handles.z_ff, &v);
+ v = math::constrain(v, 0.0f, 1.0f);
_params.vel_ff(2) = v;
_params.sp_offs_max = _params.vel_max.edivide(_params.pos_p) * 2.0f;
@@ -497,8 +530,11 @@ MulticopterPositionControl::reset_pos_sp()
{
if (_reset_pos_sp) {
_reset_pos_sp = false;
- _pos_sp(0) = _pos(0);
- _pos_sp(1) = _pos(1);
+ /* shift position setpoint to make attitude setpoint continuous */
+ _pos_sp(0) = _pos(0) + (_vel(0) - _att_sp.R_body[0][2] * _att_sp.thrust / _params.vel_p(0)
+ - _params.vel_ff(0) * _sp_move_rate(0)) / _params.pos_p(0);
+ _pos_sp(1) = _pos(1) + (_vel(1) - _att_sp.R_body[1][2] * _att_sp.thrust / _params.vel_p(1)
+ - _params.vel_ff(1) * _sp_move_rate(1)) / _params.pos_p(1);
mavlink_log_info(_mavlink_fd, "[mpc] reset pos sp: %.2f, %.2f", (double)_pos_sp(0), (double)_pos_sp(1));
}
}
@@ -508,12 +544,317 @@ MulticopterPositionControl::reset_alt_sp()
{
if (_reset_alt_sp) {
_reset_alt_sp = false;
- _pos_sp(2) = _pos(2);
+ _pos_sp(2) = _pos(2) + (_vel(2) - _params.vel_ff(2) * _sp_move_rate(2)) / _params.pos_p(2);
mavlink_log_info(_mavlink_fd, "[mpc] reset alt sp: %.2f", -(double)_pos_sp(2));
}
}
void
+MulticopterPositionControl::limit_pos_sp_offset()
+{
+ math::Vector<3> pos_sp_offs;
+ pos_sp_offs.zero();
+
+ if (_control_mode.flag_control_position_enabled) {
+ pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0);
+ pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1);
+ }
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2);
+ }
+
+ float pos_sp_offs_norm = pos_sp_offs.length();
+
+ if (pos_sp_offs_norm > 1.0f) {
+ pos_sp_offs /= pos_sp_offs_norm;
+ _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
+ }
+}
+
+void
+MulticopterPositionControl::control_manual(float dt)
+{
+ _sp_move_rate.zero();
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ /* move altitude setpoint with throttle stick */
+ _sp_move_rate(2) = -scale_control(_manual.z - 0.5f, 0.5f, alt_ctl_dz);
+ }
+
+ if (_control_mode.flag_control_position_enabled) {
+ /* move position setpoint with roll/pitch stick */
+ _sp_move_rate(0) = _manual.x;
+ _sp_move_rate(1) = _manual.y;
+ }
+
+ /* limit setpoint move rate */
+ float sp_move_norm = _sp_move_rate.length();
+
+ if (sp_move_norm > 1.0f) {
+ _sp_move_rate /= sp_move_norm;
+ }
+
+ /* _sp_move_rate scaled to 0..1, scale it to max speed and rotate around yaw */
+ math::Matrix<3, 3> R_yaw_sp;
+ R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body);
+ _sp_move_rate = R_yaw_sp * _sp_move_rate.emult(_params.vel_max);
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ /* reset alt setpoint to current altitude if needed */
+ reset_alt_sp();
+ }
+
+ if (_control_mode.flag_control_position_enabled) {
+ /* reset position setpoint to current position if needed */
+ reset_pos_sp();
+ }
+
+ /* feed forward setpoint move rate with weight vel_ff */
+ _vel_ff = _sp_move_rate.emult(_params.vel_ff);
+
+ /* move position setpoint */
+ _pos_sp += _sp_move_rate * dt;
+
+ /* check if position setpoint is too far from actual position */
+ math::Vector<3> pos_sp_offs;
+ pos_sp_offs.zero();
+
+ if (_control_mode.flag_control_position_enabled) {
+ pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0);
+ pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1);
+ }
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2);
+ }
+
+ float pos_sp_offs_norm = pos_sp_offs.length();
+
+ if (pos_sp_offs_norm > 1.0f) {
+ pos_sp_offs /= pos_sp_offs_norm;
+ _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
+ }
+}
+
+void
+MulticopterPositionControl::control_offboard(float dt)
+{
+ bool updated;
+ orb_check(_pos_sp_triplet_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
+ }
+
+ if (_pos_sp_triplet.current.valid) {
+ if (_control_mode.flag_control_position_enabled && _pos_sp_triplet.current.position_valid) {
+ /* control position */
+ _pos_sp(0) = _pos_sp_triplet.current.x;
+ _pos_sp(1) = _pos_sp_triplet.current.y;
+ _pos_sp(2) = _pos_sp_triplet.current.z;
+
+ } else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) {
+ /* control velocity */
+ /* reset position setpoint to current position if needed */
+ reset_pos_sp();
+
+ /* set position setpoint move rate */
+ _sp_move_rate(0) = _pos_sp_triplet.current.vx;
+ _sp_move_rate(1) = _pos_sp_triplet.current.vy;
+ }
+
+ if (_pos_sp_triplet.current.yaw_valid) {
+ _att_sp.yaw_body = _pos_sp_triplet.current.yaw;
+ } else if (_pos_sp_triplet.current.yawspeed_valid) {
+ _att_sp.yaw_body = _att_sp.yaw_body + _pos_sp_triplet.current.yawspeed * dt;
+ }
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ /* reset alt setpoint to current altitude if needed */
+ reset_alt_sp();
+
+ /* set altitude setpoint move rate */
+ _sp_move_rate(2) = _pos_sp_triplet.current.vz;
+ }
+
+ /* feed forward setpoint move rate with weight vel_ff */
+ _vel_ff = _sp_move_rate.emult(_params.vel_ff);
+
+ /* move position setpoint */
+ _pos_sp += _sp_move_rate * dt;
+
+ } else {
+ reset_pos_sp();
+ reset_alt_sp();
+ }
+}
+
+bool
+MulticopterPositionControl::cross_sphere_line(const math::Vector<3>& sphere_c, float sphere_r,
+ const math::Vector<3> line_a, const math::Vector<3> line_b, math::Vector<3>& res)
+{
+ /* project center of sphere on line */
+ /* normalized AB */
+ math::Vector<3> ab_norm = line_b - line_a;
+ ab_norm.normalize();
+ math::Vector<3> d = line_a + ab_norm * ((sphere_c - line_a) * ab_norm);
+ float cd_len = (sphere_c - d).length();
+
+ /* we have triangle CDX with known CD and CX = R, find DX */
+ if (sphere_r > cd_len) {
+ /* have two roots, select one in A->B direction from D */
+ float dx_len = sqrtf(sphere_r * sphere_r - cd_len * cd_len);
+ res = d + ab_norm * dx_len;
+ return true;
+
+ } else {
+ /* have no roots, return D */
+ res = d;
+ return false;
+ }
+}
+
+void
+MulticopterPositionControl::control_auto(float dt)
+{
+ if (!_mode_auto) {
+ _mode_auto = true;
+ /* reset position setpoint on AUTO mode activation */
+ reset_pos_sp();
+ reset_alt_sp();
+ }
+
+ bool updated;
+ orb_check(_pos_sp_triplet_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
+ }
+
+ if (_pos_sp_triplet.current.valid) {
+ /* in case of interrupted mission don't go to waypoint but stay at current position */
+ _reset_pos_sp = true;
+ _reset_alt_sp = true;
+
+ /* project setpoint to local frame */
+ math::Vector<3> curr_sp;
+ map_projection_project(&_ref_pos,
+ _pos_sp_triplet.current.lat, _pos_sp_triplet.current.lon,
+ &curr_sp.data[0], &curr_sp.data[1]);
+ curr_sp(2) = -(_pos_sp_triplet.current.alt - _ref_alt);
+
+ /* scaled space: 1 == position error resulting max allowed speed, L1 = 1 in this space */
+ math::Vector<3> scale = _params.pos_p.edivide(_params.vel_max); // TODO add mult param here
+
+ /* convert current setpoint to scaled space */
+ math::Vector<3> curr_sp_s = curr_sp.emult(scale);
+
+ /* by default use current setpoint as is */
+ math::Vector<3> pos_sp_s = curr_sp_s;
+
+ if (_pos_sp_triplet.current.type == SETPOINT_TYPE_POSITION && _pos_sp_triplet.previous.valid) {
+ /* follow "previous - current" line */
+ math::Vector<3> prev_sp;
+ map_projection_project(&_ref_pos,
+ _pos_sp_triplet.previous.lat, _pos_sp_triplet.previous.lon,
+ &prev_sp.data[0], &prev_sp.data[1]);
+ prev_sp(2) = -(_pos_sp_triplet.previous.alt - _ref_alt);
+
+ if ((curr_sp - prev_sp).length() > MIN_DIST) {
+
+ /* find X - cross point of L1 sphere and trajectory */
+ math::Vector<3> pos_s = _pos.emult(scale);
+ math::Vector<3> prev_sp_s = prev_sp.emult(scale);
+ math::Vector<3> prev_curr_s = curr_sp_s - prev_sp_s;
+ math::Vector<3> curr_pos_s = pos_s - curr_sp_s;
+ float curr_pos_s_len = curr_pos_s.length();
+ if (curr_pos_s_len < 1.0f) {
+ /* copter is closer to waypoint than L1 radius */
+ /* check next waypoint and use it to avoid slowing down when passing via waypoint */
+ if (_pos_sp_triplet.next.valid) {
+ math::Vector<3> next_sp;
+ map_projection_project(&_ref_pos,
+ _pos_sp_triplet.next.lat, _pos_sp_triplet.next.lon,
+ &next_sp.data[0], &next_sp.data[1]);
+ next_sp(2) = -(_pos_sp_triplet.next.alt - _ref_alt);
+
+ if ((next_sp - curr_sp).length() > MIN_DIST) {
+ math::Vector<3> next_sp_s = next_sp.emult(scale);
+
+ /* calculate angle prev - curr - next */
+ math::Vector<3> curr_next_s = next_sp_s - curr_sp_s;
+ math::Vector<3> prev_curr_s_norm = prev_curr_s.normalized();
+
+ /* cos(a) * curr_next, a = angle between current and next trajectory segments */
+ float cos_a_curr_next = prev_curr_s_norm * curr_next_s;
+
+ /* cos(b), b = angle pos - curr_sp - prev_sp */
+ float cos_b = -curr_pos_s * prev_curr_s_norm / curr_pos_s_len;
+
+ if (cos_a_curr_next > 0.0f && cos_b > 0.0f) {
+ float curr_next_s_len = curr_next_s.length();
+ /* if curr - next distance is larger than L1 radius, limit it */
+ if (curr_next_s_len > 1.0f) {
+ cos_a_curr_next /= curr_next_s_len;
+ }
+
+ /* feed forward position setpoint offset */
+ math::Vector<3> pos_ff = prev_curr_s_norm *
+ cos_a_curr_next * cos_b * cos_b * (1.0f - curr_pos_s_len) *
+ (1.0f - expf(-curr_pos_s_len * curr_pos_s_len * 20.0f));
+ pos_sp_s += pos_ff;
+ }
+ }
+ }
+
+ } else {
+ bool near = cross_sphere_line(pos_s, 1.0f, prev_sp_s, curr_sp_s, pos_sp_s);
+ if (near) {
+ /* L1 sphere crosses trajectory */
+
+ } else {
+ /* copter is too far from trajectory */
+ /* if copter is behind prev waypoint, go directly to prev waypoint */
+ if ((pos_sp_s - prev_sp_s) * prev_curr_s < 0.0f) {
+ pos_sp_s = prev_sp_s;
+ }
+
+ /* if copter is in front of curr waypoint, go directly to curr waypoint */
+ if ((pos_sp_s - curr_sp_s) * prev_curr_s > 0.0f) {
+ pos_sp_s = curr_sp_s;
+ }
+
+ pos_sp_s = pos_s + (pos_sp_s - pos_s).normalized();
+ }
+ }
+ }
+ }
+
+ /* move setpoint not faster than max allowed speed */
+ math::Vector<3> pos_sp_old_s = _pos_sp.emult(scale);
+
+ /* difference between current and desired position setpoints, 1 = max speed */
+ math::Vector<3> d_pos_m = (pos_sp_s - pos_sp_old_s).edivide(_params.pos_p);
+ float d_pos_m_len = d_pos_m.length();
+ if (d_pos_m_len > dt) {
+ pos_sp_s = pos_sp_old_s + (d_pos_m / d_pos_m_len * dt).emult(_params.pos_p);
+ }
+
+ /* scale result back to normal space */
+ _pos_sp = pos_sp_s.edivide(scale);
+
+ /* update yaw setpoint if needed */
+ if (isfinite(_pos_sp_triplet.current.yaw)) {
+ _att_sp.yaw_body = _pos_sp_triplet.current.yaw;
+ }
+
+ } else {
+ /* no waypoint, do nothing, setpoint was already reset */
+ }
+}
+
+void
MulticopterPositionControl::task_main()
{
warnx("started");
@@ -551,13 +892,6 @@ MulticopterPositionControl::task_main()
hrt_abstime t_prev = 0;
- const float alt_ctl_dz = 0.2f;
-
- math::Vector<3> sp_move_rate;
- sp_move_rate.zero();
-
- float yaw_sp_move_rate;
-
math::Vector<3> thrust_int;
thrust_int.zero();
math::Matrix<3, 3> R;
@@ -616,172 +950,27 @@ MulticopterPositionControl::task_main()
_vel(1) = _local_pos.vy;
_vel(2) = _local_pos.vz;
- sp_move_rate.zero();
+ _vel_ff.zero();
+ _sp_move_rate.zero();
/* select control source */
if (_control_mode.flag_control_manual_enabled) {
/* manual control */
- if (_control_mode.flag_control_altitude_enabled) {
- /* reset alt setpoint to current altitude if needed */
- reset_alt_sp();
-
- /* move altitude setpoint with throttle stick */
- sp_move_rate(2) = -scale_control(_manual.z - 0.5f, 0.5f, alt_ctl_dz);
- }
-
- if (_control_mode.flag_control_position_enabled) {
- /* reset position setpoint to current position if needed */
- reset_pos_sp();
-
- /* move position setpoint with roll/pitch stick */
- sp_move_rate(0) = _manual.x;
- sp_move_rate(1) = _manual.y;
- }
-
- /* limit setpoint move rate */
- float sp_move_norm = sp_move_rate.length();
-
- if (sp_move_norm > 1.0f) {
- sp_move_rate /= sp_move_norm;
- }
-
- /* scale to max speed and rotate around yaw */
- math::Matrix<3, 3> R_yaw_sp;
- R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body);
- sp_move_rate = R_yaw_sp * sp_move_rate.emult(_params.vel_max);
-
- /* move position setpoint */
- _pos_sp += sp_move_rate * dt;
-
- /* check if position setpoint is too far from actual position */
- math::Vector<3> pos_sp_offs;
- pos_sp_offs.zero();
-
- if (_control_mode.flag_control_position_enabled) {
- pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0);
- pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1);
- }
-
- if (_control_mode.flag_control_altitude_enabled) {
- pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2);
- }
-
- float pos_sp_offs_norm = pos_sp_offs.length();
-
- if (pos_sp_offs_norm > 1.0f) {
- pos_sp_offs /= pos_sp_offs_norm;
- _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
- }
+ control_manual(dt);
+ _mode_auto = false;
} else if (_control_mode.flag_control_offboard_enabled) {
- /* Offboard control */
- bool updated;
- orb_check(_pos_sp_triplet_sub, &updated);
-
- if (updated) {
- orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
- }
-
- if (_pos_sp_triplet.current.valid) {
-
- if (_control_mode.flag_control_position_enabled && _pos_sp_triplet.current.position_valid) {
-
- _pos_sp(0) = _pos_sp_triplet.current.x;
- _pos_sp(1) = _pos_sp_triplet.current.y;
- _pos_sp(2) = _pos_sp_triplet.current.z;
- _att_sp.yaw_body = _pos_sp_triplet.current.yaw;
-
- } else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) {
- /* reset position setpoint to current position if needed */
- reset_pos_sp();
- /* move position setpoint with roll/pitch stick */
- sp_move_rate(0) = _pos_sp_triplet.current.vx;
- sp_move_rate(1) = _pos_sp_triplet.current.vy;
- yaw_sp_move_rate = _pos_sp_triplet.current.yawspeed;
- _att_sp.yaw_body = _att.yaw + yaw_sp_move_rate * dt;
- }
-
- if (_control_mode.flag_control_altitude_enabled) {
- /* reset alt setpoint to current altitude if needed */
- reset_alt_sp();
-
- /* move altitude setpoint with throttle stick */
- sp_move_rate(2) = -scale_control(_pos_sp_triplet.current.vz - 0.5f, 0.5f, alt_ctl_dz);;
- }
-
- /* limit setpoint move rate */
- float sp_move_norm = sp_move_rate.length();
-
- if (sp_move_norm > 1.0f) {
- sp_move_rate /= sp_move_norm;
- }
-
- /* scale to max speed and rotate around yaw */
- math::Matrix<3, 3> R_yaw_sp;
- R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body);
- sp_move_rate = R_yaw_sp * sp_move_rate.emult(_params.vel_max);
-
- /* move position setpoint */
- _pos_sp += sp_move_rate * dt;
-
- /* check if position setpoint is too far from actual position */
- math::Vector<3> pos_sp_offs;
- pos_sp_offs.zero();
-
- if (_control_mode.flag_control_position_enabled) {
- pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0);
- pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1);
- }
-
- if (_control_mode.flag_control_altitude_enabled) {
- pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2);
- }
-
- float pos_sp_offs_norm = pos_sp_offs.length();
-
- if (pos_sp_offs_norm > 1.0f) {
- pos_sp_offs /= pos_sp_offs_norm;
- _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
- }
-
- } else {
- reset_pos_sp();
- reset_alt_sp();
- }
+ /* offboard control */
+ control_offboard(dt);
+ _mode_auto = false;
} else {
/* AUTO */
- bool updated;
- orb_check(_pos_sp_triplet_sub, &updated);
-
- if (updated) {
- orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
- }
-
- if (_pos_sp_triplet.current.valid) {
- /* in case of interrupted mission don't go to waypoint but stay at current position */
- _reset_pos_sp = true;
- _reset_alt_sp = true;
-
- /* project setpoint to local frame */
- map_projection_project(&_ref_pos,
- _pos_sp_triplet.current.lat, _pos_sp_triplet.current.lon,
- &_pos_sp.data[0], &_pos_sp.data[1]);
- _pos_sp(2) = -(_pos_sp_triplet.current.alt - _ref_alt);
-
- /* update yaw setpoint if needed */
- if (isfinite(_pos_sp_triplet.current.yaw)) {
- _att_sp.yaw_body = _pos_sp_triplet.current.yaw;
- }
-
- } else {
- /* no waypoint, loiter, reset position setpoint if needed */
- reset_pos_sp();
- reset_alt_sp();
- }
+ control_auto(dt);
}
/* fill local position setpoint */
+ _local_pos_sp.timestamp = hrt_absolute_time();
_local_pos_sp.x = _pos_sp(0);
_local_pos_sp.y = _pos_sp(1);
_local_pos_sp.z = _pos_sp(2);
@@ -821,7 +1010,7 @@ MulticopterPositionControl::task_main()
/* run position & altitude controllers, calculate velocity setpoint */
math::Vector<3> pos_err = _pos_sp - _pos;
- _vel_sp = pos_err.emult(_params.pos_p) + sp_move_rate.emult(_params.vel_ff);
+ _vel_sp = pos_err.emult(_params.pos_p) + _vel_ff;
if (!_control_mode.flag_control_altitude_enabled) {
_reset_alt_sp = true;
@@ -839,16 +1028,6 @@ MulticopterPositionControl::task_main()
_vel_sp(2) = _params.land_speed;
}
-
- if (!_control_mode.flag_control_manual_enabled) {
- /* limit 3D speed only in non-manual modes */
- float vel_sp_norm = _vel_sp.edivide(_params.vel_max).length();
-
- if (vel_sp_norm > 1.0f) {
- _vel_sp /= vel_sp_norm;
- }
- }
-
_global_vel_sp.vx = _vel_sp(0);
_global_vel_sp.vy = _vel_sp(1);
_global_vel_sp.vz = _vel_sp(2);
@@ -901,7 +1080,7 @@ MulticopterPositionControl::task_main()
math::Vector<3> vel_err = _vel_sp - _vel;
/* derivative of velocity error, not includes setpoint acceleration */
- math::Vector<3> vel_err_d = (sp_move_rate - _vel).emult(_params.pos_p) - (_vel - _vel_prev) / dt;
+ math::Vector<3> vel_err_d = (_sp_move_rate - _vel).emult(_params.pos_p) - (_vel - _vel_prev) / dt;
_vel_prev = _vel;
/* thrust vector in NED frame */
@@ -1125,9 +1304,9 @@ MulticopterPositionControl::task_main()
/* position controller disabled, reset setpoints */
_reset_alt_sp = true;
_reset_pos_sp = true;
+ _mode_auto = false;
reset_int_z = true;
reset_int_xy = true;
-
}
/* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */
diff --git a/src/modules/navigator/datalinkloss.cpp b/src/modules/navigator/datalinkloss.cpp
new file mode 100644
index 000000000..66f1c8c73
--- /dev/null
+++ b/src/modules/navigator/datalinkloss.cpp
@@ -0,0 +1,227 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file datalinkloss.cpp
+ * Helper class for Data Link Loss Mode according to the OBC rules
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/home_position.h>
+
+#include "navigator.h"
+#include "datalinkloss.h"
+
+#define DELAY_SIGMA 0.01f
+
+DataLinkLoss::DataLinkLoss(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name),
+ _param_commsholdwaittime(this, "CH_T"),
+ _param_commsholdlat(this, "CH_LAT"),
+ _param_commsholdlon(this, "CH_LON"),
+ _param_commsholdalt(this, "CH_ALT"),
+ _param_airfieldhomelat(this, "NAV_AH_LAT", false),
+ _param_airfieldhomelon(this, "NAV_AH_LON", false),
+ _param_airfieldhomealt(this, "NAV_AH_ALT", false),
+ _param_airfieldhomewaittime(this, "AH_T"),
+ _param_numberdatalinklosses(this, "N"),
+ _param_skipcommshold(this, "CHSK"),
+ _dll_state(DLL_STATE_NONE)
+{
+ /* load initial params */
+ updateParams();
+ /* initial reset */
+ on_inactive();
+}
+
+DataLinkLoss::~DataLinkLoss()
+{
+}
+
+void
+DataLinkLoss::on_inactive()
+{
+ /* reset DLL state only if setpoint moved */
+ if (!_navigator->get_can_loiter_at_sp()) {
+ _dll_state = DLL_STATE_NONE;
+ }
+}
+
+void
+DataLinkLoss::on_activation()
+{
+ _dll_state = DLL_STATE_NONE;
+ updateParams();
+ advance_dll();
+ set_dll_item();
+}
+
+void
+DataLinkLoss::on_active()
+{
+ if (is_mission_item_reached()) {
+ updateParams();
+ advance_dll();
+ set_dll_item();
+ }
+}
+
+void
+DataLinkLoss::set_dll_item()
+{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ set_previous_pos_setpoint();
+ _navigator->set_can_loiter_at_sp(false);
+
+ switch (_dll_state) {
+ case DLL_STATE_FLYTOCOMMSHOLDWP: {
+ _mission_item.lat = (double)(_param_commsholdlat.get()) * 1.0e-7;
+ _mission_item.lon = (double)(_param_commsholdlon.get()) * 1.0e-7;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _param_commsholdalt.get();
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = _param_commsholdwaittime.get() < 0.0f ? 0.0f : _param_commsholdwaittime.get();
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ _navigator->set_can_loiter_at_sp(true);
+ break;
+ }
+ case DLL_STATE_FLYTOAIRFIELDHOMEWP: {
+ _mission_item.lat = (double)(_param_airfieldhomelat.get()) * 1.0e-7;
+ _mission_item.lon = (double)(_param_airfieldhomelon.get()) * 1.0e-7;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _param_airfieldhomealt.get();
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
+ _mission_item.time_inside = _param_airfieldhomewaittime.get() < 0.0f ? 0.0f : _param_airfieldhomewaittime.get();
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ _navigator->set_can_loiter_at_sp(true);
+ break;
+ }
+ case DLL_STATE_TERMINATE: {
+ /* Request flight termination from the commander */
+ _navigator->get_mission_result()->flight_termination = true;
+ _navigator->publish_mission_result();
+ warnx("not switched to manual: request flight termination");
+ pos_sp_triplet->previous.valid = false;
+ pos_sp_triplet->current.valid = false;
+ pos_sp_triplet->next.valid = false;
+ break;
+ }
+ default:
+ break;
+ }
+
+ reset_mission_item_reached();
+
+ /* convert mission item to current position setpoint and make it valid */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ pos_sp_triplet->next.valid = false;
+
+ _navigator->set_position_setpoint_triplet_updated();
+}
+
+void
+DataLinkLoss::advance_dll()
+{
+ switch (_dll_state) {
+ case DLL_STATE_NONE:
+ /* Check the number of data link losses. If above home fly home directly */
+ /* if number of data link losses limit is not reached fly to comms hold wp */
+ if (_navigator->get_vstatus()->data_link_lost_counter > _param_numberdatalinklosses.get()) {
+ warnx("%d data link losses, limit is %d, fly to airfield home",
+ _navigator->get_vstatus()->data_link_lost_counter, _param_numberdatalinklosses.get());
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: too many DL losses, fly to airfield home");
+ _navigator->get_mission_result()->stay_in_failsafe = true;
+ _navigator->publish_mission_result();
+ _dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
+ } else {
+ if (!_param_skipcommshold.get()) {
+ warnx("fly to comms hold, datalink loss counter: %d", _navigator->get_vstatus()->data_link_lost_counter);
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: fly to comms hold");
+ _dll_state = DLL_STATE_FLYTOCOMMSHOLDWP;
+ } else {
+ /* comms hold wp not active, fly to airfield home directly */
+ warnx("Skipping comms hold wp. Flying directly to airfield home");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: fly to airfield home, comms hold skipped");
+ _dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
+ }
+ }
+ break;
+ case DLL_STATE_FLYTOCOMMSHOLDWP:
+ warnx("fly to airfield home");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: fly to airfield home");
+ _dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP;
+ _navigator->get_mission_result()->stay_in_failsafe = true;
+ _navigator->publish_mission_result();
+ break;
+ case DLL_STATE_FLYTOAIRFIELDHOMEWP:
+ _dll_state = DLL_STATE_TERMINATE;
+ warnx("time is up, state should have been changed manually by now");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no manual control, terminating");
+ _navigator->get_mission_result()->stay_in_failsafe = true;
+ _navigator->publish_mission_result();
+ break;
+ case DLL_STATE_TERMINATE:
+ warnx("dll end");
+ _dll_state = DLL_STATE_END;
+ break;
+
+ default:
+ break;
+ }
+}
diff --git a/src/modules/navigator/datalinkloss.h b/src/modules/navigator/datalinkloss.h
new file mode 100644
index 000000000..31e0e3907
--- /dev/null
+++ b/src/modules/navigator/datalinkloss.h
@@ -0,0 +1,98 @@
+/***************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file datalinkloss.h
+ * Helper class for Data Link Loss Mode acording to the OBC rules
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#ifndef NAVIGATOR_DATALINKLOSS_H
+#define NAVIGATOR_DATALINKLOSS_H
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <uORB/Subscription.hpp>
+
+#include "navigator_mode.h"
+#include "mission_block.h"
+
+class Navigator;
+
+class DataLinkLoss : public MissionBlock
+{
+public:
+ DataLinkLoss(Navigator *navigator, const char *name);
+
+ ~DataLinkLoss();
+
+ virtual void on_inactive();
+
+ virtual void on_activation();
+
+ virtual void on_active();
+
+private:
+ /* Params */
+ control::BlockParamFloat _param_commsholdwaittime;
+ control::BlockParamInt _param_commsholdlat; // * 1e7
+ control::BlockParamInt _param_commsholdlon; // * 1e7
+ control::BlockParamFloat _param_commsholdalt;
+ control::BlockParamInt _param_airfieldhomelat; // * 1e7
+ control::BlockParamInt _param_airfieldhomelon; // * 1e7
+ control::BlockParamFloat _param_airfieldhomealt;
+ control::BlockParamFloat _param_airfieldhomewaittime;
+ control::BlockParamInt _param_numberdatalinklosses;
+ control::BlockParamInt _param_skipcommshold;
+
+ enum DLLState {
+ DLL_STATE_NONE = 0,
+ DLL_STATE_FLYTOCOMMSHOLDWP = 1,
+ DLL_STATE_FLYTOAIRFIELDHOMEWP = 2,
+ DLL_STATE_TERMINATE = 3,
+ DLL_STATE_END = 4
+ } _dll_state;
+
+ /**
+ * Set the DLL item
+ */
+ void set_dll_item();
+
+ /**
+ * Move to next DLL item
+ */
+ void advance_dll();
+
+};
+#endif
diff --git a/src/modules/navigator/datalinkloss_params.c b/src/modules/navigator/datalinkloss_params.c
new file mode 100644
index 000000000..6780c0c88
--- /dev/null
+++ b/src/modules/navigator/datalinkloss_params.c
@@ -0,0 +1,126 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file datalinkloss_params.c
+ *
+ * Parameters for DLL
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * Data Link Loss parameters, accessible via MAVLink
+ */
+
+/**
+ * Comms hold wait time
+ *
+ * The amount of time in seconds the system should wait at the comms hold waypoint
+ *
+ * @unit seconds
+ * @min 0.0
+ * @group DLL
+ */
+PARAM_DEFINE_FLOAT(NAV_DLL_CH_T, 120.0f);
+
+/**
+ * Comms hold Lat
+ *
+ * Latitude of comms hold waypoint
+ *
+ * @unit degrees * 1e7
+ * @min 0.0
+ * @group DLL
+ */
+PARAM_DEFINE_INT32(NAV_DLL_CH_LAT, -266072120);
+
+/**
+ * Comms hold Lon
+ *
+ * Longitude of comms hold waypoint
+ *
+ * @unit degrees * 1e7
+ * @min 0.0
+ * @group DLL
+ */
+PARAM_DEFINE_INT32(NAV_DLL_CH_LON, 1518453890);
+
+/**
+ * Comms hold alt
+ *
+ * Altitude of comms hold waypoint
+ *
+ * @unit m
+ * @min 0.0
+ * @group DLL
+ */
+PARAM_DEFINE_FLOAT(NAV_DLL_CH_ALT, 600.0f);
+
+/**
+ * Aifield hole wait time
+ *
+ * The amount of time in seconds the system should wait at the airfield home waypoint
+ *
+ * @unit seconds
+ * @min 0.0
+ * @group DLL
+ */
+PARAM_DEFINE_FLOAT(NAV_DLL_AH_T, 120.0f);
+
+/**
+ * Number of allowed Datalink timeouts
+ *
+ * After more than this number of data link timeouts the aircraft returns home directly
+ *
+ * @group DLL
+ * @min 0
+ * @max 1000
+ */
+PARAM_DEFINE_INT32(NAV_DLL_N, 2);
+
+/**
+ * Skip comms hold wp
+ *
+ * If set to 1 the system will skip the comms hold wp on data link loss and will directly fly to
+ * airfield home
+ *
+ * @group DLL
+ * @min 0
+ * @max 1
+ */
+PARAM_DEFINE_INT32(NAV_DLL_CHSK, 0);
diff --git a/src/modules/navigator/enginefailure.cpp b/src/modules/navigator/enginefailure.cpp
new file mode 100644
index 000000000..e007b208b
--- /dev/null
+++ b/src/modules/navigator/enginefailure.cpp
@@ -0,0 +1,149 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+ /* @file enginefailure.cpp
+ * Helper class for a fixedwing engine failure mode
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+#include <string.h>
+#include <stdlib.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+
+#include "navigator.h"
+#include "enginefailure.h"
+
+#define DELAY_SIGMA 0.01f
+
+EngineFailure::EngineFailure(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name),
+ _ef_state(EF_STATE_NONE)
+{
+ /* load initial params */
+ updateParams();
+ /* initial reset */
+ on_inactive();
+}
+
+EngineFailure::~EngineFailure()
+{
+}
+
+void
+EngineFailure::on_inactive()
+{
+ _ef_state = EF_STATE_NONE;
+}
+
+void
+EngineFailure::on_activation()
+{
+ _ef_state = EF_STATE_NONE;
+ advance_ef();
+ set_ef_item();
+}
+
+void
+EngineFailure::on_active()
+{
+ if (is_mission_item_reached()) {
+ advance_ef();
+ set_ef_item();
+ }
+}
+
+void
+EngineFailure::set_ef_item()
+{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ /* make sure we have the latest params */
+ updateParams();
+
+ set_previous_pos_setpoint();
+ _navigator->set_can_loiter_at_sp(false);
+
+ switch (_ef_state) {
+ case EF_STATE_LOITERDOWN: {
+ //XXX create mission item at ground (below?) here
+
+ _mission_item.lat = _navigator->get_global_position()->lat;
+ _mission_item.lon = _navigator->get_global_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ //XXX setting altitude to a very low value, evaluate other options
+ _mission_item.altitude = _navigator->get_home_position()->alt - 1000.0f;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_LOITER_UNLIMITED;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ _navigator->set_can_loiter_at_sp(true);
+ break;
+ }
+ default:
+ break;
+ }
+
+ reset_mission_item_reached();
+
+ /* convert mission item to current position setpoint and make it valid */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ pos_sp_triplet->next.valid = false;
+
+ _navigator->set_position_setpoint_triplet_updated();
+}
+
+void
+EngineFailure::advance_ef()
+{
+ switch (_ef_state) {
+ case EF_STATE_NONE:
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: Engine failure. Loitering down");
+ _ef_state = EF_STATE_LOITERDOWN;
+ break;
+ default:
+ break;
+ }
+}
diff --git a/src/modules/navigator/offboard.h b/src/modules/navigator/enginefailure.h
index 66b923bdb..2c48c2fce 100644
--- a/src/modules/navigator/offboard.h
+++ b/src/modules/navigator/enginefailure.h
@@ -1,6 +1,6 @@
/***************************************************************************
*
- * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -31,42 +31,53 @@
*
****************************************************************************/
/**
- * @file offboard.h
+ * @file enginefailure.h
+ * Helper class for a fixedwing engine failure mode
*
- * Helper class for offboard commands
- *
- * @author Julian Oes <julian@oes.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
-#ifndef NAVIGATOR_OFFBOARD_H
-#define NAVIGATOR_OFFBOARD_H
+#ifndef NAVIGATOR_ENGINEFAILURE_H
+#define NAVIGATOR_ENGINEFAILURE_H
#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
-#include <uORB/uORB.h>
-#include <uORB/topics/offboard_control_setpoint.h>
+#include <uORB/Subscription.hpp>
#include "navigator_mode.h"
+#include "mission_block.h"
class Navigator;
-class Offboard : public NavigatorMode
+class EngineFailure : public MissionBlock
{
public:
- Offboard(Navigator *navigator, const char *name);
+ EngineFailure(Navigator *navigator, const char *name);
- ~Offboard();
+ ~EngineFailure();
virtual void on_inactive();
virtual void on_activation();
virtual void on_active();
+
private:
- void update_offboard_control_setpoint();
+ enum EFState {
+ EF_STATE_NONE = 0,
+ EF_STATE_LOITERDOWN = 1,
+ } _ef_state;
- struct offboard_control_setpoint_s _offboard_control_sp;
-};
+ /**
+ * Set the DLL item
+ */
+ void set_ef_item();
+ /**
+ * Move to next EF item
+ */
+ void advance_ef();
+
+};
#endif
diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp
index 266215308..0f431ded2 100644
--- a/src/modules/navigator/geofence.cpp
+++ b/src/modules/navigator/geofence.cpp
@@ -48,6 +48,7 @@
#include <ctype.h>
#include <nuttx/config.h>
#include <unistd.h>
+#include <mavlink/mavlink_log.h>
/* Oddly, ERROR is not defined for C++ */
@@ -62,7 +63,12 @@ Geofence::Geofence() :
_altitude_min(0),
_altitude_max(0),
_verticesCount(0),
- param_geofence_on(this, "ON")
+ _param_geofence_on(this, "ON"),
+ _param_altitude_mode(this, "ALTMODE"),
+ _param_source(this, "SOURCE"),
+ _param_counter_threshold(this, "COUNT"),
+ _outside_counter(0),
+ _mavlinkFd(-1)
{
/* Load initial params */
updateParams();
@@ -74,27 +80,69 @@ Geofence::~Geofence()
}
-bool Geofence::inside(const struct vehicle_global_position_s *vehicle)
+bool Geofence::inside(const struct vehicle_global_position_s &global_position)
{
- double lat = vehicle->lat / 1e7d;
- double lon = vehicle->lon / 1e7d;
- //float alt = vehicle->alt;
+ return inside(global_position.lat, global_position.lon, global_position.alt);
+}
+
+bool Geofence::inside(const struct vehicle_global_position_s &global_position, float baro_altitude_amsl)
+{
+ return inside(global_position.lat, global_position.lon, baro_altitude_amsl);
+}
+
- return inside(lat, lon, vehicle->alt);
+bool Geofence::inside(const struct vehicle_global_position_s &global_position,
+ const struct vehicle_gps_position_s &gps_position,float baro_altitude_amsl) {
+ updateParams();
+
+ if (getAltitudeMode() == Geofence::GF_ALT_MODE_WGS84) {
+ if (getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
+ return inside(global_position);
+ } else {
+ return inside((double)gps_position.lat * 1.0e-7, (double)gps_position.lon * 1.0e-7,
+ (double)gps_position.alt * 1.0e-3);
+ }
+ } else {
+ if (getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
+ return inside(global_position, baro_altitude_amsl);
+ } else {
+ return inside((double)gps_position.lat * 1.0e-7, (double)gps_position.lon * 1.0e-7,
+ baro_altitude_amsl);
+ }
+ }
}
bool Geofence::inside(double lat, double lon, float altitude)
{
+ bool inside_fence = inside_polygon(lat, lon, altitude);
+
+ if (inside_fence) {
+ _outside_counter = 0;
+ return inside_fence;
+ } {
+ _outside_counter++;
+ if(_outside_counter > _param_counter_threshold.get()) {
+ return inside_fence;
+ } else {
+ return true;
+ }
+ }
+}
+
+
+bool Geofence::inside_polygon(double lat, double lon, float altitude)
+{
/* Return true if geofence is disabled */
- if (param_geofence_on.get() != 1)
+ if (_param_geofence_on.get() != 1)
return true;
if (valid()) {
if (!isEmpty()) {
/* Vertical check */
- if (altitude > _altitude_max || altitude < _altitude_min)
+ if (altitude > _altitude_max || altitude < _altitude_min) {
return false;
+ }
/*Horizontal check */
/* Adaptation of algorithm originally presented as
@@ -284,8 +332,10 @@ Geofence::loadFromFile(const char *filename)
{
_verticesCount = pointCounter;
warnx("Geofence: imported successfully");
+ mavlink_log_info(_mavlinkFd, "Geofence imported");
} else {
warnx("Geofence: import error");
+ mavlink_log_critical(_mavlinkFd, "#audio: Geofence import error");
}
return ERROR;
diff --git a/src/modules/navigator/geofence.h b/src/modules/navigator/geofence.h
index 2eb126ab5..9d647cb68 100644
--- a/src/modules/navigator/geofence.h
+++ b/src/modules/navigator/geofence.h
@@ -42,6 +42,9 @@
#define GEOFENCE_H_
#include <uORB/topics/fence.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/sensor_combined.h>
#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
@@ -49,30 +52,32 @@
class Geofence : public control::SuperBlock
{
-private:
- orb_advert_t _fence_pub; /**< publish fence topic */
-
- float _altitude_min;
- float _altitude_max;
-
- unsigned _verticesCount;
-
- /* Params */
- control::BlockParamInt param_geofence_on;
public:
Geofence();
~Geofence();
+ /* Altitude mode, corresponding to the param GF_ALTMODE */
+ enum {
+ GF_ALT_MODE_WGS84 = 0,
+ GF_ALT_MODE_AMSL = 1
+ };
+
+ /* Source, corresponding to the param GF_SOURCE */
+ enum {
+ GF_SOURCE_GLOBALPOS = 0,
+ GF_SOURCE_GPS = 1
+ };
+
/**
- * Return whether craft is inside geofence.
+ * Return whether system is inside geofence.
*
* Calculate whether point is inside arbitrary polygon
* @param craft pointer craft coordinates
- * @param fence pointer to array of coordinates, one per vertex. First and last vertex are assumed connected
- * @return true: craft is inside fence, false:craft is outside fence
+ * @return true: system is inside fence, false: system is outside fence
*/
- bool inside(const struct vehicle_global_position_s *craft);
- bool inside(double lat, double lon, float altitude);
+ bool inside(const struct vehicle_global_position_s &global_position,
+ const struct vehicle_gps_position_s &gps_position,float baro_altitude_amsl);
+ bool inside_polygon(double lat, double lon, float altitude);
int clearDm();
@@ -88,6 +93,34 @@ public:
int loadFromFile(const char *filename);
bool isEmpty() {return _verticesCount == 0;}
+
+ int getAltitudeMode() { return _param_altitude_mode.get(); }
+
+ int getSource() { return _param_source.get(); }
+
+ void setMavlinkFd(int value) { _mavlinkFd = value; }
+
+private:
+ orb_advert_t _fence_pub; /**< publish fence topic */
+
+ float _altitude_min;
+ float _altitude_max;
+
+ unsigned _verticesCount;
+
+ /* Params */
+ control::BlockParamInt _param_geofence_on;
+ control::BlockParamInt _param_altitude_mode;
+ control::BlockParamInt _param_source;
+ control::BlockParamInt _param_counter_threshold;
+
+ uint8_t _outside_counter;
+
+ int _mavlinkFd;
+
+ bool inside(double lat, double lon, float altitude);
+ bool inside(const struct vehicle_global_position_s &global_position);
+ bool inside(const struct vehicle_global_position_s &global_position, float baro_altitude_amsl);
};
diff --git a/src/modules/navigator/geofence_params.c b/src/modules/navigator/geofence_params.c
index 653b1ad84..fca3918e1 100644
--- a/src/modules/navigator/geofence_params.c
+++ b/src/modules/navigator/geofence_params.c
@@ -58,3 +58,39 @@
* @group Geofence
*/
PARAM_DEFINE_INT32(GF_ON, 1);
+
+/**
+ * Geofence altitude mode
+ *
+ * Select which altitude reference should be used
+ * 0 = WGS84, 1 = AMSL
+ *
+ * @min 0
+ * @max 1
+ * @group Geofence
+ */
+PARAM_DEFINE_INT32(GF_ALTMODE, 0);
+
+/**
+ * Geofence source
+ *
+ * Select which position source should be used. Selecting GPS instead of global position makes sure that there is
+ * no dependence on the position estimator
+ * 0 = global position, 1 = GPS
+ *
+ * @min 0
+ * @max 1
+ * @group Geofence
+ */
+PARAM_DEFINE_INT32(GF_SOURCE, 0);
+
+/**
+ * Geofence counter limit
+ *
+ * Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered
+ *
+ * @min -1
+ * @max 10
+ * @group Geofence
+ */
+PARAM_DEFINE_INT32(GF_COUNT, -1);
diff --git a/src/modules/navigator/gpsfailure.cpp b/src/modules/navigator/gpsfailure.cpp
new file mode 100644
index 000000000..cd55f60b0
--- /dev/null
+++ b/src/modules/navigator/gpsfailure.cpp
@@ -0,0 +1,178 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file gpsfailure.cpp
+ * Helper class for gpsfailure mode according to the OBC rules
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/home_position.h>
+
+#include "navigator.h"
+#include "gpsfailure.h"
+
+#define DELAY_SIGMA 0.01f
+
+GpsFailure::GpsFailure(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name),
+ _param_loitertime(this, "LT"),
+ _param_openlooploiter_roll(this, "R"),
+ _param_openlooploiter_pitch(this, "P"),
+ _param_openlooploiter_thrust(this, "TR"),
+ _gpsf_state(GPSF_STATE_NONE),
+ _timestamp_activation(0)
+{
+ /* load initial params */
+ updateParams();
+ /* initial reset */
+ on_inactive();
+}
+
+GpsFailure::~GpsFailure()
+{
+}
+
+void
+GpsFailure::on_inactive()
+{
+ /* reset GPSF state only if setpoint moved */
+ if (!_navigator->get_can_loiter_at_sp()) {
+ _gpsf_state = GPSF_STATE_NONE;
+ }
+}
+
+void
+GpsFailure::on_activation()
+{
+ _gpsf_state = GPSF_STATE_NONE;
+ _timestamp_activation = hrt_absolute_time();
+ updateParams();
+ advance_gpsf();
+ set_gpsf_item();
+}
+
+void
+GpsFailure::on_active()
+{
+
+ switch (_gpsf_state) {
+ case GPSF_STATE_LOITER: {
+ /* Position controller does not run in this mode:
+ * navigator has to publish an attitude setpoint */
+ _navigator->get_att_sp()->roll_body = M_DEG_TO_RAD_F * _param_openlooploiter_roll.get();
+ _navigator->get_att_sp()->pitch_body = M_DEG_TO_RAD_F * _param_openlooploiter_pitch.get();
+ _navigator->get_att_sp()->thrust = _param_openlooploiter_thrust.get();
+ _navigator->publish_att_sp();
+
+ /* Measure time */
+ hrt_abstime elapsed = hrt_elapsed_time(&_timestamp_activation);
+
+ //warnx("open loop loiter, posctl enabled %u, elapsed %.1fs, thrust %.2f",
+ //_navigator->get_control_mode()->flag_control_position_enabled, elapsed * 1e-6, (double)_param_openlooploiter_thrust.get());
+ if (elapsed > _param_loitertime.get() * 1e6f) {
+ /* no recovery, adavance the state machine */
+ warnx("gps not recovered, switch to next state");
+ advance_gpsf();
+ }
+ break;
+ }
+ case GPSF_STATE_TERMINATE:
+ set_gpsf_item();
+ advance_gpsf();
+ break;
+ default:
+ break;
+ }
+}
+
+void
+GpsFailure::set_gpsf_item()
+{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ /* Set pos sp triplet to invalid to stop pos controller */
+ pos_sp_triplet->previous.valid = false;
+ pos_sp_triplet->current.valid = false;
+ pos_sp_triplet->next.valid = false;
+
+ switch (_gpsf_state) {
+ case GPSF_STATE_TERMINATE: {
+ /* Request flight termination from the commander */
+ _navigator->get_mission_result()->flight_termination = true;
+ _navigator->publish_mission_result();
+ warnx("gps fail: request flight termination");
+ }
+ default:
+ break;
+ }
+
+ reset_mission_item_reached();
+ _navigator->set_position_setpoint_triplet_updated();
+}
+
+void
+GpsFailure::advance_gpsf()
+{
+ updateParams();
+
+ switch (_gpsf_state) {
+ case GPSF_STATE_NONE:
+ _gpsf_state = GPSF_STATE_LOITER;
+ warnx("gpsf loiter");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: open loop loiter");
+ break;
+ case GPSF_STATE_LOITER:
+ _gpsf_state = GPSF_STATE_TERMINATE;
+ warnx("gpsf terminate");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no gps recovery, termination");
+ warnx("mavlink sent");
+ break;
+ case GPSF_STATE_TERMINATE:
+ warnx("gpsf end");
+ _gpsf_state = GPSF_STATE_END;
+ default:
+ break;
+ }
+}
diff --git a/src/modules/navigator/gpsfailure.h b/src/modules/navigator/gpsfailure.h
new file mode 100644
index 000000000..e9e72babf
--- /dev/null
+++ b/src/modules/navigator/gpsfailure.h
@@ -0,0 +1,97 @@
+/***************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file gpsfailure.h
+ * Helper class for Data Link Loss Mode according to the OBC rules
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#ifndef NAVIGATOR_GPSFAILURE_H
+#define NAVIGATOR_GPSFAILURE_H
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <uORB/uORB.h>
+#include <uORB/Publication.hpp>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+
+#include <drivers/drv_hrt.h>
+
+#include "navigator_mode.h"
+#include "mission_block.h"
+
+class Navigator;
+
+class GpsFailure : public MissionBlock
+{
+public:
+ GpsFailure(Navigator *navigator, const char *name);
+
+ ~GpsFailure();
+
+ virtual void on_inactive();
+
+ virtual void on_activation();
+
+ virtual void on_active();
+
+private:
+ /* Params */
+ control::BlockParamFloat _param_loitertime;
+ control::BlockParamFloat _param_openlooploiter_roll;
+ control::BlockParamFloat _param_openlooploiter_pitch;
+ control::BlockParamFloat _param_openlooploiter_thrust;
+
+ enum GPSFState {
+ GPSF_STATE_NONE = 0,
+ GPSF_STATE_LOITER = 1,
+ GPSF_STATE_TERMINATE = 2,
+ GPSF_STATE_END = 3,
+ } _gpsf_state;
+
+ hrt_abstime _timestamp_activation; //*< timestamp when this mode was activated */
+
+ /**
+ * Set the GPSF item
+ */
+ void set_gpsf_item();
+
+ /**
+ * Move to next GPSF item
+ */
+ void advance_gpsf();
+
+};
+#endif
diff --git a/src/modules/navigator/gpsfailure_params.c b/src/modules/navigator/gpsfailure_params.c
new file mode 100644
index 000000000..39d179eed
--- /dev/null
+++ b/src/modules/navigator/gpsfailure_params.c
@@ -0,0 +1,97 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file gpsfailure_params.c
+ *
+ * Parameters for GPSF navigation mode
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * GPS Failure Navigation Mode parameters, accessible via MAVLink
+ */
+
+/**
+ * Loiter time
+ *
+ * The amount of time in seconds the system should do open loop loiter and wait for gps recovery
+ * before it goes into flight termination.
+ *
+ * @unit seconds
+ * @min 0.0
+ * @group GPSF
+ */
+PARAM_DEFINE_FLOAT(NAV_GPSF_LT, 30.0f);
+
+/**
+ * Open loop loiter roll
+ *
+ * Roll in degrees during the open loop loiter
+ *
+ * @unit deg
+ * @min 0.0
+ * @max 30.0
+ * @group GPSF
+ */
+PARAM_DEFINE_FLOAT(NAV_GPSF_R, 15.0f);
+
+/**
+ * Open loop loiter pitch
+ *
+ * Pitch in degrees during the open loop loiter
+ *
+ * @unit deg
+ * @min -30.0
+ * @max 30.0
+ * @group GPSF
+ */
+PARAM_DEFINE_FLOAT(NAV_GPSF_P, 0.0f);
+
+/**
+ * Open loop loiter thrust
+ *
+ * Thrust value which is set during the open loop loiter
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group GPSF
+ */
+PARAM_DEFINE_FLOAT(NAV_GPSF_TR, 0.7f);
+
+
diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp
index 12f6b9c21..7fac69a61 100644
--- a/src/modules/navigator/mission.cpp
+++ b/src/modules/navigator/mission.cpp
@@ -36,12 +36,15 @@
* Helper class to access missions
*
* @author Julian Oes <julian@oes.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <sys/types.h>
#include <string.h>
#include <stdlib.h>
#include <unistd.h>
+#include <float.h>
#include <drivers/drv_hrt.h>
@@ -49,6 +52,7 @@
#include <mavlink/mavlink_log.h>
#include <systemlib/err.h>
#include <geo/geo.h>
+#include <lib/mathlib/mathlib.h>
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
@@ -59,20 +63,23 @@
Mission::Mission(Navigator *navigator, const char *name) :
MissionBlock(navigator, name),
- _param_onboard_enabled(this, "ONBOARD_EN"),
- _param_takeoff_alt(this, "TAKEOFF_ALT"),
- _param_dist_1wp(this, "DIST_1WP"),
+ _param_onboard_enabled(this, "MIS_ONBOARD_EN", false),
+ _param_takeoff_alt(this, "MIS_TAKEOFF_ALT", false),
+ _param_dist_1wp(this, "MIS_DIST_1WP", false),
+ _param_altmode(this, "MIS_ALTMODE", false),
_onboard_mission({0}),
_offboard_mission({0}),
_current_onboard_mission_index(-1),
_current_offboard_mission_index(-1),
_need_takeoff(true),
_takeoff(false),
- _mission_result_pub(-1),
- _mission_result({0}),
_mission_type(MISSION_TYPE_NONE),
_inited(false),
- _dist_1wp_ok(false)
+ _dist_1wp_ok(false),
+ _missionFeasiblityChecker(),
+ _min_current_sp_distance_xy(FLT_MAX),
+ _mission_item_previous_alt(NAN),
+ _distance_current_previous(0.0f)
{
/* load initial params */
updateParams();
@@ -107,6 +114,7 @@ Mission::on_inactive()
update_offboard_mission();
}
+ /* require takeoff after non-loiter or landing */
if (!_navigator->get_can_loiter_at_sp() || _navigator->get_vstatus()->condition_landed) {
_need_takeoff = true;
}
@@ -141,9 +149,22 @@ Mission::on_active()
/* lets check if we reached the current mission item */
if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) {
- advance_mission();
- set_mission_items();
+ if (_mission_item.autocontinue) {
+ /* switch to next waypoint if 'autocontinue' flag set */
+ advance_mission();
+ set_mission_items();
+ } else {
+ /* else just report that item reached */
+ if (_mission_type == MISSION_TYPE_OFFBOARD) {
+ if (!(_navigator->get_mission_result()->seq_reached == _current_offboard_mission_index && _navigator->get_mission_result()->reached)) {
+ set_mission_item_reached();
+ }
+ }
+ }
+
+ } else if (_mission_type != MISSION_TYPE_NONE &&_param_altmode.get() == MISSION_ALTMODE_FOH) {
+ altitude_sp_foh_update();
} else {
/* if waypoint position reached allow loiter on the setpoint */
if (_waypoint_position_reached && _mission_item.nav_cmd != NAV_CMD_IDLE) {
@@ -202,7 +223,7 @@ Mission::update_offboard_mission()
* however warnings are issued to the gcs via mavlink from inside the MissionFeasiblityChecker */
dm_item_t dm_current = DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id);
- missionFeasiblityChecker.checkMissionFeasible(_navigator->get_vstatus()->is_rotary_wing,
+ _missionFeasiblityChecker.checkMissionFeasible(_navigator->get_vstatus()->is_rotary_wing,
dm_current, (size_t) _offboard_mission.count, _navigator->get_geofence(),
_navigator->get_home_position()->alt);
@@ -213,7 +234,7 @@ Mission::update_offboard_mission()
_current_offboard_mission_index = 0;
}
- report_current_offboard_mission_item();
+ set_current_offboard_mission_item();
}
@@ -273,6 +294,10 @@ Mission::check_dist_1wp()
if (dist_to_1wp < _param_dist_1wp.get()) {
_dist_1wp_ok = true;
+ if (dist_to_1wp > ((_param_dist_1wp.get() * 3) / 2)) {
+ /* allow at 2/3 distance, but warn */
+ mavlink_log_critical(_navigator->get_mavlink_fd(), "Warning: First waypoint very far: %d m", (int)dist_to_1wp);
+ }
return true;
} else {
@@ -309,11 +334,19 @@ Mission::set_mission_items()
/* make sure param is up to date */
updateParams();
+ /* reset the altitude foh logic, if altitude foh is enabled (param) a new foh element starts now */
+ altitude_sp_foh_reset();
+
struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
/* set previous position setpoint to current */
set_previous_pos_setpoint();
+ /* Copy previous mission item altitude (can be extended to a copy of the full mission item if needed) */
+ if (pos_sp_triplet->previous.valid) {
+ _mission_item_previous_alt = _mission_item.altitude;
+ }
+
/* get home distance state */
bool home_dist_ok = check_dist_1wp();
/* the home dist check provides user feedback, so we initialize it to this */
@@ -339,6 +372,10 @@ Mission::set_mission_items()
/* no mission available or mission finished, switch to loiter */
if (_mission_type != MISSION_TYPE_NONE) {
mavlink_log_critical(_navigator->get_mavlink_fd(), "mission finished, loitering");
+
+ /* use last setpoint for loiter */
+ _navigator->set_can_loiter_at_sp(true);
+
} else if (!user_feedback_done) {
/* only tell users that we got no mission if there has not been any
* better, more specific feedback yet
@@ -355,10 +392,11 @@ Mission::set_mission_items()
mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
pos_sp_triplet->next.valid = false;
+ /* reuse setpoint for LOITER only if it's not IDLE */
_navigator->set_can_loiter_at_sp(pos_sp_triplet->current.type == SETPOINT_TYPE_LOITER);
reset_mission_item_reached();
- report_mission_finished();
+ set_mission_finished();
_navigator->set_position_setpoint_triplet_updated();
return;
@@ -395,7 +433,7 @@ Mission::set_mission_items()
takeoff_alt += _navigator->get_home_position()->alt;
}
- /* perform takeoff at least to NAV_TAKEOFF_ALT above home/ground, even if first waypoint is lower */
+ /* takeoff to at least NAV_TAKEOFF_ALT above home/ground, even if first waypoint is lower */
if (_navigator->get_vstatus()->condition_landed) {
takeoff_alt = fmaxf(takeoff_alt, _navigator->get_global_position()->alt + _param_takeoff_alt.get());
@@ -403,32 +441,46 @@ Mission::set_mission_items()
takeoff_alt = fmaxf(takeoff_alt, _navigator->get_home_position()->alt + _param_takeoff_alt.get());
}
- mavlink_log_critical(_navigator->get_mavlink_fd(), "takeoff to %.1f meters above home", (double)(takeoff_alt - _navigator->get_home_position()->alt));
+ /* check if we already above takeoff altitude */
+ if (_navigator->get_global_position()->alt < takeoff_alt - _navigator->get_acceptance_radius()) {
+ mavlink_log_critical(_navigator->get_mavlink_fd(), "takeoff to %.1f meters above home", (double)(takeoff_alt - _navigator->get_home_position()->alt));
- _mission_item.lat = _navigator->get_global_position()->lat;
- _mission_item.lon = _navigator->get_global_position()->lon;
- _mission_item.altitude = takeoff_alt;
- _mission_item.altitude_is_relative = false;
+ _mission_item.nav_cmd = NAV_CMD_TAKEOFF;
+ _mission_item.lat = _navigator->get_global_position()->lat;
+ _mission_item.lon = _navigator->get_global_position()->lon;
+ _mission_item.altitude = takeoff_alt;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.autocontinue = true;
+ _mission_item.time_inside = 0;
- mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
- } else {
- /* set current position setpoint from mission item */
- mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ _navigator->set_position_setpoint_triplet_updated();
+ return;
- /* require takeoff after landing or idle */
- if (pos_sp_triplet->current.type == SETPOINT_TYPE_LAND || pos_sp_triplet->current.type == SETPOINT_TYPE_IDLE) {
- _need_takeoff = true;
+ } else {
+ /* skip takeoff */
+ _takeoff = false;
}
+ }
- _navigator->set_can_loiter_at_sp(false);
- reset_mission_item_reached();
+ /* set current position setpoint from mission item */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
- if (_mission_type == MISSION_TYPE_OFFBOARD) {
- report_current_offboard_mission_item();
- }
- // TODO: report onboard mission item somehow
+ /* require takeoff after landing or idle */
+ if (pos_sp_triplet->current.type == SETPOINT_TYPE_LAND || pos_sp_triplet->current.type == SETPOINT_TYPE_IDLE) {
+ _need_takeoff = true;
+ }
+
+ _navigator->set_can_loiter_at_sp(false);
+ reset_mission_item_reached();
+
+ if (_mission_type == MISSION_TYPE_OFFBOARD) {
+ set_current_offboard_mission_item();
+ }
+ // TODO: report onboard mission item somehow
+ if (_mission_item.autocontinue && _mission_item.time_inside <= 0.001f) {
/* try to read next mission item */
struct mission_item_s mission_item_next;
@@ -440,11 +492,81 @@ Mission::set_mission_items()
/* next mission item is not available */
pos_sp_triplet->next.valid = false;
}
+
+ } else {
+ /* vehicle will be paused on current waypoint, don't set next item */
+ pos_sp_triplet->next.valid = false;
+ }
+
+ /* Save the distance between the current sp and the previous one */
+ if (pos_sp_triplet->current.valid && pos_sp_triplet->previous.valid) {
+ _distance_current_previous = get_distance_to_next_waypoint(pos_sp_triplet->current.lat,
+ pos_sp_triplet->current.lon,
+ pos_sp_triplet->previous.lat,
+ pos_sp_triplet->previous.lon);
}
_navigator->set_position_setpoint_triplet_updated();
}
+void
+Mission::altitude_sp_foh_update()
+{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ /* Don't change setpoint if last and current waypoint are not valid */
+ if (!pos_sp_triplet->previous.valid || !pos_sp_triplet->current.valid ||
+ !isfinite(_mission_item_previous_alt)) {
+ return;
+ }
+
+ /* Do not try to find a solution if the last waypoint is inside the acceptance radius of the current one */
+ if (_distance_current_previous - _mission_item.acceptance_radius < 0.0f) {
+ return;
+ }
+
+ /* Don't do FOH for landing and takeoff waypoints, the ground may be near
+ * and the FW controller has a custom landing logic */
+ if (_mission_item.nav_cmd == NAV_CMD_LAND || _mission_item.nav_cmd == NAV_CMD_TAKEOFF) {
+ return;
+ }
+
+
+ /* Calculate distance to current waypoint */
+ float d_current = get_distance_to_next_waypoint(_mission_item.lat, _mission_item.lon,
+ _navigator->get_global_position()->lat, _navigator->get_global_position()->lon);
+
+ /* Save distance to waypoint if it is the smallest ever achieved, however make sure that
+ * _min_current_sp_distance_xy is never larger than the distance between the current and the previous wp */
+ _min_current_sp_distance_xy = math::min(math::min(d_current, _min_current_sp_distance_xy),
+ _distance_current_previous);
+
+ /* if the minimal distance is smaller then the acceptance radius, we should be at waypoint alt
+ * navigator will soon switch to the next waypoint item (if there is one) as soon as we reach this altitude */
+ if (_min_current_sp_distance_xy < _mission_item.acceptance_radius) {
+ pos_sp_triplet->current.alt = _mission_item.altitude;
+ } else {
+ /* update the altitude sp of the 'current' item in the sp triplet, but do not update the altitude sp
+ * of the mission item as it is used to check if the mission item is reached
+ * The setpoint is set linearly and such that the system reaches the current altitude at the acceptance
+ * radius around the current waypoint
+ **/
+ float delta_alt = (_mission_item.altitude - _mission_item_previous_alt);
+ float grad = -delta_alt/(_distance_current_previous - _mission_item.acceptance_radius);
+ float a = _mission_item_previous_alt - grad * _distance_current_previous;
+ pos_sp_triplet->current.alt = a + grad * _min_current_sp_distance_xy;
+
+ }
+
+ _navigator->set_position_setpoint_triplet_updated();
+}
+
+void
+Mission::altitude_sp_foh_reset()
+{
+ _min_current_sp_distance_xy = FLT_MAX;
+}
+
bool
Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s *mission_item)
{
@@ -580,45 +702,28 @@ Mission::save_offboard_mission_state()
}
void
-Mission::report_mission_item_reached()
+Mission::set_mission_item_reached()
{
- if (_mission_type == MISSION_TYPE_OFFBOARD) {
- _mission_result.reached = true;
- _mission_result.seq_reached = _current_offboard_mission_index;
- }
- publish_mission_result();
+ _navigator->get_mission_result()->reached = true;
+ _navigator->get_mission_result()->seq_reached = _current_offboard_mission_index;
+ _navigator->publish_mission_result();
}
void
-Mission::report_current_offboard_mission_item()
+Mission::set_current_offboard_mission_item()
{
warnx("current offboard mission index: %d", _current_offboard_mission_index);
- _mission_result.seq_current = _current_offboard_mission_index;
- publish_mission_result();
+ _navigator->get_mission_result()->reached = false;
+ _navigator->get_mission_result()->finished = false;
+ _navigator->get_mission_result()->seq_current = _current_offboard_mission_index;
+ _navigator->publish_mission_result();
save_offboard_mission_state();
}
void
-Mission::report_mission_finished()
-{
- _mission_result.finished = true;
- publish_mission_result();
-}
-
-void
-Mission::publish_mission_result()
+Mission::set_mission_finished()
{
- /* lazily publish the mission result only once available */
- if (_mission_result_pub > 0) {
- /* publish mission result */
- orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);
-
- } else {
- /* advertise and publish */
- _mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
- }
- /* reset reached bool */
- _mission_result.reached = false;
- _mission_result.finished = false;
+ _navigator->get_mission_result()->finished = true;
+ _navigator->publish_mission_result();
}
diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h
index 4da6a1155..ea7cc0927 100644
--- a/src/modules/navigator/mission.h
+++ b/src/modules/navigator/mission.h
@@ -36,6 +36,8 @@
* Navigator mode to access missions
*
* @author Julian Oes <julian@oes.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#ifndef NAVIGATOR_MISSION_H
@@ -75,6 +77,11 @@ public:
virtual void on_active();
+ enum mission_altitude_mode {
+ MISSION_ALTMODE_ZOH = 0,
+ MISSION_ALTMODE_FOH = 1
+ };
+
private:
/**
* Update onboard mission topic
@@ -103,6 +110,16 @@ private:
void set_mission_items();
/**
+ * Updates the altitude sp to follow a foh
+ */
+ void altitude_sp_foh_update();
+
+ /**
+ * Resets the altitude sp foh logic
+ */
+ void altitude_sp_foh_reset();
+
+ /**
* Read current or next mission item from the dataman and watch out for DO_JUMPS
* @return true if successful
*/
@@ -114,39 +131,32 @@ private:
void save_offboard_mission_state();
/**
- * Report that a mission item has been reached
- */
- void report_mission_item_reached();
-
- /**
- * Rport the current mission item
+ * Set a mission item as reached
*/
- void report_current_offboard_mission_item();
+ void set_mission_item_reached();
/**
- * Report that the mission is finished if one exists or that none exists
+ * Set the current offboard mission item
*/
- void report_mission_finished();
+ void set_current_offboard_mission_item();
/**
- * Publish the mission result so commander and mavlink know what is going on
+ * Set that the mission is finished if one exists or that none exists
*/
- void publish_mission_result();
+ void set_mission_finished();
control::BlockParamInt _param_onboard_enabled;
control::BlockParamFloat _param_takeoff_alt;
control::BlockParamFloat _param_dist_1wp;
+ control::BlockParamInt _param_altmode;
struct mission_s _onboard_mission;
struct mission_s _offboard_mission;
int _current_onboard_mission_index;
int _current_offboard_mission_index;
- bool _need_takeoff;
- bool _takeoff;
-
- orb_advert_t _mission_result_pub;
- struct mission_result_s _mission_result;
+ bool _need_takeoff; /**< if true, then takeoff must be performed before going to the first waypoint (if needed) */
+ bool _takeoff; /**< takeoff state flag */
enum {
MISSION_TYPE_NONE,
@@ -157,7 +167,13 @@ private:
bool _inited;
bool _dist_1wp_ok;
- MissionFeasibilityChecker missionFeasiblityChecker; /**< class that checks if a mission is feasible */
+ MissionFeasibilityChecker _missionFeasiblityChecker; /**< class that checks if a mission is feasible */
+
+ float _min_current_sp_distance_xy; /**< minimum distance which was achieved to the current waypoint */
+ float _mission_item_previous_alt; /**< holds the altitude of the previous mission item,
+ can be replaced by a full copy of the previous mission item if needed*/
+ float _distance_current_previous; /**< distance from previous to current sp in pos_sp_triplet,
+ only use if current and previous are valid */
};
#endif
diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp
index 4adf77dce..723caec7c 100644
--- a/src/modules/navigator/mission_block.cpp
+++ b/src/modules/navigator/mission_block.cpp
@@ -113,6 +113,19 @@ MissionBlock::is_mission_item_reached()
if (dist >= 0.0f && dist <= _navigator->get_acceptance_radius()) {
_waypoint_position_reached = true;
}
+ } else if (!_navigator->get_vstatus()->is_rotary_wing &&
+ (_mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT)) {
+ /* Loiter mission item on a non rotary wing: the aircraft is going to circle the
+ * coordinates with a radius equal to the loiter_radius field. It is not flying
+ * through the waypoint center.
+ * Therefore the item is marked as reached once the system reaches the loiter
+ * radius (+ some margin). Time inside and turn count is handled elsewhere.
+ */
+ if (dist >= 0.0f && dist <= _mission_item.loiter_radius * 1.2f) {
+ _waypoint_position_reached = true;
+ }
} else {
/* for normal mission items used their acceptance radius */
if (dist >= 0.0f && dist <= _mission_item.acceptance_radius) {
diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp
index 606521f20..389cdd0d2 100644
--- a/src/modules/navigator/mission_feasibility_checker.cpp
+++ b/src/modules/navigator/mission_feasibility_checker.cpp
@@ -84,7 +84,12 @@ bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_
bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
{
- return (checkGeofence(dm_current, nMissionItems, geofence) && checkHomePositionAltitude(dm_current, nMissionItems, home_alt));
+ /* Perform checks and issue feedback to the user for all checks */
+ bool resGeofence = checkGeofence(dm_current, nMissionItems, geofence);
+ bool resHomeAltitude = checkHomePositionAltitude(dm_current, nMissionItems, home_alt);
+
+ /* Mission is only marked as feasible if all checks return true */
+ return (resGeofence && resHomeAltitude);
}
bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
@@ -93,7 +98,13 @@ bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_curre
updateNavigationCapabilities();
// warnx("_nav_caps.landing_slope_angle_rad %.4f, _nav_caps.landing_horizontal_slope_displacement %.4f", _nav_caps.landing_slope_angle_rad, _nav_caps.landing_horizontal_slope_displacement);
- return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, geofence) && checkHomePositionAltitude(dm_current, nMissionItems, home_alt));
+ /* Perform checks and issue feedback to the user for all checks */
+ bool resLanding = checkFixedWingLanding(dm_current, nMissionItems);
+ bool resGeofence = checkGeofence(dm_current, nMissionItems, geofence);
+ bool resHomeAltitude = checkHomePositionAltitude(dm_current, nMissionItems, home_alt);
+
+ /* Mission is only marked as feasible if all checks return true */
+ return (resLanding && resGeofence && resHomeAltitude);
}
bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
@@ -109,7 +120,7 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
return false;
}
- if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) {
+ if (!geofence.inside_polygon(missionitem.lat, missionitem.lon, missionitem.altitude)) {
mavlink_log_info(_mavlink_fd, "#audio: Geofence violation waypoint %d", i);
return false;
}
@@ -216,9 +227,8 @@ bool MissionFeasibilityChecker::checkFixedWingLanding(dm_item_t dm_current, size
}
}
-
-// float slope_alt = wp_altitude + _H0 * expf(-math::max(0.0f, _flare_length - wp_distance)/_flare_constant) - _H1_virt;
- return false;
+ /* No landing waypoints or no waypoints */
+ return true;
}
void MissionFeasibilityChecker::updateNavigationCapabilities()
diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c
index 881caa24e..04c01fe51 100644
--- a/src/modules/navigator/mission_params.c
+++ b/src/modules/navigator/mission_params.c
@@ -78,7 +78,20 @@ PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 1);
* waypoint is more distant than MIS_DIS_1WP from the current position.
*
* @min 0
- * @max 250
+ * @max 1000
* @group Mission
*/
-PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 175);
+PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 500);
+
+/**
+ * Altitude setpoint mode
+ *
+ * 0: the system will follow a zero order hold altitude setpoint
+ * 1: the system will follow a first order hold altitude setpoint
+ * values follow the definition in enum mission_altitude_mode
+ *
+ * @min 0
+ * @max 1
+ * @group Mission
+ */
+PARAM_DEFINE_INT32(MIS_ALTMODE, 0);
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index b50198996..c44d4c35e 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -46,13 +46,19 @@ SRCS = navigator_main.cpp \
loiter.cpp \
rtl.cpp \
rtl_params.c \
- offboard.cpp \
mission_feasibility_checker.cpp \
geofence.cpp \
- geofence_params.c
+ geofence_params.c \
+ datalinkloss.cpp \
+ datalinkloss_params.c \
+ rcloss.cpp \
+ rcloss_params.c \
+ enginefailure.cpp \
+ gpsfailure.cpp \
+ gpsfailure_params.c
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MODULE_STACKSIZE = 1200
-EXTRACXXFLAGS = -Weffc++
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h
index 8edbb63b3..d550dcc4c 100644
--- a/src/modules/navigator/navigator.h
+++ b/src/modules/navigator/navigator.h
@@ -35,6 +35,7 @@
* Helper class to access missions
* @author Julian Oes <julian@oes.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#ifndef NAVIGATOR_H
@@ -50,20 +51,25 @@
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/mission_result.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
#include "navigator_mode.h"
#include "mission.h"
#include "loiter.h"
#include "rtl.h"
-#include "offboard.h"
+#include "datalinkloss.h"
+#include "enginefailure.h"
+#include "gpsfailure.h"
+#include "rcloss.h"
#include "geofence.h"
/**
* Number of navigation modes that need on_active/on_inactive calls
- * Currently: mission, loiter, and rtl
*/
-#define NAVIGATOR_MODE_ARRAY_SIZE 4
+#define NAVIGATOR_MODE_ARRAY_SIZE 7
class Navigator : public control::SuperBlock
{
@@ -101,6 +107,17 @@ public:
void load_fence_from_file(const char *filename);
/**
+ * Publish the mission result so commander and mavlink know what is going on
+ */
+ void publish_mission_result();
+
+ /**
+ * Publish the attitude sp, only to be used in very special modes when position control is deactivated
+ * Example: mode that is triggered on gps failure
+ */
+ void publish_att_sp();
+
+ /**
* Setters
*/
void set_can_loiter_at_sp(bool can_loiter) { _can_loiter_at_sp = can_loiter; }
@@ -112,11 +129,15 @@ public:
struct vehicle_status_s* get_vstatus() { return &_vstatus; }
struct vehicle_control_mode_s* get_control_mode() { return &_control_mode; }
struct vehicle_global_position_s* get_global_position() { return &_global_pos; }
+ struct vehicle_gps_position_s* get_gps_position() { return &_gps_pos; }
+ struct sensor_combined_s* get_sensor_combined() { return &_sensor_combined; }
struct home_position_s* get_home_position() { return &_home_pos; }
- struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; }
+ struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; }
+ struct mission_result_s* get_mission_result() { return &_mission_result; }
+ struct vehicle_attitude_setpoint_s* get_att_sp() { return &_att_sp; }
+
int get_onboard_mission_sub() { return _onboard_mission_sub; }
int get_offboard_mission_sub() { return _offboard_mission_sub; }
- int get_offboard_control_sp_sub() { return _offboard_control_sp_sub; }
Geofence& get_geofence() { return _geofence; }
bool get_can_loiter_at_sp() { return _can_loiter_at_sp; }
float get_loiter_radius() { return _param_loiter_radius.get(); }
@@ -131,25 +152,35 @@ private:
int _mavlink_fd; /**< the file descriptor to send messages over mavlink */
int _global_pos_sub; /**< global position subscription */
+ int _gps_pos_sub; /**< gps position subscription */
+ int _sensor_combined_sub; /**< sensor combined subscription */
int _home_pos_sub; /**< home position subscription */
int _vstatus_sub; /**< vehicle status subscription */
int _capabilities_sub; /**< notification of vehicle capabilities updates */
- int _offboard_control_sp_sub; /*** offboard control subscription */
int _control_mode_sub; /**< vehicle control mode subscription */
int _onboard_mission_sub; /**< onboard mission subscription */
int _offboard_mission_sub; /**< offboard mission subscription */
int _param_update_sub; /**< param update subscription */
orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */
+ orb_advert_t _mission_result_pub;
+ orb_advert_t _att_sp_pub; /**< publish att sp
+ used only in very special failsafe modes
+ when pos control is deactivated */
vehicle_status_s _vstatus; /**< vehicle status */
vehicle_control_mode_s _control_mode; /**< vehicle control mode */
vehicle_global_position_s _global_pos; /**< global vehicle position */
+ vehicle_gps_position_s _gps_pos; /**< gps position */
+ sensor_combined_s _sensor_combined; /**< sensor values */
home_position_s _home_pos; /**< home position for RTL */
mission_item_s _mission_item; /**< current mission item */
navigation_capabilities_s _nav_caps; /**< navigation capabilities */
position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */
+ mission_result_s _mission_result;
+ vehicle_attitude_setpoint_s _att_sp;
+
bool _mission_item_valid; /**< flags if the current mission item is valid */
perf_counter_t _loop_perf; /**< loop performance counter */
@@ -157,14 +188,18 @@ private:
Geofence _geofence; /**< class that handles the geofence */
bool _geofence_violation_warning_sent; /**< prevents spaming to mavlink */
- bool _fence_valid; /**< flag if fence is valid */
bool _inside_fence; /**< vehicle is inside fence */
NavigatorMode *_navigation_mode; /**< abstract pointer to current navigation mode class */
Mission _mission; /**< class that handles the missions */
Loiter _loiter; /**< class that handles loiter */
RTL _rtl; /**< class that handles RTL */
- Offboard _offboard; /**< class that handles offboard */
+ RCLoss _rcLoss; /**< class that handles RTL according to
+ OBC rules (rc loss mode) */
+ DataLinkLoss _dataLinkLoss; /**< class that handles the OBC datalink loss mode */
+ EngineFailure _engineFailure; /**< class that handles the engine failure mode
+ (FW only!) */
+ GpsFailure _gpsFailure; /**< class that handles the OBC gpsfailure loss mode */
NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE]; /**< array of navigation modes */
@@ -173,12 +208,24 @@ private:
control::BlockParamFloat _param_loiter_radius; /**< loiter radius for fixedwing */
control::BlockParamFloat _param_acceptance_radius; /**< acceptance for takeoff */
+ control::BlockParamInt _param_datalinkloss_obc; /**< if true: obc mode on data link loss enabled */
+ control::BlockParamInt _param_rcloss_obc; /**< if true: obc mode on rc loss enabled */
/**
* Retrieve global position
*/
void global_position_update();
/**
+ * Retrieve gps position
+ */
+ void gps_position_update();
+
+ /**
+ * Retrieve sensor values
+ */
+ void sensor_combined_update();
+
+ /**
* Retrieve home position
*/
void home_position_update();
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index 331a9a728..a867dd0da 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -40,6 +40,7 @@
* @author Jean Cyr <jean.m.cyr@gmail.com>
* @author Julian Oes <julian@oes.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <nuttx/config.h>
@@ -67,7 +68,7 @@
#include <uORB/topics/mission.h>
#include <uORB/topics/fence.h>
#include <uORB/topics/navigation_capabilities.h>
-#include <uORB/topics/offboard_control_setpoint.h>
+#include <drivers/drv_baro.h>
#include <systemlib/err.h>
#include <systemlib/systemlib.h>
@@ -85,6 +86,7 @@
*/
extern "C" __EXPORT int navigator_main(int argc, char *argv[]);
+#define GEOFENCE_CHECK_INTERVAL 200000
namespace navigator
{
@@ -98,43 +100,56 @@ Navigator::Navigator() :
_navigator_task(-1),
_mavlink_fd(-1),
_global_pos_sub(-1),
+ _gps_pos_sub(-1),
_home_pos_sub(-1),
_vstatus_sub(-1),
_capabilities_sub(-1),
- _offboard_control_sp_sub(-1),
_control_mode_sub(-1),
_onboard_mission_sub(-1),
_offboard_mission_sub(-1),
_param_update_sub(-1),
_pos_sp_triplet_pub(-1),
+ _mission_result_pub(-1),
+ _att_sp_pub(-1),
_vstatus{},
_control_mode{},
_global_pos{},
+ _gps_pos{},
+ _sensor_combined{},
_home_pos{},
_mission_item{},
_nav_caps{},
_pos_sp_triplet{},
+ _mission_result{},
+ _att_sp{},
_mission_item_valid(false),
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
_geofence{},
_geofence_violation_warning_sent(false),
- _fence_valid(false),
_inside_fence(true),
_navigation_mode(nullptr),
_mission(this, "MIS"),
_loiter(this, "LOI"),
_rtl(this, "RTL"),
- _offboard(this, "OFF"),
+ _rcLoss(this, "RCL"),
+ _dataLinkLoss(this, "DLL"),
+ _engineFailure(this, "EF"),
+ _gpsFailure(this, "GPSF"),
_can_loiter_at_sp(false),
_pos_sp_triplet_updated(false),
_param_loiter_radius(this, "LOITER_RAD"),
- _param_acceptance_radius(this, "ACC_RAD")
+ _param_acceptance_radius(this, "ACC_RAD"),
+ _param_datalinkloss_obc(this, "DLL_OBC"),
+ _param_rcloss_obc(this, "RCL_OBC")
{
/* Create a list of our possible navigation types */
_navigation_mode_array[0] = &_mission;
_navigation_mode_array[1] = &_loiter;
_navigation_mode_array[2] = &_rtl;
- _navigation_mode_array[3] = &_offboard;
+ _navigation_mode_array[3] = &_dataLinkLoss;
+ _navigation_mode_array[4] = &_engineFailure;
+ _navigation_mode_array[5] = &_gpsFailure;
+ _navigation_mode_array[6] = &_rcLoss;
updateParams();
}
@@ -171,6 +186,18 @@ Navigator::global_position_update()
}
void
+Navigator::gps_position_update()
+{
+ orb_copy(ORB_ID(vehicle_gps_position), _gps_pos_sub, &_gps_pos);
+}
+
+void
+Navigator::sensor_combined_update()
+{
+ orb_copy(ORB_ID(sensor_combined), _sensor_combined_sub, &_sensor_combined);
+}
+
+void
Navigator::home_position_update()
{
orb_copy(ORB_ID(home_position), _home_pos_sub, &_home_pos);
@@ -221,6 +248,7 @@ Navigator::task_main()
warnx("Initializing..");
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ _geofence.setMavlinkFd(_mavlink_fd);
/* Try to load the geofence:
* if /fs/microsd/etc/geofence.txt load from this file
@@ -232,6 +260,7 @@ Navigator::task_main()
_geofence.loadFromFile(GEOFENCE_FILENAME);
} else {
+ mavlink_log_critical(_mavlink_fd, "#audio: No geofence file");
if (_geofence.clearDm() > 0)
warnx("Geofence cleared");
else
@@ -240,6 +269,8 @@ Navigator::task_main()
/* do subscriptions */
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ _gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ _sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
_capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
@@ -247,12 +278,13 @@ Navigator::task_main()
_onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission));
_offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
_param_update_sub = orb_subscribe(ORB_ID(parameter_update));
- _offboard_control_sp_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
/* copy all topics first time */
vehicle_status_update();
vehicle_control_mode_update();
global_position_update();
+ gps_position_update();
+ sensor_combined_update();
home_position_update();
navigation_capabilities_update();
params_update();
@@ -264,7 +296,7 @@ Navigator::task_main()
const hrt_abstime mavlink_open_interval = 500000;
/* wakeup source(s) */
- struct pollfd fds[6];
+ struct pollfd fds[8];
/* Setup of loop */
fds[0].fd = _global_pos_sub;
@@ -279,6 +311,10 @@ Navigator::task_main()
fds[4].events = POLLIN;
fds[5].fd = _param_update_sub;
fds[5].events = POLLIN;
+ fds[6].fd = _sensor_combined_sub;
+ fds[6].events = POLLIN;
+ fds[7].fd = _gps_pos_sub;
+ fds[7].events = POLLIN;
while (!_task_should_exit) {
@@ -303,6 +339,21 @@ Navigator::task_main()
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
}
+ static bool have_geofence_position_data = false;
+
+ /* gps updated */
+ if (fds[7].revents & POLLIN) {
+ gps_position_update();
+ if (_geofence.getSource() == Geofence::GF_SOURCE_GPS) {
+ have_geofence_position_data = true;
+ }
+ }
+
+ /* sensors combined updated */
+ if (fds[6].revents & POLLIN) {
+ sensor_combined_update();
+ }
+
/* parameters updated */
if (fds[5].revents & POLLIN) {
params_update();
@@ -332,9 +383,21 @@ Navigator::task_main()
/* global position updated */
if (fds[0].revents & POLLIN) {
global_position_update();
+ if (_geofence.getSource() == Geofence::GF_SOURCE_GLOBALPOS) {
+ have_geofence_position_data = true;
+ }
+ }
- /* Check geofence violation */
- if (!_geofence.inside(&_global_pos)) {
+ /* Check geofence violation */
+ static hrt_abstime last_geofence_check = 0;
+ if (have_geofence_position_data && hrt_elapsed_time(&last_geofence_check) > GEOFENCE_CHECK_INTERVAL) {
+ bool inside = _geofence.inside(_global_pos, _gps_pos, _sensor_combined.baro_alt_meter);
+ last_geofence_check = hrt_absolute_time();
+ have_geofence_position_data = false;
+ if (!inside) {
+ /* inform other apps via the mission result */
+ _mission_result.geofence_violated = true;
+ publish_mission_result();
/* Issue a warning about the geofence violation once */
if (!_geofence_violation_warning_sent) {
@@ -342,6 +405,9 @@ Navigator::task_main()
_geofence_violation_warning_sent = true;
}
} else {
+ /* inform other apps via the mission result */
+ _mission_result.geofence_violated = false;
+ publish_mission_result();
/* Reset the _geofence_violation_warning_sent field */
_geofence_violation_warning_sent = false;
}
@@ -353,6 +419,9 @@ Navigator::task_main()
case NAVIGATION_STATE_ACRO:
case NAVIGATION_STATE_ALTCTL:
case NAVIGATION_STATE_POSCTL:
+ case NAVIGATION_STATE_LAND:
+ case NAVIGATION_STATE_TERMINATION:
+ case NAVIGATION_STATE_OFFBOARD:
_navigation_mode = nullptr;
_can_loiter_at_sp = false;
break;
@@ -362,16 +431,30 @@ Navigator::task_main()
case NAVIGATION_STATE_AUTO_LOITER:
_navigation_mode = &_loiter;
break;
+ case NAVIGATION_STATE_AUTO_RCRECOVER:
+ if (_param_rcloss_obc.get() != 0) {
+ _navigation_mode = &_rcLoss;
+ } else {
+ _navigation_mode = &_rtl;
+ }
+ break;
case NAVIGATION_STATE_AUTO_RTL:
- _navigation_mode = &_rtl;
+ _navigation_mode = &_rtl;
break;
case NAVIGATION_STATE_AUTO_RTGS:
- _navigation_mode = &_rtl; /* TODO: change this to something else */
+ /* Use complex data link loss mode only when enabled via param
+ * otherwise use rtl */
+ if (_param_datalinkloss_obc.get() != 0) {
+ _navigation_mode = &_dataLinkLoss;
+ } else {
+ _navigation_mode = &_rtl;
+ }
break;
- case NAVIGATION_STATE_LAND:
- case NAVIGATION_STATE_TERMINATION:
- case NAVIGATION_STATE_OFFBOARD:
- _navigation_mode = &_offboard;
+ case NAVIGATION_STATE_AUTO_LANDENGFAIL:
+ _navigation_mode = &_engineFailure;
+ break;
+ case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
+ _navigation_mode = &_gpsFailure;
break;
default:
_navigation_mode = nullptr;
@@ -442,7 +525,7 @@ Navigator::status()
// warnx("Compass heading in degrees %5.5f", (double)(_global_pos.yaw * M_RAD_TO_DEG_F));
// }
- if (_fence_valid) {
+ if (_geofence.valid()) {
warnx("Geofence is valid");
/* TODO: needed? */
// warnx("Vertex longitude latitude");
@@ -450,7 +533,7 @@ Navigator::status()
// warnx("%6u %9.5f %8.5f", i, (double)_fence.vertices[i].lon, (double)_fence.vertices[i].lat);
} else {
- warnx("Geofence not set");
+ warnx("Geofence not set (no /etc/geofence.txt on microsd) or not valid");
}
}
@@ -534,3 +617,34 @@ int navigator_main(int argc, char *argv[])
return 0;
}
+
+void
+Navigator::publish_mission_result()
+{
+ /* lazily publish the mission result only once available */
+ if (_mission_result_pub > 0) {
+ /* publish mission result */
+ orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);
+
+ } else {
+ /* advertise and publish */
+ _mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
+ }
+ /* reset reached bool */
+ _mission_result.reached = false;
+ _mission_result.finished = false;
+}
+
+void
+Navigator::publish_att_sp()
+{
+ /* lazily publish the attitude sp only once available */
+ if (_att_sp_pub > 0) {
+ /* publish att sp*/
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_att_sp);
+
+ } else {
+ /* advertise and publish */
+ _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_att_sp);
+ }
+}
diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp
index f43215665..3807c5ea8 100644
--- a/src/modules/navigator/navigator_mode.cpp
+++ b/src/modules/navigator/navigator_mode.cpp
@@ -43,7 +43,7 @@
#include "navigator.h"
NavigatorMode::NavigatorMode(Navigator *navigator, const char *name) :
- SuperBlock(NULL, name),
+ SuperBlock(navigator, name),
_navigator(navigator),
_first_run(true)
{
@@ -63,6 +63,9 @@ NavigatorMode::run(bool active) {
if (_first_run) {
/* first run */
_first_run = false;
+ /* Reset stay in failsafe flag */
+ _navigator->get_mission_result()->stay_in_failsafe = false;
+ _navigator->publish_mission_result();
on_activation();
} else {
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 084afe340..1f40e634e 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -37,6 +37,7 @@
* Parameters for navigator in general
*
* @author Julian Oes <julian@oes.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <nuttx/config.h>
@@ -64,3 +65,56 @@ PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
* @group Mission
*/
PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 25.0f);
+
+/**
+ * Set OBC mode for data link loss
+ *
+ * If set to 1 the behaviour on data link loss is set to a mode according to the OBC rules
+ *
+ * @min 0
+ * @group Mission
+ */
+PARAM_DEFINE_INT32(NAV_DLL_OBC, 0);
+
+/**
+ * Set OBC mode for rc loss
+ *
+ * If set to 1 the behaviour on data link loss is set to a mode according to the OBC rules
+ *
+ * @min 0
+ * @group Mission
+ */
+PARAM_DEFINE_INT32(NAV_RCL_OBC, 0);
+
+/**
+ * Airfield home Lat
+ *
+ * Latitude of airfield home waypoint
+ *
+ * @unit degrees * 1e7
+ * @min 0.0
+ * @group DLL
+ */
+PARAM_DEFINE_INT32(NAV_AH_LAT, -265847810);
+
+/**
+ * Airfield home Lon
+ *
+ * Longitude of airfield home waypoint
+ *
+ * @unit degrees * 1e7
+ * @min 0.0
+ * @group DLL
+ */
+PARAM_DEFINE_INT32(NAV_AH_LON, 1518423250);
+
+/**
+ * Airfield home alt
+ *
+ * Altitude of airfield home waypoint
+ *
+ * @unit m
+ * @min 0.0
+ * @group DLL
+ */
+PARAM_DEFINE_FLOAT(NAV_AH_ALT, 600.0f);
diff --git a/src/modules/navigator/offboard.cpp b/src/modules/navigator/offboard.cpp
deleted file mode 100644
index dcb5c6000..000000000
--- a/src/modules/navigator/offboard.cpp
+++ /dev/null
@@ -1,129 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2014 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-/**
- * @file offboard.cpp
- *
- * Helper class for offboard commands
- *
- * @author Julian Oes <julian@oes.ch>
- */
-
-#include <string.h>
-#include <stdlib.h>
-#include <stdbool.h>
-#include <math.h>
-#include <fcntl.h>
-
-#include <mavlink/mavlink_log.h>
-#include <systemlib/err.h>
-
-#include <uORB/uORB.h>
-#include <uORB/topics/position_setpoint_triplet.h>
-
-#include "navigator.h"
-#include "offboard.h"
-
-Offboard::Offboard(Navigator *navigator, const char *name) :
- NavigatorMode(navigator, name),
- _offboard_control_sp({0})
-{
- /* load initial params */
- updateParams();
- /* initial reset */
- on_inactive();
-}
-
-Offboard::~Offboard()
-{
-}
-
-void
-Offboard::on_inactive()
-{
-}
-
-void
-Offboard::on_activation()
-{
-}
-
-void
-Offboard::on_active()
-{
- struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
-
- bool updated;
- orb_check(_navigator->get_offboard_control_sp_sub(), &updated);
- if (updated) {
- update_offboard_control_setpoint();
- }
-
- /* copy offboard setpoints to the corresponding topics */
- if (_navigator->get_control_mode()->flag_control_position_enabled
- && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) {
- /* position control */
- pos_sp_triplet->current.x = _offboard_control_sp.p1;
- pos_sp_triplet->current.y = _offboard_control_sp.p2;
- pos_sp_triplet->current.yaw = _offboard_control_sp.p3;
- pos_sp_triplet->current.z = -_offboard_control_sp.p4;
-
- pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
- pos_sp_triplet->current.valid = true;
- pos_sp_triplet->current.position_valid = true;
-
- _navigator->set_position_setpoint_triplet_updated();
-
- } else if (_navigator->get_control_mode()->flag_control_velocity_enabled
- && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY) {
- /* velocity control */
- pos_sp_triplet->current.vx = _offboard_control_sp.p2;
- pos_sp_triplet->current.vy = _offboard_control_sp.p1;
- pos_sp_triplet->current.yawspeed = _offboard_control_sp.p3;
- pos_sp_triplet->current.vz = _offboard_control_sp.p4;
-
- pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
- pos_sp_triplet->current.valid = true;
- pos_sp_triplet->current.velocity_valid = true;
-
- _navigator->set_position_setpoint_triplet_updated();
- }
-
-}
-
-
-void
-Offboard::update_offboard_control_setpoint()
-{
- orb_copy(ORB_ID(offboard_control_setpoint), _navigator->get_offboard_control_sp_sub(), &_offboard_control_sp);
-
-}
diff --git a/src/modules/navigator/rcloss.cpp b/src/modules/navigator/rcloss.cpp
new file mode 100644
index 000000000..5564a1c42
--- /dev/null
+++ b/src/modules/navigator/rcloss.cpp
@@ -0,0 +1,182 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file rcloss.cpp
+ * Helper class for RC Loss Mode according to the OBC rules
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/home_position.h>
+
+#include "navigator.h"
+#include "datalinkloss.h"
+
+#define DELAY_SIGMA 0.01f
+
+RCLoss::RCLoss(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name),
+ _param_loitertime(this, "LT"),
+ _rcl_state(RCL_STATE_NONE)
+{
+ /* load initial params */
+ updateParams();
+ /* initial reset */
+ on_inactive();
+}
+
+RCLoss::~RCLoss()
+{
+}
+
+void
+RCLoss::on_inactive()
+{
+ /* reset RCL state only if setpoint moved */
+ if (!_navigator->get_can_loiter_at_sp()) {
+ _rcl_state = RCL_STATE_NONE;
+ }
+}
+
+void
+RCLoss::on_activation()
+{
+ _rcl_state = RCL_STATE_NONE;
+ updateParams();
+ advance_rcl();
+ set_rcl_item();
+}
+
+void
+RCLoss::on_active()
+{
+ if (is_mission_item_reached()) {
+ updateParams();
+ advance_rcl();
+ set_rcl_item();
+ }
+}
+
+void
+RCLoss::set_rcl_item()
+{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ set_previous_pos_setpoint();
+ _navigator->set_can_loiter_at_sp(false);
+
+ switch (_rcl_state) {
+ case RCL_STATE_LOITER: {
+ _mission_item.lat = _navigator->get_global_position()->lat;
+ _mission_item.lon = _navigator->get_global_position()->lon;
+ _mission_item.altitude = _navigator->get_global_position()->alt;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = _param_loitertime.get() < 0.0f ? 0.0f : _param_loitertime.get();
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ _navigator->set_can_loiter_at_sp(true);
+ break;
+ }
+ case RCL_STATE_TERMINATE: {
+ /* Request flight termination from the commander */
+ _navigator->get_mission_result()->flight_termination = true;
+ _navigator->publish_mission_result();
+ warnx("rc not recovered: request flight termination");
+ pos_sp_triplet->previous.valid = false;
+ pos_sp_triplet->current.valid = false;
+ pos_sp_triplet->next.valid = false;
+ break;
+ }
+ default:
+ break;
+ }
+
+ reset_mission_item_reached();
+
+ /* convert mission item to current position setpoint and make it valid */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ pos_sp_triplet->next.valid = false;
+
+ _navigator->set_position_setpoint_triplet_updated();
+}
+
+void
+RCLoss::advance_rcl()
+{
+ switch (_rcl_state) {
+ case RCL_STATE_NONE:
+ if (_param_loitertime.get() > 0.0f) {
+ warnx("RC loss, OBC mode, loiter");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: rc loss, loitering");
+ _rcl_state = RCL_STATE_LOITER;
+ } else {
+ warnx("RC loss, OBC mode, slip loiter, terminate");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: rc loss, terminating");
+ _rcl_state = RCL_STATE_TERMINATE;
+ _navigator->get_mission_result()->stay_in_failsafe = true;
+ _navigator->publish_mission_result();
+ }
+ break;
+ case RCL_STATE_LOITER:
+ _rcl_state = RCL_STATE_TERMINATE;
+ warnx("time is up, no RC regain, terminating");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RC not regained, terminating");
+ _navigator->get_mission_result()->stay_in_failsafe = true;
+ _navigator->publish_mission_result();
+ break;
+ case RCL_STATE_TERMINATE:
+ warnx("rcl end");
+ _rcl_state = RCL_STATE_END;
+ break;
+ default:
+ break;
+ }
+}
diff --git a/src/modules/navigator/rcloss.h b/src/modules/navigator/rcloss.h
new file mode 100644
index 000000000..bcb74d877
--- /dev/null
+++ b/src/modules/navigator/rcloss.h
@@ -0,0 +1,88 @@
+/***************************************************************************
+ *
+ * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file rcloss.h
+ * Helper class for RC Loss Mode acording to the OBC rules
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#ifndef NAVIGATOR_RCLOSS_H
+#define NAVIGATOR_RCLOSS_H
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <uORB/Subscription.hpp>
+
+#include "navigator_mode.h"
+#include "mission_block.h"
+
+class Navigator;
+
+class RCLoss : public MissionBlock
+{
+public:
+ RCLoss(Navigator *navigator, const char *name);
+
+ ~RCLoss();
+
+ virtual void on_inactive();
+
+ virtual void on_activation();
+
+ virtual void on_active();
+
+private:
+ /* Params */
+ control::BlockParamFloat _param_loitertime;
+
+ enum RCLState {
+ RCL_STATE_NONE = 0,
+ RCL_STATE_LOITER = 1,
+ RCL_STATE_TERMINATE = 2,
+ RCL_STATE_END = 3
+ } _rcl_state;
+
+ /**
+ * Set the RCL item
+ */
+ void set_rcl_item();
+
+ /**
+ * Move to next RCL item
+ */
+ void advance_rcl();
+
+};
+#endif
diff --git a/src/modules/navigator/rcloss_params.c b/src/modules/navigator/rcloss_params.c
new file mode 100644
index 000000000..f1a01c73b
--- /dev/null
+++ b/src/modules/navigator/rcloss_params.c
@@ -0,0 +1,60 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * AS IS AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file rcloss_params.c
+ *
+ * Parameters for RC Loss (OBC)
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * OBC RC Loss mode parameters, accessible via MAVLink
+ */
+
+/**
+ * Loiter Time
+ *
+ * The amount of time in seconds the system should loiter at current position before termination
+ * Set to -1 to make the system skip loitering
+ *
+ * @unit seconds
+ * @min -1.0
+ * @group RCL
+ */
+PARAM_DEFINE_FLOAT(NAV_RCL_LT, 120.0f);
diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp
index 142a73409..b6c4b8fdf 100644
--- a/src/modules/navigator/rtl.cpp
+++ b/src/modules/navigator/rtl.cpp
@@ -58,9 +58,9 @@
RTL::RTL(Navigator *navigator, const char *name) :
MissionBlock(navigator, name),
_rtl_state(RTL_STATE_NONE),
- _param_return_alt(this, "RETURN_ALT"),
- _param_descend_alt(this, "DESCEND_ALT"),
- _param_land_delay(this, "LAND_DELAY")
+ _param_return_alt(this, "RTL_RETURN_ALT", false),
+ _param_descend_alt(this, "RTL_DESCEND_ALT", false),
+ _param_land_delay(this, "RTL_LAND_DELAY", false)
{
/* load initial params */
updateParams();
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 05eae047c..81bbaa658 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -59,6 +59,7 @@
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/vision_position_estimate.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/optical_flow.h>
#include <mavlink/mavlink_log.h>
@@ -80,6 +81,7 @@ static bool thread_running = false; /**< Deamon status flag */
static int position_estimator_inav_task; /**< Handle of deamon task / thread */
static bool verbose_mode = false;
+static const hrt_abstime vision_topic_timeout = 500000; // Vision topic timeout = 0.5s
static const hrt_abstime gps_topic_timeout = 500000; // GPS topic timeout = 0.5s
static const hrt_abstime flow_topic_timeout = 1000000; // optical flow topic timeout = 1s
static const hrt_abstime sonar_timeout = 150000; // sonar timeout = 150ms
@@ -233,6 +235,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float eph_flow = 1.0f;
+ float eph_vision = 0.5f;
+ float epv_vision = 0.5f;
+
float x_est_prev[2], y_est_prev[2], z_est_prev[2];
memset(x_est_prev, 0, sizeof(x_est_prev));
memset(y_est_prev, 0, sizeof(y_est_prev));
@@ -279,6 +284,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
};
float w_gps_xy = 1.0f;
float w_gps_z = 1.0f;
+
+ float corr_vision[3][2] = {
+ { 0.0f, 0.0f }, // N (pos, vel)
+ { 0.0f, 0.0f }, // E (pos, vel)
+ { 0.0f, 0.0f }, // D (pos, vel)
+ };
+
float corr_sonar = 0.0f;
float corr_sonar_filtered = 0.0f;
@@ -294,6 +306,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
bool sonar_valid = false; // sonar is valid
bool flow_valid = false; // flow is valid
bool flow_accurate = false; // flow should be accurate (this flag not updated if flow_valid == false)
+ bool vision_valid = false;
/* declare and safely initialize all structs */
struct actuator_controls_s actuator;
@@ -312,6 +325,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
memset(&local_pos, 0, sizeof(local_pos));
struct optical_flow_s flow;
memset(&flow, 0, sizeof(flow));
+ struct vision_position_estimate vision;
+ memset(&vision, 0, sizeof(vision));
struct vehicle_global_position_s global_pos;
memset(&global_pos, 0, sizeof(global_pos));
@@ -323,6 +338,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
int optical_flow_sub = orb_subscribe(ORB_ID(optical_flow));
int vehicle_gps_position_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ int vision_position_estimate_sub = orb_subscribe(ORB_ID(vision_position_estimate));
int home_position_sub = orb_subscribe(ORB_ID(home_position));
/* advertise */
@@ -616,6 +632,46 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
}
+
+ /* check no vision circuit breaker is set */
+ if (params.no_vision != CBRK_NO_VISION_KEY) {
+ /* vehicle vision position */
+ orb_check(vision_position_estimate_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vision_position_estimate), vision_position_estimate_sub, &vision);
+
+ /* reset position estimate on first vision update */
+ if (!vision_valid) {
+ x_est[0] = vision.x;
+ x_est[1] = vision.vx;
+ y_est[0] = vision.y;
+ y_est[1] = vision.vy;
+ /* only reset the z estimate if the z weight parameter is not zero */
+ if (params.w_z_vision_p > MIN_VALID_W)
+ {
+ z_est[0] = vision.z;
+ z_est[1] = vision.vz;
+ }
+
+ vision_valid = true;
+ warnx("VISION estimate valid");
+ mavlink_log_info(mavlink_fd, "[inav] VISION estimate valid");
+ }
+
+ /* calculate correction for position */
+ corr_vision[0][0] = vision.x - x_est[0];
+ corr_vision[1][0] = vision.y - y_est[0];
+ corr_vision[2][0] = vision.z - z_est[0];
+
+ /* calculate correction for velocity */
+ corr_vision[0][1] = vision.vx - x_est[1];
+ corr_vision[1][1] = vision.vy - y_est[1];
+ corr_vision[2][1] = vision.vz - z_est[1];
+
+ }
+ }
+
/* vehicle GPS position */
orb_check(vehicle_gps_position_sub, &updated);
@@ -732,14 +788,21 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
/* check for timeout on GPS topic */
- if (gps_valid && t > gps.timestamp_position + gps_topic_timeout) {
+ if (gps_valid && (t > (gps.timestamp_position + gps_topic_timeout))) {
gps_valid = false;
warnx("GPS timeout");
mavlink_log_info(mavlink_fd, "[inav] GPS timeout");
}
+ /* check for timeout on vision topic */
+ if (vision_valid && (t > (vision.timestamp_boot + vision_topic_timeout))) {
+ vision_valid = false;
+ warnx("VISION timeout");
+ mavlink_log_info(mavlink_fd, "[inav] VISION timeout");
+ }
+
/* check for sonar measurement timeout */
- if (sonar_valid && t > sonar_time + sonar_timeout) {
+ if (sonar_valid && (t > (sonar_time + sonar_timeout))) {
corr_sonar = 0.0f;
sonar_valid = false;
}
@@ -759,10 +822,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* use GPS if it's valid and reference position initialized */
bool use_gps_xy = ref_inited && gps_valid && params.w_xy_gps_p > MIN_VALID_W;
bool use_gps_z = ref_inited && gps_valid && params.w_z_gps_p > MIN_VALID_W;
+ /* use VISION if it's valid and has a valid weight parameter */
+ bool use_vision_xy = vision_valid && params.w_xy_vision_p > MIN_VALID_W;
+ bool use_vision_z = vision_valid && params.w_z_vision_p > MIN_VALID_W;
/* use flow if it's valid and (accurate or no GPS available) */
bool use_flow = flow_valid && (flow_accurate || !use_gps_xy);
- bool can_estimate_xy = (eph < max_eph_epv) || use_gps_xy || use_flow;
+ bool can_estimate_xy = (eph < max_eph_epv) || use_gps_xy || use_flow || use_vision_xy;
bool dist_bottom_valid = (t < sonar_valid_time + sonar_valid_timeout);
@@ -781,6 +847,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float w_xy_gps_v = params.w_xy_gps_v * w_gps_xy;
float w_z_gps_p = params.w_z_gps_p * w_gps_z;
+ float w_xy_vision_p = params.w_xy_vision_p;
+ float w_xy_vision_v = params.w_xy_vision_v;
+ float w_z_vision_p = params.w_z_vision_p;
+
/* reduce GPS weight if optical flow is good */
if (use_flow && flow_accurate) {
w_xy_gps_p *= params.w_gps_flow;
@@ -821,6 +891,35 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
}
+ /* accelerometer bias correction for VISION (use buffered rotation matrix) */
+ accel_bias_corr[0] = 0.0f;
+ accel_bias_corr[1] = 0.0f;
+ accel_bias_corr[2] = 0.0f;
+
+ if (use_vision_xy) {
+ accel_bias_corr[0] -= corr_vision[0][0] * w_xy_vision_p * w_xy_vision_p;
+ accel_bias_corr[0] -= corr_vision[0][1] * w_xy_vision_v;
+ accel_bias_corr[1] -= corr_vision[1][0] * w_xy_vision_p * w_xy_vision_p;
+ accel_bias_corr[1] -= corr_vision[1][1] * w_xy_vision_v;
+ }
+
+ if (use_vision_z) {
+ accel_bias_corr[2] -= corr_vision[2][0] * w_z_vision_p * w_z_vision_p;
+ }
+
+ /* transform error vector from NED frame to body frame */
+ for (int i = 0; i < 3; i++) {
+ float c = 0.0f;
+
+ for (int j = 0; j < 3; j++) {
+ c += att.R[j][i] * accel_bias_corr[j];
+ }
+
+ if (isfinite(c)) {
+ acc_bias[i] += c * params.w_acc_bias * dt;
+ }
+ }
+
/* accelerometer bias correction for flow and baro (assume that there is no delay) */
accel_bias_corr[0] = 0.0f;
accel_bias_corr[1] = 0.0f;
@@ -863,10 +962,16 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
inertial_filter_correct(corr_gps[2][0], dt, z_est, 0, w_z_gps_p);
}
+ if (use_vision_z) {
+ epv = fminf(epv, epv_vision);
+ inertial_filter_correct(corr_vision[2][0], dt, z_est, 0, w_z_vision_p);
+ }
+
if (!(isfinite(z_est[0]) && isfinite(z_est[1]))) {
write_debug_log("BAD ESTIMATE AFTER Z CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
memcpy(z_est, z_est_prev, sizeof(z_est));
memset(corr_gps, 0, sizeof(corr_gps));
+ memset(corr_vision, 0, sizeof(corr_vision));
corr_baro = 0;
} else {
@@ -904,11 +1009,24 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
}
+ if (use_vision_xy) {
+ eph = fminf(eph, eph_vision);
+
+ inertial_filter_correct(corr_vision[0][0], dt, x_est, 0, w_xy_vision_p);
+ inertial_filter_correct(corr_vision[1][0], dt, y_est, 0, w_xy_vision_p);
+
+ if (w_xy_vision_v > MIN_VALID_W) {
+ inertial_filter_correct(corr_vision[0][1], dt, x_est, 1, w_xy_vision_v);
+ inertial_filter_correct(corr_vision[1][1], dt, y_est, 1, w_xy_vision_v);
+ }
+ }
+
if (!(isfinite(x_est[0]) && isfinite(x_est[1]) && isfinite(y_est[0]) && isfinite(y_est[1]))) {
write_debug_log("BAD ESTIMATE AFTER CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
memcpy(x_est, x_est_prev, sizeof(x_est));
memcpy(y_est, y_est_prev, sizeof(y_est));
memset(corr_gps, 0, sizeof(corr_gps));
+ memset(corr_vision, 0, sizeof(corr_vision));
memset(corr_flow, 0, sizeof(corr_flow));
} else {
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
index 98b31d17b..cc0fb4155 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 Anton Babushkin. All rights reserved.
- * Author: Anton Babushkin <rk3dov@gmail.com>
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +34,8 @@
/*
* @file position_estimator_inav_params.c
*
+ * @author Anton Babushkin <rk3dov@gmail.com>
+ *
* Parameters for position_estimator_inav
*/
@@ -63,6 +64,17 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 0.5f);
PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f);
/**
+ * Z axis weight for vision
+ *
+ * Weight (cutoff frequency) for vision altitude measurements. vision altitude data is very noisy and should be used only as slow correction for baro offset.
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group Position Estimator INAV
+ */
+PARAM_DEFINE_FLOAT(INAV_W_Z_VIS_P, 0.5f);
+
+/**
* Z axis weight for sonar
*
* Weight (cutoff frequency) for sonar measurements.
@@ -96,6 +108,28 @@ PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f);
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f);
/**
+ * XY axis weight for vision position
+ *
+ * Weight (cutoff frequency) for vision position measurements.
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group Position Estimator INAV
+ */
+PARAM_DEFINE_FLOAT(INAV_W_XY_VIS_P, 5.0f);
+
+/**
+ * XY axis weight for vision velocity
+ *
+ * Weight (cutoff frequency) for vision velocity measurements.
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group Position Estimator INAV
+ */
+PARAM_DEFINE_FLOAT(INAV_W_XY_VIS_V, 0.0f);
+
+/**
* XY axis weight for optical flow
*
* Weight (cutoff frequency) for optical flow (velocity) measurements.
@@ -232,13 +266,27 @@ PARAM_DEFINE_FLOAT(INAV_LAND_THR, 0.2f);
*/
PARAM_DEFINE_FLOAT(INAV_DELAY_GPS, 0.2f);
+/**
+ * Disable vision input
+ *
+ * Set to the appropriate key (328754) to disable vision input.
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group Position Estimator INAV
+ */
+PARAM_DEFINE_INT32(CBRK_NO_VISION, 0);
+
int parameters_init(struct position_estimator_inav_param_handles *h)
{
h->w_z_baro = param_find("INAV_W_Z_BARO");
h->w_z_gps_p = param_find("INAV_W_Z_GPS_P");
+ h->w_z_vision_p = param_find("INAV_W_Z_VIS_P");
h->w_z_sonar = param_find("INAV_W_Z_SONAR");
h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P");
h->w_xy_gps_v = param_find("INAV_W_XY_GPS_V");
+ h->w_xy_vision_p = param_find("INAV_W_XY_VIS_P");
+ h->w_xy_vision_v = param_find("INAV_W_XY_VIS_V");
h->w_xy_flow = param_find("INAV_W_XY_FLOW");
h->w_xy_res_v = param_find("INAV_W_XY_RES_V");
h->w_gps_flow = param_find("INAV_W_GPS_FLOW");
@@ -250,6 +298,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h)
h->land_t = param_find("INAV_LAND_T");
h->land_disp = param_find("INAV_LAND_DISP");
h->land_thr = param_find("INAV_LAND_THR");
+ h->no_vision = param_find("CBRK_NO_VISION");
h->delay_gps = param_find("INAV_DELAY_GPS");
return OK;
@@ -259,9 +308,12 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str
{
param_get(h->w_z_baro, &(p->w_z_baro));
param_get(h->w_z_gps_p, &(p->w_z_gps_p));
+ param_get(h->w_z_vision_p, &(p->w_z_vision_p));
param_get(h->w_z_sonar, &(p->w_z_sonar));
param_get(h->w_xy_gps_p, &(p->w_xy_gps_p));
param_get(h->w_xy_gps_v, &(p->w_xy_gps_v));
+ param_get(h->w_xy_vision_p, &(p->w_xy_vision_p));
+ param_get(h->w_xy_vision_v, &(p->w_xy_vision_v));
param_get(h->w_xy_flow, &(p->w_xy_flow));
param_get(h->w_xy_res_v, &(p->w_xy_res_v));
param_get(h->w_gps_flow, &(p->w_gps_flow));
@@ -273,6 +325,7 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str
param_get(h->land_t, &(p->land_t));
param_get(h->land_disp, &(p->land_disp));
param_get(h->land_thr, &(p->land_thr));
+ param_get(h->no_vision, &(p->no_vision));
param_get(h->delay_gps, &(p->delay_gps));
return OK;
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
index 423f0d879..d0a65e42e 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.h
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 Anton Babushkin. All rights reserved.
- * Author: Anton Babushkin <rk3dov@gmail.com>
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,9 +32,11 @@
****************************************************************************/
/*
- * @file position_estimator_inav_params.h
+ * @file position_estimator_inav_params.c
*
- * Parameters for Position Estimator
+ * @author Anton Babushkin <rk3dov@gmail.com>
+ *
+ * Parameters definition for position_estimator_inav
*/
#include <systemlib/param/param.h>
@@ -43,9 +44,12 @@
struct position_estimator_inav_params {
float w_z_baro;
float w_z_gps_p;
+ float w_z_vision_p;
float w_z_sonar;
float w_xy_gps_p;
float w_xy_gps_v;
+ float w_xy_vision_p;
+ float w_xy_vision_v;
float w_xy_flow;
float w_xy_res_v;
float w_gps_flow;
@@ -57,15 +61,19 @@ struct position_estimator_inav_params {
float land_t;
float land_disp;
float land_thr;
+ int32_t no_vision;
float delay_gps;
};
struct position_estimator_inav_param_handles {
param_t w_z_baro;
param_t w_z_gps_p;
+ param_t w_z_vision_p;
param_t w_z_sonar;
param_t w_xy_gps_p;
param_t w_xy_gps_v;
+ param_t w_xy_vision_p;
+ param_t w_xy_vision_v;
param_t w_xy_flow;
param_t w_xy_res_v;
param_t w_gps_flow;
@@ -77,9 +85,12 @@ struct position_estimator_inav_param_handles {
param_t land_t;
param_t land_disp;
param_t land_thr;
+ param_t no_vision;
param_t delay_gps;
};
+#define CBRK_NO_VISION_KEY 328754
+
/**
* Initialize all parameter handles and values
*
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 185cb20dd..ad60ee03e 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -43,6 +43,7 @@
#include <drivers/drv_hrt.h>
#include <systemlib/perf_counter.h>
#include <systemlib/ppm_decode.h>
+#include <rc/st24.h>
#include "px4io.h"
@@ -51,11 +52,62 @@
#define RC_CHANNEL_LOW_THRESH -8000 /* 10% threshold */
static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len);
+static bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated);
static perf_counter_t c_gather_dsm;
static perf_counter_t c_gather_sbus;
static perf_counter_t c_gather_ppm;
+static int _dsm_fd;
+
+static uint16_t rc_value_override = 0;
+
+bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated)
+{
+ perf_begin(c_gather_dsm);
+ uint16_t temp_count = r_raw_rc_count;
+ uint8_t n_bytes = 0;
+ uint8_t *bytes;
+ *dsm_updated = dsm_input(r_raw_rc_values, &temp_count, &n_bytes, &bytes);
+ if (*dsm_updated) {
+ r_raw_rc_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM;
+ r_raw_rc_count = temp_count & 0x7fff;
+ if (temp_count & 0x8000)
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_DSM11;
+ else
+ r_raw_rc_flags &= ~PX4IO_P_RAW_RC_FLAGS_RC_DSM11;
+
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP);
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
+
+ }
+ perf_end(c_gather_dsm);
+
+ /* get data from FD and attempt to parse with DSM and ST24 libs */
+ uint8_t st24_rssi, rx_count;
+ uint16_t st24_channel_count = 0;
+
+ *st24_updated = false;
+
+ for (unsigned i = 0; i < n_bytes; i++) {
+ /* set updated flag if one complete packet was parsed */
+ *st24_updated |= (OK == st24_decode(bytes[i], &st24_rssi, &rx_count,
+ &st24_channel_count, r_raw_rc_values, PX4IO_RC_INPUT_CHANNELS));
+ }
+
+ if (*st24_updated) {
+
+ *rssi = st24_rssi;
+ r_raw_rc_count = st24_channel_count;
+
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_ST24;
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP);
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
+ }
+
+ return (*dsm_updated | *st24_updated);
+}
+
void
controls_init(void)
{
@@ -65,7 +117,7 @@ controls_init(void)
system_state.rc_channels_timestamp_valid = 0;
/* DSM input (USART1) */
- dsm_init("/dev/ttyS0");
+ _dsm_fd = dsm_init("/dev/ttyS0");
/* S.bus input (USART3) */
sbus_init("/dev/ttyS2");
@@ -116,20 +168,8 @@ controls_tick() {
#endif
perf_begin(c_gather_dsm);
- uint16_t temp_count = r_raw_rc_count;
- bool dsm_updated = dsm_input(r_raw_rc_values, &temp_count);
- if (dsm_updated) {
- r_raw_rc_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM;
- r_raw_rc_count = temp_count & 0x7fff;
- if (temp_count & 0x8000)
- r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_DSM11;
- else
- r_raw_rc_flags &= ~PX4IO_P_RAW_RC_FLAGS_RC_DSM11;
-
- r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP);
- r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
-
- }
+ bool dsm_updated, st24_updated;
+ (void)dsm_port_input(&rssi, &dsm_updated, &st24_updated);
perf_end(c_gather_dsm);
perf_begin(c_gather_sbus);
@@ -191,7 +231,7 @@ controls_tick() {
/*
* If we received a new frame from any of the RC sources, process it.
*/
- if (dsm_updated || sbus_updated || ppm_updated) {
+ if (dsm_updated || sbus_updated || ppm_updated || st24_updated) {
/* record a bitmask of channels assigned */
unsigned assigned_channels = 0;
@@ -278,6 +318,9 @@ controls_tick() {
r_rc_values[mapped] = SIGNED_TO_REG(scaled);
assigned_channels |= (1 << mapped);
+ } else if (mapped == PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH) {
+ /* pick out override channel, indicated by special mapping */
+ rc_value_override = SIGNED_TO_REG(scaled);
}
}
}
@@ -371,7 +414,7 @@ controls_tick() {
* requested override.
*
*/
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(r_rc_values[4]) < RC_CHANNEL_LOW_THRESH))
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(rc_value_override) < RC_CHANNEL_LOW_THRESH))
override = true;
if (override) {
@@ -379,7 +422,7 @@ controls_tick() {
r_status_flags |= PX4IO_P_STATUS_FLAGS_OVERRIDE;
/* mix new RC input control values to servos */
- if (dsm_updated || sbus_updated || ppm_updated)
+ if (dsm_updated || sbus_updated || ppm_updated || st24_updated)
mixer_tick();
} else {
diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c
index d3f365822..6e57c9ec7 100644
--- a/src/modules/px4iofirmware/dsm.c
+++ b/src/modules/px4iofirmware/dsm.c
@@ -452,10 +452,12 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
*
* @param[out] values pointer to per channel array of decoded values
* @param[out] num_values pointer to number of raw channel values returned, high order bit 0:10 bit data, 1:11 bit data
+ * @param[out] n_butes number of bytes read
+ * @param[out] bytes pointer to the buffer of read bytes
* @return true=decoded raw channel values updated, false=no update
*/
bool
-dsm_input(uint16_t *values, uint16_t *num_values)
+dsm_input(uint16_t *values, uint16_t *num_values, uint8_t *n_bytes, uint8_t **bytes)
{
ssize_t ret;
hrt_abstime now;
@@ -478,8 +480,12 @@ dsm_input(uint16_t *values, uint16_t *num_values)
ret = read(dsm_fd, &dsm_frame[dsm_partial_frame_count], DSM_FRAME_SIZE - dsm_partial_frame_count);
/* if the read failed for any reason, just give up here */
- if (ret < 1)
+ if (ret < 1) {
return false;
+ } else {
+ *n_bytes = ret;
+ *bytes = &dsm_frame[dsm_partial_frame_count];
+ }
dsm_last_rx_time = now;
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index 606c639f9..c0b8ac358 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -58,14 +58,7 @@ extern "C" {
/*
* Maximum interval in us before FMU signal is considered lost
*/
-#define FMU_INPUT_DROP_LIMIT_US 200000
-
-/* XXX need to move the RC_CHANNEL_FUNCTION out of rc_channels.h and into systemlib */
-#define ROLL 0
-#define PITCH 1
-#define YAW 2
-#define THROTTLE 3
-#define OVERRIDE 4
+#define FMU_INPUT_DROP_LIMIT_US 500000
/* current servo arm/disarm state */
static bool mixer_servos_armed = false;
@@ -98,7 +91,8 @@ mixer_tick(void)
{
/* check that we are receiving fresh data from the FMU */
- if (hrt_elapsed_time(&system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {
+ if ((system_state.fmu_data_received_time == 0) ||
+ hrt_elapsed_time(&system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {
/* too long without FMU input, time to go to failsafe */
if (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) {
@@ -109,6 +103,9 @@ mixer_tick(void)
} else {
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
+
+ /* this flag is never cleared once OK */
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED;
}
/* default to failsafe mixing - it will be forced below if flag is set */
@@ -139,7 +136,9 @@ mixer_tick(void)
(r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) &&
(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) &&
!(r_setup_arming & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) &&
- !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) {
+ !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
+ /* do not enter manual override if we asked for termination failsafe and FMU is lost */
+ !(r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE)) {
/* if allowed, mix from RC inputs directly */
source = MIX_OVERRIDE;
@@ -155,29 +154,11 @@ mixer_tick(void)
}
/*
- * Check if we should force failsafe - and do it if we have to
- */
- if (r_setup_arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) {
- source = MIX_FAILSAFE;
- }
-
- /*
- * Set failsafe status flag depending on mixing source
- */
- if (source == MIX_FAILSAFE) {
- r_status_flags |= PX4IO_P_STATUS_FLAGS_FAILSAFE;
- } else {
- r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FAILSAFE);
- }
-
- /*
* Decide whether the servos should be armed right now.
*
* We must be armed, and we must have a PWM source; either raw from
* FMU or from the mixer.
*
- * XXX correct behaviour for failsafe may require an additional case
- * here.
*/
should_arm = (
/* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)
@@ -195,6 +176,38 @@ mixer_tick(void)
&& (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK);
/*
+ * Check if failsafe termination is set - if yes,
+ * set the force failsafe flag once entering the first
+ * failsafe condition.
+ */
+ if ( /* if we have requested flight termination style failsafe (noreturn) */
+ (r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) &&
+ /* and we ended up in a failsafe condition */
+ (source == MIX_FAILSAFE) &&
+ /* and we should be armed, so we intended to provide outputs */
+ should_arm &&
+ /* and FMU is initialized */
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED)) {
+ r_setup_arming |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
+ }
+
+ /*
+ * Check if we should force failsafe - and do it if we have to
+ */
+ if (r_setup_arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) {
+ source = MIX_FAILSAFE;
+ }
+
+ /*
+ * Set failsafe status flag depending on mixing source
+ */
+ if (source == MIX_FAILSAFE) {
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_FAILSAFE;
+ } else {
+ r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FAILSAFE);
+ }
+
+ /*
* Run the mixers.
*/
if (source == MIX_FAILSAFE) {
diff --git a/src/modules/px4iofirmware/module.mk b/src/modules/px4iofirmware/module.mk
index 01869569f..eb99e8a96 100644
--- a/src/modules/px4iofirmware/module.mk
+++ b/src/modules/px4iofirmware/module.mk
@@ -14,7 +14,8 @@ SRCS = adc.c \
../systemlib/mixer/mixer_group.cpp \
../systemlib/mixer/mixer_multirotor.cpp \
../systemlib/mixer/mixer_simple.cpp \
- ../systemlib/pwm_limit/pwm_limit.c
+ ../systemlib/pwm_limit/pwm_limit.c \
+ ../../lib/rc/st24.c
ifeq ($(BOARD),px4io-v1)
SRCS += i2c.c
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index 050783687..9b2e047cb 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -111,6 +111,8 @@
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */
#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */
#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF (1 << 12) /* safety is off */
+#define PX4IO_P_STATUS_FLAGS_FMU_INITIALIZED (1 << 13) /* FMU was initialized and OK once */
+#define PX4IO_P_STATUS_FLAGS_RC_ST24 (1 << 14) /* ST24 input is valid */
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* [1] VBatt is very close to regulator dropout */
@@ -180,6 +182,7 @@
#define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED (1 << 6) /* Disable the IO-internal evaluation of the RC */
#define PX4IO_P_SETUP_ARMING_LOCKDOWN (1 << 7) /* If set, the system operates normally, but won't actuate any servos */
#define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE (1 << 8) /* If set, the system will always output the failsafe values */
+#define PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE (1 << 9) /* If set, the system will never return from a failsafe, but remain in failsafe once triggered. */
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */
@@ -218,6 +221,7 @@ enum { /* DSM bind states */
hence index 12 can safely be used. */
#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 /**< the throttle failsafe pulse length in microseconds */
+#define PX4IO_P_SETUP_FORCE_SAFETY_ON 14 /* force safety switch into 'disarmed' (PWM disabled state) */
#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
/* autopilot control values, -10000..10000 */
@@ -243,6 +247,7 @@ enum { /* DSM bind states */
#define PX4IO_P_RC_CONFIG_MAX 2 /**< highest input value */
#define PX4IO_P_RC_CONFIG_DEADZONE 3 /**< band around center that is ignored */
#define PX4IO_P_RC_CONFIG_ASSIGNMENT 4 /**< mapped input value */
+#define PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH 100 /**< magic value for mode switch */
#define PX4IO_P_RC_CONFIG_OPTIONS 5 /**< channel options bitmask */
#define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED (1 << 0)
#define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE (1 << 1)
diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c
index cd134ccb4..30f32b38e 100644
--- a/src/modules/px4iofirmware/px4io.c
+++ b/src/modules/px4iofirmware/px4io.c
@@ -124,6 +124,9 @@ heartbeat_blink(void)
{
static bool heartbeat = false;
LED_BLUE(heartbeat = !heartbeat);
+#ifdef GPIO_LED4
+ LED_RING(heartbeat);
+#endif
}
static uint64_t reboot_time;
@@ -191,6 +194,9 @@ user_start(int argc, char *argv[])
LED_AMBER(false);
LED_BLUE(false);
LED_SAFETY(false);
+#ifdef GPIO_LED4
+ LED_RING(false);
+#endif
/* turn on servo power (if supported) */
#ifdef POWER_SERVO
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index b00a96717..8186e4c78 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -140,6 +140,7 @@ extern pwm_limit_t pwm_limit;
#define LED_BLUE(_s) stm32_gpiowrite(GPIO_LED1, !(_s))
#define LED_AMBER(_s) stm32_gpiowrite(GPIO_LED2, !(_s))
#define LED_SAFETY(_s) stm32_gpiowrite(GPIO_LED3, !(_s))
+#define LED_RING(_s) stm32_gpiowrite(GPIO_LED4, !(_s))
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
@@ -215,7 +216,7 @@ extern uint16_t adc_measure(unsigned channel);
extern void controls_init(void);
extern void controls_tick(void);
extern int dsm_init(const char *device);
-extern bool dsm_input(uint16_t *values, uint16_t *num_values);
+extern bool dsm_input(uint16_t *values, uint16_t *num_values, uint8_t *n_bytes, uint8_t **bytes);
extern void dsm_bind(uint16_t cmd, int pulses);
extern int sbus_init(const char *device);
extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels);
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 43161aa70..49c2a9f56 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -190,7 +190,8 @@ volatile uint16_t r_page_setup[] =
PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE | \
PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED | \
PX4IO_P_SETUP_ARMING_LOCKDOWN | \
- PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE)
+ PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE | \
+ PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE)
#define PX4IO_P_SETUP_RATES_VALID ((1 << PX4IO_SERVO_COUNT) - 1)
#define PX4IO_P_SETUP_RELAYS_VALID ((1 << PX4IO_RELAY_CHANNELS) - 1)
@@ -285,7 +286,9 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
/* XXX range-check value? */
- r_page_servos[offset] = *values;
+ if (*values != PWM_IGNORE_THIS_CHANNEL) {
+ r_page_servos[offset] = *values;
+ }
offset++;
num_values--;
@@ -516,6 +519,19 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
r_status_flags |= PX4IO_P_STATUS_FLAGS_INIT_OK;
}
+ /*
+ * If the failsafe termination flag is set, do not allow the autopilot to unset it
+ */
+ value |= (r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE);
+
+ /*
+ * If failsafe termination is enabled and force failsafe bit is set, do not allow
+ * the autopilot to clear it.
+ */
+ if (r_setup_arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) {
+ value |= (r_setup_arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE);
+ }
+
r_setup_arming = value;
break;
@@ -587,6 +603,12 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
dsm_bind(value & 0x0f, (value >> 4) & 0xF);
break;
+ case PX4IO_P_SETUP_FORCE_SAFETY_ON:
+ if (value == PX4IO_FORCE_SAFETY_MAGIC) {
+ r_status_flags &= ~PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
+ }
+ break;
+
case PX4IO_P_SETUP_FORCE_SAFETY_OFF:
if (value == PX4IO_FORCE_SAFETY_MAGIC) {
r_status_flags |= PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
@@ -670,7 +692,8 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] == UINT8_MAX) {
disabled = true;
- } else if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_RC_MAPPED_CONTROL_CHANNELS) {
+ } else if ((conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_RC_MAPPED_CONTROL_CHANNELS) &&
+ (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] != PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH)) {
count++;
}
diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c
index 0f0414148..d76ec55f0 100644
--- a/src/modules/px4iofirmware/sbus.c
+++ b/src/modules/px4iofirmware/sbus.c
@@ -57,11 +57,12 @@
#define SBUS_FLAGS_BYTE 23
#define SBUS_FAILSAFE_BIT 3
#define SBUS_FRAMELOST_BIT 2
+#define SBUS1_FRAME_DELAY 14000
/*
Measured values with Futaba FX-30/R6108SB:
-+100% on TX: PCM 1.100/1.520/1.950ms -> SBus raw values: 350/1024/1700 (100% ATV)
- -+140% on TX: PCM 0.930/1.520/2.112ms -> SBus raw values: 78/1024/1964 (140% ATV)
+ -+140% on TX: PCM 0.930/1.520/2.112ms -> SBus raw values: 78/1024/1964 (140% ATV)
-+152% on TX: PCM 0.884/1.520/2.160ms -> SBus raw values: 1/1024/2047 (140% ATV plus dirty tricks)
*/
@@ -80,6 +81,7 @@ static int sbus_fd = -1;
static hrt_abstime last_rx_time;
static hrt_abstime last_frame_time;
+static hrt_abstime last_txframe_time = 0;
static uint8_t frame[SBUS_FRAME_SIZE];
@@ -87,13 +89,15 @@ static unsigned partial_frame_count;
unsigned sbus_frame_drops;
-static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels);
+static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe,
+ bool *sbus_frame_drop, uint16_t max_channels);
int
sbus_init(const char *device)
{
- if (sbus_fd < 0)
+ if (sbus_fd < 0) {
sbus_fd = open(device, O_RDWR | O_NONBLOCK);
+ }
if (sbus_fd >= 0) {
struct termios t;
@@ -113,16 +117,49 @@ sbus_init(const char *device)
} else {
debug("S.Bus: open failed");
}
+
return sbus_fd;
}
void
sbus1_output(uint16_t *values, uint16_t num_values)
{
- char a = 'A';
- write(sbus_fd, &a, 1);
-}
+ uint8_t byteindex = 1; /*Data starts one byte into the sbus frame. */
+ uint8_t offset = 0;
+ uint16_t value;
+ hrt_abstime now;
+
+ now = hrt_absolute_time();
+
+ if ((now - last_txframe_time) > SBUS1_FRAME_DELAY) {
+ last_txframe_time = now;
+ uint8_t oframe[SBUS_FRAME_SIZE] = { 0x0f };
+
+ /* 16 is sbus number of servos/channels minus 2 single bit channels.
+ * currently ignoring single bit channels. */
+ for (unsigned i = 0; (i < num_values) && (i < 16); ++i) {
+ value = (uint16_t)(((values[i] - SBUS_SCALE_OFFSET) / SBUS_SCALE_FACTOR) + .5f);
+
+ /*protect from out of bounds values and limit to 11 bits*/
+ if (value > 0x07ff ) {
+ value = 0x07ff;
+ }
+
+ while (offset >= 8) {
+ ++byteindex;
+ offset -= 8;
+ }
+
+ oframe[byteindex] |= (value << (offset)) & 0xff;
+ oframe[byteindex + 1] |= (value >> (8 - offset)) & 0xff;
+ oframe[byteindex + 2] |= (value >> (16 - offset)) & 0xff;
+ offset += 11;
+ }
+
+ write(sbus_fd, oframe, SBUS_FRAME_SIZE);
+ }
+}
void
sbus2_output(uint16_t *values, uint16_t num_values)
{
@@ -167,8 +204,9 @@ sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sb
ret = read(sbus_fd, &frame[partial_frame_count], SBUS_FRAME_SIZE - partial_frame_count);
/* if the read failed for any reason, just give up here */
- if (ret < 1)
+ if (ret < 1) {
return false;
+ }
last_rx_time = now;
@@ -180,8 +218,9 @@ sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sb
/*
* If we don't have a full frame, return
*/
- if (partial_frame_count < SBUS_FRAME_SIZE)
+ if (partial_frame_count < SBUS_FRAME_SIZE) {
return false;
+ }
/*
* Great, it looks like we might have a frame. Go ahead and
@@ -228,7 +267,8 @@ static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = {
};
static bool
-sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
+sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop,
+ uint16_t max_values)
{
/* check frame boundary markers to avoid out-of-sync cases */
if ((frame[0] != 0x0f)) {
@@ -237,23 +277,27 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool
}
switch (frame[24]) {
- case 0x00:
+ case 0x00:
/* this is S.BUS 1 */
break;
- case 0x03:
+
+ case 0x03:
/* S.BUS 2 SLOT0: RX battery and external voltage */
break;
- case 0x83:
+
+ case 0x83:
/* S.BUS 2 SLOT1 */
break;
- case 0x43:
- case 0xC3:
- case 0x23:
- case 0xA3:
- case 0x63:
- case 0xE3:
+
+ case 0x43:
+ case 0xC3:
+ case 0x23:
+ case 0xA3:
+ case 0x63:
+ case 0xE3:
break;
- default:
+
+ default:
/* we expect one of the bits above, but there are some we don't know yet */
break;
}
@@ -283,7 +327,7 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool
/* convert 0-2048 values to 1000-2000 ppm encoding in a not too sloppy fashion */
- values[channel] = (uint16_t)(value * SBUS_SCALE_FACTOR +.5f) + SBUS_SCALE_OFFSET;
+ values[channel] = (uint16_t)(value * SBUS_SCALE_FACTOR + .5f) + SBUS_SCALE_OFFSET;
}
/* decode switch channels if data fields are wide enough */
@@ -304,16 +348,17 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool
/* report that we failed to read anything valid off the receiver */
*sbus_failsafe = true;
*sbus_frame_drop = true;
- }
- else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
+
+ } else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
/* set a special warning flag
- *
- * Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
- * condition as fail-safe greatly reduces the reliability and range of the radio link,
+ *
+ * Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
+ * condition as fail-safe greatly reduces the reliability and range of the radio link,
* e.g. by prematurely issueing return-to-launch!!! */
*sbus_failsafe = false;
*sbus_frame_drop = true;
+
} else {
*sbus_failsafe = false;
*sbus_frame_drop = false;
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 31861c3fc..af580f1f7 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -76,6 +76,7 @@
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/satellite_info.h>
#include <uORB/topics/vehicle_vicon_position.h>
+#include <uORB/topics/vision_position_estimate.h>
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/battery_status.h>
@@ -89,6 +90,7 @@
#include <uORB/topics/system_power.h>
#include <uORB/topics/servorail_status.h>
#include <uORB/topics/wind_estimate.h>
+#include <uORB/topics/encoders.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
@@ -627,6 +629,9 @@ void sdlog2_start_log()
perf_print_all(perf_fd);
close(perf_fd);
+ /* reset performance counters to get in-flight min and max values in post flight log */
+ perf_reset_all();
+
logging_enabled = true;
}
@@ -934,6 +939,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct vehicle_global_position_s global_pos;
struct position_setpoint_triplet_s triplet;
struct vehicle_vicon_position_s vicon_pos;
+ struct vision_position_estimate vision_pos;
struct optical_flow_s flow;
struct rc_channels_s rc;
struct differential_pressure_s diff_pres;
@@ -949,6 +955,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct servorail_status_s servorail_status;
struct satellite_info_s sat_info;
struct wind_estimate_s wind_estimate;
+ struct encoders_s encoders;
} buf;
memset(&buf, 0, sizeof(buf));
@@ -984,12 +991,14 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_EST1_s log_EST1;
struct log_PWR_s log_PWR;
struct log_VICN_s log_VICN;
+ struct log_VISN_s log_VISN;
struct log_GS0A_s log_GS0A;
struct log_GS0B_s log_GS0B;
struct log_GS1A_s log_GS1A;
struct log_GS1B_s log_GS1B;
struct log_TECS_s log_TECS;
struct log_WIND_s log_WIND;
+ struct log_ENCD_s log_ENCD;
} body;
} log_msg = {
LOG_PACKET_HEADER_INIT(0)
@@ -1013,6 +1022,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int gps_pos_sub;
int sat_info_sub;
int vicon_pos_sub;
+ int vision_pos_sub;
int flow_sub;
int rc_sub;
int airspeed_sub;
@@ -1026,12 +1036,12 @@ int sdlog2_thread_main(int argc, char *argv[])
int system_power_sub;
int servorail_status_sub;
int wind_sub;
+ int encoders_sub;
} subs;
subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
subs.status_sub = orb_subscribe(ORB_ID(vehicle_status));
subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
- subs.sat_info_sub = orb_subscribe(ORB_ID(satellite_info));
subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
@@ -1043,15 +1053,13 @@ int sdlog2_thread_main(int argc, char *argv[])
subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
subs.triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet));
subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
+ subs.vision_pos_sub = orb_subscribe(ORB_ID(vision_position_estimate));
subs.flow_sub = orb_subscribe(ORB_ID(optical_flow));
subs.rc_sub = orb_subscribe(ORB_ID(rc_channels));
subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed));
subs.esc_sub = orb_subscribe(ORB_ID(esc_status));
subs.global_vel_sp_sub = orb_subscribe(ORB_ID(vehicle_global_velocity_setpoint));
subs.battery_sub = orb_subscribe(ORB_ID(battery_status));
- for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
- subs.telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]);
- }
subs.range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
subs.estimator_status_sub = orb_subscribe(ORB_ID(estimator_status));
subs.tecs_status_sub = orb_subscribe(ORB_ID(tecs_status));
@@ -1060,6 +1068,25 @@ int sdlog2_thread_main(int argc, char *argv[])
subs.wind_sub = orb_subscribe(ORB_ID(wind_estimate));
/* we need to rate-limit wind, as we do not need the full update rate */
orb_set_interval(subs.wind_sub, 90);
+ subs.encoders_sub = orb_subscribe(ORB_ID(encoders));
+
+ /* add new topics HERE */
+
+
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ subs.telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]);
+ }
+
+ if (_extended_logging) {
+ subs.sat_info_sub = orb_subscribe(ORB_ID(satellite_info));
+ }
+
+ /* close non-needed fd's */
+
+ /* close stdin */
+ close(0);
+ /* close stdout */
+ close(1);
thread_running = true;
@@ -1427,6 +1454,11 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_GPOS.vel_d = buf.global_pos.vel_d;
log_msg.body.log_GPOS.eph = buf.global_pos.eph;
log_msg.body.log_GPOS.epv = buf.global_pos.epv;
+ if (buf.global_pos.terrain_alt_valid) {
+ log_msg.body.log_GPOS.terrain_alt = buf.global_pos.terrain_alt;
+ } else {
+ log_msg.body.log_GPOS.terrain_alt = -1.0f;
+ }
LOGBUFFER_WRITE_AND_COUNT(GPOS);
}
@@ -1460,6 +1492,22 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(VICN);
}
+ /* --- VISION POSITION --- */
+ if (copy_if_updated(ORB_ID(vision_position_estimate), subs.vision_pos_sub, &buf.vision_pos)) {
+ log_msg.msg_type = LOG_VISN_MSG;
+ log_msg.body.log_VISN.x = buf.vision_pos.x;
+ log_msg.body.log_VISN.y = buf.vision_pos.y;
+ log_msg.body.log_VISN.z = buf.vision_pos.z;
+ log_msg.body.log_VISN.vx = buf.vision_pos.vx;
+ log_msg.body.log_VISN.vy = buf.vision_pos.vy;
+ log_msg.body.log_VISN.vz = buf.vision_pos.vz;
+ log_msg.body.log_VISN.qx = buf.vision_pos.q[0];
+ log_msg.body.log_VISN.qy = buf.vision_pos.q[1];
+ log_msg.body.log_VISN.qz = buf.vision_pos.q[2];
+ log_msg.body.log_VISN.qw = buf.vision_pos.q[3];
+ LOGBUFFER_WRITE_AND_COUNT(VISN);
+ }
+
/* --- FLOW --- */
if (copy_if_updated(ORB_ID(optical_flow), subs.flow_sub, &buf.flow)) {
log_msg.msg_type = LOG_FLOW_MSG;
@@ -1597,14 +1645,12 @@ int sdlog2_thread_main(int argc, char *argv[])
if (copy_if_updated(ORB_ID(tecs_status), subs.tecs_status_sub, &buf.tecs_status)) {
log_msg.msg_type = LOG_TECS_MSG;
log_msg.body.log_TECS.altitudeSp = buf.tecs_status.altitudeSp;
- log_msg.body.log_TECS.altitude = buf.tecs_status.altitude;
- log_msg.body.log_TECS.altitudeFiltered = buf.tecs_status.altitudeFiltered;
+ log_msg.body.log_TECS.altitudeFiltered = buf.tecs_status.altitude_filtered;
log_msg.body.log_TECS.flightPathAngleSp = buf.tecs_status.flightPathAngleSp;
log_msg.body.log_TECS.flightPathAngle = buf.tecs_status.flightPathAngle;
log_msg.body.log_TECS.flightPathAngleFiltered = buf.tecs_status.flightPathAngleFiltered;
log_msg.body.log_TECS.airspeedSp = buf.tecs_status.airspeedSp;
- log_msg.body.log_TECS.airspeed = buf.tecs_status.airspeed;
- log_msg.body.log_TECS.airspeedFiltered = buf.tecs_status.airspeedFiltered;
+ log_msg.body.log_TECS.airspeedFiltered = buf.tecs_status.airspeed_filtered;
log_msg.body.log_TECS.airspeedDerivativeSp = buf.tecs_status.airspeedDerivativeSp;
log_msg.body.log_TECS.airspeedDerivative = buf.tecs_status.airspeedDerivative;
log_msg.body.log_TECS.totalEnergyRateSp = buf.tecs_status.totalEnergyRateSp;
@@ -1625,6 +1671,16 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(WIND);
}
+ /* --- ENCODERS --- */
+ if (copy_if_updated(ORB_ID(encoders), subs.encoders_sub, &buf.encoders)) {
+ log_msg.msg_type = LOG_ENCD_MSG;
+ log_msg.body.log_ENCD.cnt0 = buf.encoders.counts[0];
+ log_msg.body.log_ENCD.vel0 = buf.encoders.velocity[0];
+ log_msg.body.log_ENCD.cnt1 = buf.encoders.counts[1];
+ log_msg.body.log_ENCD.vel1 = buf.encoders.velocity[1];
+ LOGBUFFER_WRITE_AND_COUNT(ENCD);
+ }
+
/* signal the other thread new data, but not yet unlock */
if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) {
/* only request write if several packets can be written at once */
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 853a3811f..fa9bdacb8 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -220,6 +220,7 @@ struct log_GPOS_s {
float vel_d;
float eph;
float epv;
+ float terrain_alt;
};
/* --- GPSP - GLOBAL POSITION SETPOINT --- */
@@ -240,15 +241,15 @@ struct log_GPSP_s {
#define LOG_ESC_MSG 18
struct log_ESC_s {
uint16_t counter;
- uint8_t esc_count;
- uint8_t esc_connectiontype;
- uint8_t esc_num;
+ uint8_t esc_count;
+ uint8_t esc_connectiontype;
+ uint8_t esc_num;
uint16_t esc_address;
uint16_t esc_version;
- uint16_t esc_voltage;
- uint16_t esc_current;
- uint16_t esc_rpm;
- uint16_t esc_temperature;
+ float esc_voltage;
+ float esc_current;
+ int32_t esc_rpm;
+ float esc_temperature;
float esc_setpoint;
uint16_t esc_setpoint_raw;
};
@@ -333,13 +334,11 @@ struct log_GS1B_s {
#define LOG_TECS_MSG 30
struct log_TECS_s {
float altitudeSp;
- float altitude;
float altitudeFiltered;
float flightPathAngleSp;
float flightPathAngle;
float flightPathAngleFiltered;
float airspeedSp;
- float airspeed;
float airspeedFiltered;
float airspeedDerivativeSp;
float airspeedDerivative;
@@ -393,6 +392,30 @@ struct log_TEL_s {
uint64_t heartbeat_time;
};
+/* --- VISN - VISION POSITION --- */
+#define LOG_VISN_MSG 38
+struct log_VISN_s {
+ float x;
+ float y;
+ float z;
+ float vx;
+ float vy;
+ float vz;
+ float qx;
+ float qy;
+ float qz;
+ float qw;
+};
+
+/* --- ENCODERS - ENCODER DATA --- */
+#define LOG_ENCD_MSG 39
+struct log_ENCD_s {
+ int64_t cnt0;
+ float vel0;
+ int64_t cnt1;
+ float vel1;
+};
+
/********** SYSTEM MESSAGES, ID > 0x80 **********/
@@ -437,9 +460,9 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(AIRS, "fff", "IndSpeed,TrueSpeed,AirTemp"),
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
- LOG_FORMAT(GPOS, "LLffffff", "Lat,Lon,Alt,VelN,VelE,VelD,EPH,EPV"),
+ LOG_FORMAT(GPOS, "LLfffffff", "Lat,Lon,Alt,VelN,VelE,VelD,EPH,EPV,TALT"),
LOG_FORMAT(GPSP, "BLLffBfbf", "NavState,Lat,Lon,Alt,Yaw,Type,LoitR,LoitDir,PitMin"),
- LOG_FORMAT(ESC, "HBBBHHHHHHfH", "count,nESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
+ LOG_FORMAT(ESC, "HBBBHHffiffH", "count,nESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"),
LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"),
LOG_FORMAT(DIST, "ffB", "Bottom,BottomRate,Flags"),
@@ -451,12 +474,14 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(EST1, "ffffffffffffffff", "s12,s13,s14,s15,s16,s17,s18,s19,s20,s21,s22,s23,s24,s25,s26,s27"),
LOG_FORMAT(PWR, "fffBBBBB", "Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC"),
LOG_FORMAT(VICN, "ffffff", "X,Y,Z,Roll,Pitch,Yaw"),
+ LOG_FORMAT(VISN, "ffffffffff", "X,Y,Z,VX,VY,VZ,QuatX,QuatY,QuatZ,QuatW"),
LOG_FORMAT(GS0A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
LOG_FORMAT(GS0B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
LOG_FORMAT(GS1A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
LOG_FORMAT(GS1B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
- LOG_FORMAT(TECS, "fffffffffffffffB", "ASP,A,AF,FSP,F,FF,AsSP,As,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"),
+ LOG_FORMAT(TECS, "fffffffffffffB", "ASP,AF,FSP,F,FF,AsSP,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"),
LOG_FORMAT(WIND, "ffff", "X,Y,CovX,CovY"),
+ LOG_FORMAT(ENCD, "qfqf", "cnt0,vel0,cnt1,vel1"),
/* system-level messages, ID >= 0x80 */
/* FMT: don't write format of format message, it's useless */
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 7ce6ef5ef..229bfe3ce 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -214,6 +214,16 @@ PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f);
*/
PARAM_DEFINE_FLOAT(SENS_DPRES_ANSC, 0);
+/**
+ * QNH for barometer
+ *
+ * @min 500
+ * @max 1500
+ * @group Sensor Calibration
+ * @unit hPa
+ */
+PARAM_DEFINE_FLOAT(SENS_BARO_QNH, 1013.25f);
+
/**
* Board rotation
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 4e8a8c01d..cdcb428dd 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -143,6 +143,12 @@
#define STICK_ON_OFF_LIMIT 0.75f
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
/**
* Sensor app start / stop handling function
*
@@ -235,7 +241,7 @@ private:
math::Matrix<3, 3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
math::Matrix<3, 3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
bool _mag_is_external; /**< true if the active mag is on an external board */
-
+
uint64_t _battery_discharged; /**< battery discharged current in mA*ms */
hrt_abstime _battery_current_timestamp; /**< timestamp of last battery current reading */
@@ -258,7 +264,7 @@ private:
int board_rotation;
int external_mag_rotation;
-
+
float board_offset[3];
int rc_map_roll;
@@ -301,6 +307,8 @@ private:
float battery_voltage_scaling;
float battery_current_scaling;
+ float baro_qnh;
+
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -354,9 +362,11 @@ private:
param_t board_rotation;
param_t external_mag_rotation;
-
+
param_t board_offset[3];
+ param_t baro_qnh;
+
} _parameter_handles; /**< handles for interesting parameters */
@@ -462,12 +472,6 @@ private:
namespace sensors
{
-/* oddly, ERROR is not defined for c++ */
-#ifdef ERROR
-# undef ERROR
-#endif
-static const int ERROR = -1;
-
Sensors *g_sensors = nullptr;
}
@@ -611,12 +615,15 @@ Sensors::Sensors() :
/* rotations */
_parameter_handles.board_rotation = param_find("SENS_BOARD_ROT");
_parameter_handles.external_mag_rotation = param_find("SENS_EXT_MAG_ROT");
-
+
/* rotation offsets */
_parameter_handles.board_offset[0] = param_find("SENS_BOARD_X_OFF");
_parameter_handles.board_offset[1] = param_find("SENS_BOARD_Y_OFF");
_parameter_handles.board_offset[2] = param_find("SENS_BOARD_Z_OFF");
+ /* Barometer QNH */
+ _parameter_handles.baro_qnh = param_find("SENS_BARO_QNH");
+
/* fetch initial parameter values */
parameters_update();
}
@@ -828,19 +835,37 @@ Sensors::parameters_update()
get_rot_matrix((enum Rotation)_parameters.board_rotation, &_board_rotation);
get_rot_matrix((enum Rotation)_parameters.external_mag_rotation, &_external_mag_rotation);
-
+
param_get(_parameter_handles.board_offset[0], &(_parameters.board_offset[0]));
param_get(_parameter_handles.board_offset[1], &(_parameters.board_offset[1]));
param_get(_parameter_handles.board_offset[2], &(_parameters.board_offset[2]));
-
+
/** fine tune board offset on parameter update **/
- math::Matrix<3, 3> board_rotation_offset;
+ math::Matrix<3, 3> board_rotation_offset;
board_rotation_offset.from_euler( M_DEG_TO_RAD_F * _parameters.board_offset[0],
M_DEG_TO_RAD_F * _parameters.board_offset[1],
M_DEG_TO_RAD_F * _parameters.board_offset[2]);
-
+
_board_rotation = _board_rotation * board_rotation_offset;
+ /* update barometer qnh setting */
+ param_get(_parameter_handles.baro_qnh, &(_parameters.baro_qnh));
+ int fd;
+ fd = open(BARO_DEVICE_PATH, 0);
+ if (fd < 0) {
+ warn("%s", BARO_DEVICE_PATH);
+ errx(1, "FATAL: no barometer found");
+
+ } else {
+ int ret = ioctl(fd, BAROIOCSMSLPRESSURE, (unsigned long)(_parameters.baro_qnh * 100));
+ if (ret) {
+ warnx("qnh could not be set");
+ close(fd);
+ return ERROR;
+ }
+ close(fd);
+ }
+
return OK;
}
@@ -1204,16 +1229,18 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw)
if (updated) {
orb_copy(ORB_ID(differential_pressure), _diff_pres_sub, &_diff_pres);
- raw.differential_pressure_pa = _diff_pres.differential_pressure_pa;
+ raw.differential_pressure_pa = _diff_pres.differential_pressure_raw_pa;
raw.differential_pressure_timestamp = _diff_pres.timestamp;
raw.differential_pressure_filtered_pa = _diff_pres.differential_pressure_filtered_pa;
float air_temperature_celsius = (_diff_pres.temperature > -300.0f) ? _diff_pres.temperature : (raw.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG);
_airspeed.timestamp = _diff_pres.timestamp;
- _airspeed.indicated_airspeed_m_s = calc_indicated_airspeed(_diff_pres.differential_pressure_filtered_pa);
- _airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_filtered_pa + raw.baro_pres_mbar * 1e2f,
- raw.baro_pres_mbar * 1e2f, air_temperature_celsius);
+
+ /* don't risk to feed negative airspeed into the system */
+ _airspeed.indicated_airspeed_m_s = math::max(0.0f, calc_indicated_airspeed(_diff_pres.differential_pressure_filtered_pa));
+ _airspeed.true_airspeed_m_s = math::max(0.0f, calc_true_airspeed(_diff_pres.differential_pressure_filtered_pa + raw.baro_pres_mbar * 1e2f,
+ raw.baro_pres_mbar * 1e2f, air_temperature_celsius));
_airspeed.air_temperature_celsius = air_temperature_celsius;
/* announce the airspeed if needed, just publish else */
@@ -1432,12 +1459,10 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
if (voltage > 0.4f && (_parameters.diff_pres_analog_scale > 0.0f)) {
float diff_pres_pa_raw = voltage * _parameters.diff_pres_analog_scale - _parameters.diff_pres_offset_pa;
- float diff_pres_pa = (diff_pres_pa_raw > 0.0f) ? diff_pres_pa_raw : 0.0f;
_diff_pres.timestamp = t;
- _diff_pres.differential_pressure_pa = diff_pres_pa;
_diff_pres.differential_pressure_raw_pa = diff_pres_pa_raw;
- _diff_pres.differential_pressure_filtered_pa = (_diff_pres.differential_pressure_filtered_pa * 0.9f) + (diff_pres_pa * 0.1f);
+ _diff_pres.differential_pressure_filtered_pa = (_diff_pres.differential_pressure_filtered_pa * 0.9f) + (diff_pres_pa_raw * 0.1f);
_diff_pres.temperature = -1000.0f;
/* announce the airspeed if needed, just publish else */
diff --git a/src/modules/systemlib/circuit_breaker.c b/src/modules/systemlib/circuit_breaker.c
index 64317a18a..12187d70e 100644
--- a/src/modules/systemlib/circuit_breaker.c
+++ b/src/modules/systemlib/circuit_breaker.c
@@ -95,6 +95,47 @@ PARAM_DEFINE_INT32(CBRK_IO_SAFETY, 0);
*/
PARAM_DEFINE_INT32(CBRK_AIRSPD_CHK, 0);
+/**
+ * Circuit breaker for flight termination
+ *
+ * Setting this parameter to 121212 will disable the flight termination action.
+ * --> The IO driver will not do flight termination if requested by the FMU
+ * WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ *
+ * @min 0
+ * @max 121212
+ * @group Circuit Breaker
+ */
+PARAM_DEFINE_INT32(CBRK_FLIGHTTERM, 121212);
+
+/**
+ * Circuit breaker for engine failure detection
+ *
+ * Setting this parameter to 284953 will disable the engine failure detection.
+ * If the aircraft is in engine failure mode the enine failure flag will be
+ * set to healthy
+ * WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ *
+ * @min 0
+ * @max 284953
+ * @group Circuit Breaker
+ */
+PARAM_DEFINE_INT32(CBRK_ENGINEFAIL, 284953);
+
+/**
+ * Circuit breaker for gps failure detection
+ *
+ * Setting this parameter to 240024 will disable the gps failure detection.
+ * If the aircraft is in gps failure mode the gps failure flag will be
+ * set to healthy
+ * WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ *
+ * @min 0
+ * @max 240024
+ * @group Circuit Breaker
+ */
+PARAM_DEFINE_INT32(CBRK_GPSFAIL, 240024);
+
bool circuit_breaker_enabled(const char* breaker, int32_t magic)
{
int32_t val;
diff --git a/src/modules/systemlib/circuit_breaker.h b/src/modules/systemlib/circuit_breaker.h
index b60584608..b3431722f 100644
--- a/src/modules/systemlib/circuit_breaker.h
+++ b/src/modules/systemlib/circuit_breaker.h
@@ -53,6 +53,9 @@
#define CBRK_RATE_CTRL_KEY 140253
#define CBRK_IO_SAFETY_KEY 22027
#define CBRK_AIRSPD_CHK_KEY 162128
+#define CBRK_FLIGHTTERM_KEY 121212
+#define CBRK_ENGINEFAIL_KEY 284953
+#define CBRK_GPSFAIL_KEY 240024
#include <stdbool.h>
diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h
index cdf60febc..17989558e 100644
--- a/src/modules/systemlib/mixer/mixer.h
+++ b/src/modules/systemlib/mixer/mixer.h
@@ -130,6 +130,9 @@
#include <nuttx/config.h>
#include "drivers/drv_mixer.h"
+
+#include <uORB/topics/multirotor_motor_limits.h>
+
#include "mixer_load.h"
/**
@@ -531,6 +534,9 @@ private:
float _yaw_scale;
float _idle_speed;
+ orb_advert_t _limits_pub;
+ multirotor_motor_limits_s _limits;
+
unsigned _rotor_count;
const Rotor *_rotors;
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index 4b22a46d0..57e17b67d 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -36,7 +36,8 @@
*
* Multi-rotor mixers.
*/
-
+#include <uORB/uORB.h>
+#include <uORB/topics/multirotor_motor_limits.h>
#include <nuttx/config.h>
#include <sys/types.h>
@@ -302,6 +303,11 @@ MultirotorMixer::mix(float *outputs, unsigned space)
float min_out = 0.0f;
float max_out = 0.0f;
+ _limits.roll_pitch = false;
+ _limits.yaw = false;
+ _limits.throttle_upper = false;
+ _limits.throttle_lower = false;
+
/* perform initial mix pass yielding unbounded outputs, ignore yaw */
for (unsigned i = 0; i < _rotor_count; i++) {
float out = roll * _rotors[i].roll_scale +
@@ -311,6 +317,7 @@ MultirotorMixer::mix(float *outputs, unsigned space)
/* limit yaw if it causes outputs clipping */
if (out >= 0.0f && out < -yaw * _rotors[i].yaw_scale) {
yaw = -out / _rotors[i].yaw_scale;
+ _limits.yaw = true;
}
/* calculate min and max output values */
@@ -332,6 +339,7 @@ MultirotorMixer::mix(float *outputs, unsigned space)
for (unsigned i = 0; i < _rotor_count; i++) {
outputs[i] = scale_in * (roll * _rotors[i].roll_scale + pitch * _rotors[i].pitch_scale) + thrust;
}
+ _limits.roll_pitch = true;
} else {
/* roll/pitch mixed without limiting, add yaw control */
@@ -344,6 +352,7 @@ MultirotorMixer::mix(float *outputs, unsigned space)
float scale_out;
if (max_out > 1.0f) {
scale_out = 1.0f / max_out;
+ _limits.throttle_upper = true;
} else {
scale_out = 1.0f;
@@ -351,9 +360,20 @@ MultirotorMixer::mix(float *outputs, unsigned space)
/* scale outputs to range _idle_speed..1, and do final limiting */
for (unsigned i = 0; i < _rotor_count; i++) {
+ if (outputs[i] < _idle_speed) {
+ _limits.throttle_lower = true;
+ }
outputs[i] = constrain(_idle_speed + (outputs[i] * (1.0f - _idle_speed) * scale_out), _idle_speed, 1.0f);
}
+#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) || defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+ /* publish/advertise motor limits if running on FMU */
+ if (_limits_pub > 0) {
+ orb_publish(ORB_ID(multirotor_motor_limits), _limits_pub, &_limits);
+ } else {
+ _limits_pub = orb_advertise(ORB_ID(multirotor_motor_limits), &_limits);
+ }
+#endif
return _rotor_count;
}
diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c
index e44e6cdb0..6b8d0e634 100644
--- a/src/modules/systemlib/param/param.c
+++ b/src/modules/systemlib/param/param.c
@@ -322,7 +322,8 @@ param_get_value_ptr(param_t param)
v = &param_info_base[param].val;
}
- if (param_type(param) == PARAM_TYPE_STRUCT) {
+ if (param_type(param) >= PARAM_TYPE_STRUCT
+ && param_type(param) <= PARAM_TYPE_STRUCT_MAX) {
result = v->p;
} else {
diff --git a/src/modules/systemlib/param/param.h b/src/modules/systemlib/param/param.h
index 084cd931a..dc73b37e9 100644
--- a/src/modules/systemlib/param/param.h
+++ b/src/modules/systemlib/param/param.h
@@ -307,7 +307,7 @@ __EXPORT int param_load_default(void);
struct param_info_s __param__##_name = { \
#_name, \
PARAM_TYPE_STRUCT + sizeof(_default), \
- .val.p = &_default; \
+ .val.p = &_default \
}
/**
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 08c3ce1ac..b91a00c1e 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -192,12 +192,18 @@ ORB_DEFINE(actuator_outputs_1, struct actuator_outputs_s);
ORB_DEFINE(actuator_outputs_2, struct actuator_outputs_s);
ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s);
+#include "topics/multirotor_motor_limits.h"
+ORB_DEFINE(multirotor_motor_limits, struct multirotor_motor_limits_s);
+
#include "topics/telemetry_status.h"
ORB_DEFINE(telemetry_status_0, struct telemetry_status_s);
ORB_DEFINE(telemetry_status_1, struct telemetry_status_s);
ORB_DEFINE(telemetry_status_2, struct telemetry_status_s);
ORB_DEFINE(telemetry_status_3, struct telemetry_status_s);
+#include "topics/test_motor.h"
+ORB_DEFINE(test_motor, struct test_motor_s);
+
#include "topics/debug_key_value.h"
ORB_DEFINE(debug_key_value, struct debug_key_value_s);
@@ -213,6 +219,9 @@ ORB_DEFINE(encoders, struct encoders_s);
#include "topics/estimator_status.h"
ORB_DEFINE(estimator_status, struct estimator_status_report);
+#include "topics/vision_position_estimate.h"
+ORB_DEFINE(vision_position_estimate, struct vision_position_estimate);
+
#include "topics/vehicle_force_setpoint.h"
ORB_DEFINE(vehicle_force_setpoint, struct vehicle_force_setpoint_s);
diff --git a/src/modules/uORB/topics/differential_pressure.h b/src/modules/uORB/topics/differential_pressure.h
index cd48d3cb2..7342fcf04 100644
--- a/src/modules/uORB/topics/differential_pressure.h
+++ b/src/modules/uORB/topics/differential_pressure.h
@@ -54,7 +54,6 @@
struct differential_pressure_s {
uint64_t timestamp; /**< Microseconds since system boot, needed to integrate */
uint64_t error_count; /**< Number of errors detected by driver */
- float differential_pressure_pa; /**< Differential pressure reading */
float differential_pressure_raw_pa; /**< Raw differential pressure reading (may be negative) */
float differential_pressure_filtered_pa; /**< Low pass filtered differential pressure reading */
float max_differential_pressure_pa; /**< Maximum differential pressure reading */
diff --git a/src/modules/uORB/topics/esc_status.h b/src/modules/uORB/topics/esc_status.h
index 628824efa..b45c49788 100644
--- a/src/modules/uORB/topics/esc_status.h
+++ b/src/modules/uORB/topics/esc_status.h
@@ -78,6 +78,7 @@ enum ESC_CONNECTION_TYPE {
/**
* Electronic speed controller status.
+ * Unsupported float fields should be assigned NaN.
*/
struct esc_status_s {
/* use of a counter and timestamp recommended (but not necessary) */
@@ -89,17 +90,17 @@ struct esc_status_s {
enum ESC_CONNECTION_TYPE esc_connectiontype; /**< how ESCs connected to the system */
struct {
- uint16_t esc_address; /**< Address of current ESC (in most cases 1-8 / must be set by driver) */
enum ESC_VENDOR esc_vendor; /**< Vendor of current ESC */
- uint16_t esc_version; /**< Version of current ESC - if supported */
- uint16_t esc_voltage; /**< Voltage measured from current ESC - if supported */
- uint16_t esc_current; /**< Current measured from current ESC (100mA steps) - if supported */
- uint16_t esc_rpm; /**< RPM measured from current ESC - if supported */
- uint16_t esc_temperature; /**< Temperature measured from current ESC - if supported */
- float esc_setpoint; /**< setpoint of current ESC */
+ uint32_t esc_errorcount; /**< Number of reported errors by ESC - if supported */
+ int32_t esc_rpm; /**< Motor RPM, negative for reverse rotation [RPM] - if supported */
+ float esc_voltage; /**< Voltage measured from current ESC [V] - if supported */
+ float esc_current; /**< Current measured from current ESC [A] - if supported */
+ float esc_temperature; /**< Temperature measured from current ESC [degC] - if supported */
+ float esc_setpoint; /**< setpoint of current ESC */
uint16_t esc_setpoint_raw; /**< setpoint of current ESC (Value sent to ESC) */
- uint16_t esc_state; /**< State of ESC - depend on Vendor */
- uint16_t esc_errorcount; /**< Number of reported errors by ESC - if supported */
+ uint16_t esc_address; /**< Address of current ESC (in most cases 1-8 / must be set by driver) */
+ uint16_t esc_version; /**< Version of current ESC - if supported */
+ uint16_t esc_state; /**< State of ESC - depend on Vendor */
} esc[CONNECTED_ESC_MAX];
};
diff --git a/src/modules/uORB/topics/mission_result.h b/src/modules/uORB/topics/mission_result.h
index beb797e62..c7d25d1f0 100644
--- a/src/modules/uORB/topics/mission_result.h
+++ b/src/modules/uORB/topics/mission_result.h
@@ -55,8 +55,11 @@ struct mission_result_s
{
unsigned seq_reached; /**< Sequence of the mission item which has been reached */
unsigned seq_current; /**< Sequence of the current mission item */
- bool reached; /**< true if mission has been reached */
- bool finished; /**< true if mission has been completed */
+ bool reached; /**< true if mission has been reached */
+ bool finished; /**< true if mission has been completed */
+ bool stay_in_failsafe; /**< true if the commander should not switch out of the failsafe mode*/
+ bool geofence_violated; /**< true if the geofence is violated */
+ bool flight_termination; /**< true if the navigator demands a flight termination from the commander app */
};
/**
diff --git a/src/modules/uORB/topics/multirotor_motor_limits.h b/src/modules/uORB/topics/multirotor_motor_limits.h
new file mode 100644
index 000000000..44c51e4d9
--- /dev/null
+++ b/src/modules/uORB/topics/multirotor_motor_limits.h
@@ -0,0 +1,69 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file multirotor_motor_limits.h
+ *
+ * Definition of multirotor_motor_limits topic
+ */
+
+#ifndef MULTIROTOR_MOTOR_LIMITS_H_
+#define MULTIROTOR_MOTOR_LIMITS_H_
+
+#include "../uORB.h"
+#include <stdint.h>
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Motor limits
+ */
+struct multirotor_motor_limits_s {
+ uint8_t roll_pitch : 1; // roll/pitch limit reached
+ uint8_t yaw : 1; // yaw limit reached
+ uint8_t throttle_lower : 1; // lower throttle limit reached
+ uint8_t throttle_upper : 1; // upper throttle limit reached
+ uint8_t reserved : 4;
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(multirotor_motor_limits);
+
+#endif
diff --git a/src/modules/uORB/topics/offboard_control_setpoint.h b/src/modules/uORB/topics/offboard_control_setpoint.h
index d7b131e3c..72a28e501 100644
--- a/src/modules/uORB/topics/offboard_control_setpoint.h
+++ b/src/modules/uORB/topics/offboard_control_setpoint.h
@@ -53,11 +53,42 @@ enum OFFBOARD_CONTROL_MODE {
OFFBOARD_CONTROL_MODE_DIRECT = 0,
OFFBOARD_CONTROL_MODE_DIRECT_RATES = 1,
OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE = 2,
- OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY = 3,
- OFFBOARD_CONTROL_MODE_DIRECT_POSITION = 4,
- OFFBOARD_CONTROL_MODE_ATT_YAW_RATE = 5,
- OFFBOARD_CONTROL_MODE_ATT_YAW_POS = 6,
- OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 7, /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
+ OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED = 3,
+ OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED = 4,
+ OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED = 5,
+ OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED = 6,
+ OFFBOARD_CONTROL_MODE_DIRECT_GLOBAL = 7,
+ OFFBOARD_CONTROL_MODE_DIRECT_FORCE = 8,
+ OFFBOARD_CONTROL_MODE_ATT_YAW_RATE = 9,
+ OFFBOARD_CONTROL_MODE_ATT_YAW_POS = 10,
+ OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 11 /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
+};
+
+enum OFFBOARD_CONTROL_FRAME {
+ OFFBOARD_CONTROL_FRAME_LOCAL_NED = 0,
+ OFFBOARD_CONTROL_FRAME_LOCAL_OFFSET_NED = 1,
+ OFFBOARD_CONTROL_FRAME_BODY_NED = 2,
+ OFFBOARD_CONTROL_FRAME_BODY_OFFSET_NED = 3,
+ OFFBOARD_CONTROL_FRAME_GLOBAL = 4
+};
+
+/* mappings for the ignore bitmask */
+enum {OFB_IGN_BIT_POS_X,
+ OFB_IGN_BIT_POS_Y,
+ OFB_IGN_BIT_POS_Z,
+ OFB_IGN_BIT_VEL_X,
+ OFB_IGN_BIT_VEL_Y,
+ OFB_IGN_BIT_VEL_Z,
+ OFB_IGN_BIT_ACC_X,
+ OFB_IGN_BIT_ACC_Y,
+ OFB_IGN_BIT_ACC_Z,
+ OFB_IGN_BIT_BODYRATE_X,
+ OFB_IGN_BIT_BODYRATE_Y,
+ OFB_IGN_BIT_BODYRATE_Z,
+ OFB_IGN_BIT_ATT,
+ OFB_IGN_BIT_THRUST,
+ OFB_IGN_BIT_YAW,
+ OFB_IGN_BIT_YAWRATE,
};
/**
@@ -70,10 +101,21 @@ struct offboard_control_setpoint_s {
enum OFFBOARD_CONTROL_MODE mode; /**< The current control inputs mode */
- float p1; /**< ailerons roll / roll rate input */
- float p2; /**< elevator / pitch / pitch rate */
- float p3; /**< rudder / yaw rate / yaw */
- float p4; /**< throttle / collective thrust / altitude */
+ double position[3]; /**< lat, lon, alt / x, y, z */
+ float velocity[3]; /**< x vel, y vel, z vel */
+ float acceleration[3]; /**< x acc, y acc, z acc */
+ float attitude[4]; /**< attitude of vehicle (quaternion) */
+ float attitude_rate[3]; /**< body angular rates (x, y, z) */
+ float thrust; /**< thrust */
+ float yaw; /**< yaw: this is the yaw from the position_target message
+ (not from the full attitude_target message) */
+ float yaw_rate; /**< yaw rate: this is the yaw from the position_target message
+ (not from the full attitude_target message) */
+
+ uint16_t ignore; /**< if field i is set to true, the value should be ignored, see definition at top of file
+ for mapping */
+
+ bool isForceSetpoint; /**< the acceleration vector should be interpreted as force */
float override_mode_switch;
@@ -87,6 +129,147 @@ struct offboard_control_setpoint_s {
* @}
*/
+/**
+ * Returns true if the position setpoint at index should be ignored
+ */
+inline bool offboard_control_sp_ignore_position(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
+ return (bool)(offboard_control_sp.ignore & (1 << (OFB_IGN_BIT_POS_X + index)));
+}
+
+/**
+ * Returns true if all position setpoints should be ignored
+ */
+inline bool offboard_control_sp_ignore_position_all(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ for (int i = 0; i < 3; i++) {
+ if (!offboard_control_sp_ignore_position(offboard_control_sp, i)) {
+ return false;
+ }
+ }
+ return true;
+}
+
+/**
+ * Returns true if some position setpoints should be ignored
+ */
+inline bool offboard_control_sp_ignore_position_some(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ for (int i = 0; i < 3; i++) {
+ if (offboard_control_sp_ignore_position(offboard_control_sp, i)) {
+ return true;
+ }
+ }
+ return false;
+}
+
+/**
+ * Returns true if the velocity setpoint at index should be ignored
+ */
+inline bool offboard_control_sp_ignore_velocity(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
+ return (bool)(offboard_control_sp.ignore & (1 << (OFB_IGN_BIT_VEL_X + index)));
+}
+
+/**
+ * Returns true if all velocity setpoints should be ignored
+ */
+inline bool offboard_control_sp_ignore_velocity_all(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ for (int i = 0; i < 3; i++) {
+ if (!offboard_control_sp_ignore_velocity(offboard_control_sp, i)) {
+ return false;
+ }
+ }
+ return true;
+}
+
+/**
+ * Returns true if some velocity setpoints should be ignored
+ */
+inline bool offboard_control_sp_ignore_velocity_some(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ for (int i = 0; i < 3; i++) {
+ if (offboard_control_sp_ignore_velocity(offboard_control_sp, i)) {
+ return true;
+ }
+ }
+ return false;
+}
+
+/**
+ * Returns true if the acceleration setpoint at index should be ignored
+ */
+inline bool offboard_control_sp_ignore_acceleration(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
+ return (bool)(offboard_control_sp.ignore & (1 << (OFB_IGN_BIT_ACC_X + index)));
+}
+
+/**
+ * Returns true if all acceleration setpoints should be ignored
+ */
+inline bool offboard_control_sp_ignore_acceleration_all(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ for (int i = 0; i < 3; i++) {
+ if (!offboard_control_sp_ignore_acceleration(offboard_control_sp, i)) {
+ return false;
+ }
+ }
+ return true;
+}
+
+/**
+ * Returns true if some acceleration setpoints should be ignored
+ */
+inline bool offboard_control_sp_ignore_acceleration_some(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ for (int i = 0; i < 3; i++) {
+ if (offboard_control_sp_ignore_acceleration(offboard_control_sp, i)) {
+ return true;
+ }
+ }
+ return false;
+}
+
+/**
+ * Returns true if the bodyrate setpoint at index should be ignored
+ */
+inline bool offboard_control_sp_ignore_bodyrates(const struct offboard_control_setpoint_s &offboard_control_sp, int index) {
+ return (bool)(offboard_control_sp.ignore & (1 << (OFB_IGN_BIT_BODYRATE_X + index)));
+}
+
+/**
+ * Returns true if some of the bodyrate setpoints should be ignored
+ */
+inline bool offboard_control_sp_ignore_bodyrates_some(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ for (int i = 0; i < 3; i++) {
+ if (offboard_control_sp_ignore_bodyrates(offboard_control_sp, i)) {
+ return true;
+ }
+ }
+ return false;
+}
+
+/**
+ * Returns true if the attitude setpoint should be ignored
+ */
+inline bool offboard_control_sp_ignore_attitude(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ return (bool)(offboard_control_sp.ignore & (1 << OFB_IGN_BIT_ATT));
+}
+
+/**
+ * Returns true if the thrust setpoint should be ignored
+ */
+inline bool offboard_control_sp_ignore_thrust(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ return (bool)(offboard_control_sp.ignore & (1 << OFB_IGN_BIT_THRUST));
+}
+
+/**
+ * Returns true if the yaw setpoint should be ignored
+ */
+inline bool offboard_control_sp_ignore_yaw(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ return (bool)(offboard_control_sp.ignore & (1 << OFB_IGN_BIT_YAW));
+}
+
+/**
+ * Returns true if the yaw rate setpoint should be ignored
+ */
+inline bool offboard_control_sp_ignore_yawrate(const struct offboard_control_setpoint_s &offboard_control_sp) {
+ return (bool)(offboard_control_sp.ignore & (1 << OFB_IGN_BIT_YAWRATE));
+}
+
+
/* register this as object request broker structure */
ORB_DECLARE(offboard_control_setpoint);
diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h
index 4a1932180..cb2262534 100644
--- a/src/modules/uORB/topics/position_setpoint_triplet.h
+++ b/src/modules/uORB/topics/position_setpoint_triplet.h
@@ -60,7 +60,7 @@ enum SETPOINT_TYPE
SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */
SETPOINT_TYPE_LAND, /**< land setpoint, altitude must be ignored, descend until landing */
SETPOINT_TYPE_IDLE, /**< do nothing, switch off motors or keep at idle speed (MC) */
- SETPOINT_TYPE_OFFBOARD, /**< setpoint set by offboard */
+ SETPOINT_TYPE_OFFBOARD, /**< setpoint in NED frame (x, y, z, vx, vy, vz) set by offboard */
};
struct position_setpoint_s
@@ -71,18 +71,25 @@ struct position_setpoint_s
float y; /**< local position setpoint in m in NED */
float z; /**< local position setpoint in m in NED */
bool position_valid; /**< true if local position setpoint valid */
- float vx; /**< local velocity setpoint in m in NED */
- float vy; /**< local velocity setpoint in m in NED */
- float vz; /**< local velocity setpoint in m in NED */
+ float vx; /**< local velocity setpoint in m/s in NED */
+ float vy; /**< local velocity setpoint in m/s in NED */
+ float vz; /**< local velocity setpoint in m/s in NED */
bool velocity_valid; /**< true if local velocity setpoint valid */
double lat; /**< latitude, in deg */
double lon; /**< longitude, in deg */
float alt; /**< altitude AMSL, in m */
float yaw; /**< yaw (only for multirotors), in rad [-PI..PI), NaN = hold current yaw */
+ bool yaw_valid; /**< true if yaw setpoint valid */
float yawspeed; /**< yawspeed (only for multirotors, in rad/s) */
+ bool yawspeed_valid; /**< true if yawspeed setpoint valid */
float loiter_radius; /**< loiter radius (only for fixed wing), in m */
int8_t loiter_direction; /**< loiter direction: 1 = CW, -1 = CCW */
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
+ float a_x; //**< acceleration x setpoint */
+ float a_y; //**< acceleration y setpoint */
+ float a_z; //**< acceleration z setpoint */
+ bool acceleration_valid; //*< true if acceleration setpoint is valid/should be used */
+ bool acceleration_is_force; //*< interprete acceleration as force */
};
/**
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index 8978de471..16916cc4d 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -34,6 +34,8 @@
/**
* @file rc_channels.h
* Definition of the rc_channels uORB topic.
+ *
+ * @deprecated DO NOT USE FOR NEW CODE
*/
#ifndef RC_CHANNELS_H_
@@ -63,10 +65,13 @@ enum RC_CHANNELS_FUNCTION {
AUX_2,
AUX_3,
AUX_4,
- AUX_5,
- RC_CHANNELS_FUNCTION_MAX /**< Indicates the number of functions. There can be more functions than RC channels. */
+ AUX_5
};
+// MAXIMUM FUNCTIONS IS != MAXIMUM RC INPUT CHANNELS
+
+#define RC_CHANNELS_FUNCTION_MAX 18
+
/**
* @addtogroup topics
* @{
@@ -76,7 +81,6 @@ struct rc_channels_s {
uint64_t timestamp_last_valid; /**< Timestamp of last valid RC signal */
float channels[RC_CHANNELS_FUNCTION_MAX]; /**< Scaled to -1..1 (throttle: 0..1) */
uint8_t channel_count; /**< Number of valid channels */
- char function_name[RC_CHANNELS_FUNCTION_MAX][20]; /**< String array to store the names of the functions */
int8_t function[RC_CHANNELS_FUNCTION_MAX]; /**< Functions mapping */
uint8_t rssi; /**< Receive signal strength index */
bool signal_lost; /**< Control signal lost, should be checked together with topic timeout */
diff --git a/src/modules/uORB/topics/tecs_status.h b/src/modules/uORB/topics/tecs_status.h
index 33055018c..ddca19d61 100644
--- a/src/modules/uORB/topics/tecs_status.h
+++ b/src/modules/uORB/topics/tecs_status.h
@@ -51,11 +51,13 @@
*/
typedef enum {
- TECS_MODE_NORMAL,
+ TECS_MODE_NORMAL = 0,
TECS_MODE_UNDERSPEED,
TECS_MODE_TAKEOFF,
TECS_MODE_LAND,
- TECS_MODE_LAND_THROTTLELIM
+ TECS_MODE_LAND_THROTTLELIM,
+ TECS_MODE_BAD_DESCENT,
+ TECS_MODE_CLIMBOUT
} tecs_mode;
/**
@@ -65,14 +67,12 @@ struct tecs_status_s {
uint64_t timestamp; /**< timestamp, in microseconds since system start */
float altitudeSp;
- float altitude;
- float altitudeFiltered;
+ float altitude_filtered;
float flightPathAngleSp;
float flightPathAngle;
float flightPathAngleFiltered;
float airspeedSp;
- float airspeed;
- float airspeedFiltered;
+ float airspeed_filtered;
float airspeedDerivativeSp;
float airspeedDerivative;
diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h
index 1297c1a9d..93193f32b 100644
--- a/src/modules/uORB/topics/telemetry_status.h
+++ b/src/modules/uORB/topics/telemetry_status.h
@@ -67,6 +67,8 @@ struct telemetry_status_s {
uint8_t noise; /**< background noise level */
uint8_t remote_noise; /**< remote background noise level */
uint8_t txbuf; /**< how full the tx buffer is as a percentage */
+ uint8_t system_id; /**< system id of the remote system */
+ uint8_t component_id; /**< component id of the remote system */
};
/**
diff --git a/src/modules/uORB/topics/test_motor.h b/src/modules/uORB/topics/test_motor.h
new file mode 100644
index 000000000..491096934
--- /dev/null
+++ b/src/modules/uORB/topics/test_motor.h
@@ -0,0 +1,70 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file test_motor.h
+ *
+ * Test a single drive motor while the vehicle is disarmed
+ *
+ * Publishing values to this topic causes a single motor to spin, e.g. for
+ * ground test purposes. This topic will be ignored while the vehicle is armed.
+ *
+ */
+
+#ifndef TOPIC_TEST_MOTOR_H
+#define TOPIC_TEST_MOTOR_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+#define NUM_MOTOR_OUTPUTS 8
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct test_motor_s {
+ uint64_t timestamp; /**< output timestamp in us since system boot */
+ unsigned motor_number; /**< number of motor to spin */
+ float value; /**< output data, in natural output units */
+};
+
+/**
+ * @}
+ */
+
+/* actuator output sets; this list can be expanded as more drivers emerge */
+ORB_DECLARE(test_motor);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
index 7db33d98b..f264accbb 100644
--- a/src/modules/uORB/topics/vehicle_command.h
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +34,10 @@
/**
* @file vehicle_command.h
* Definition of the vehicle command uORB topic.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef TOPIC_VEHICLE_COMMAND_H_
@@ -52,6 +53,9 @@
* but can contain additional ones.
*/
enum VEHICLE_CMD {
+ VEHICLE_CMD_CUSTOM_0 = 0, /* test command */
+ VEHICLE_CMD_CUSTOM_1 = 1, /* test command */
+ VEHICLE_CMD_CUSTOM_2 = 2, /* test command */
VEHICLE_CMD_NAV_WAYPOINT = 16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
VEHICLE_CMD_NAV_LOITER_UNLIM = 17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
VEHICLE_CMD_NAV_LOITER_TURNS = 18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
@@ -61,6 +65,9 @@ enum VEHICLE_CMD {
VEHICLE_CMD_NAV_TAKEOFF = 22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
VEHICLE_CMD_NAV_ROI = 80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
VEHICLE_CMD_NAV_PATHPLANNING = 81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
+ VEHICLE_CMD_NAV_GUIDED_LIMITS=90, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
+ VEHICLE_CMD_NAV_GUIDED_MASTER=91, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_NAV_LAST = 95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_CONDITION_DELAY = 112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_CONDITION_CHANGE_ALT = 113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
@@ -87,7 +94,8 @@ enum VEHICLE_CMD {
VEHICLE_CMD_MISSION_START = 300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
VEHICLE_CMD_COMPONENT_ARM_DISARM = 400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
VEHICLE_CMD_START_RX_PAIR = 500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
- VEHICLE_CMD_ENUM_END = 501, /* | */
+ VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY = 30001, /**< Prepare a payload deployment in the flight plan */
+ VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY = 30002 /**< Control a pre-programmed payload deployment */
};
/**
@@ -115,8 +123,8 @@ struct vehicle_command_s {
float param2; /**< Parameter 2, as defined by MAVLink VEHICLE_CMD enum. */
float param3; /**< Parameter 3, as defined by MAVLink VEHICLE_CMD enum. */
float param4; /**< Parameter 4, as defined by MAVLink VEHICLE_CMD enum. */
- float param5; /**< Parameter 5, as defined by MAVLink VEHICLE_CMD enum. */
- float param6; /**< Parameter 6, as defined by MAVLink VEHICLE_CMD enum. */
+ double param5; /**< Parameter 5, as defined by MAVLink VEHICLE_CMD enum. */
+ double param6; /**< Parameter 6, as defined by MAVLink VEHICLE_CMD enum. */
float param7; /**< Parameter 7, as defined by MAVLink VEHICLE_CMD enum. */
enum VEHICLE_CMD command; /**< Command ID, as defined MAVLink by VEHICLE_CMD enum. */
uint8_t target_system; /**< System which should execute the command */
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index 49e2ba4b5..ca7705456 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -77,6 +77,7 @@ struct vehicle_control_mode_s {
bool flag_control_offboard_enabled; /**< true if offboard control should be used */
bool flag_control_rates_enabled; /**< true if rates are stabilized */
bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
+ bool flag_control_force_enabled; /**< true if force control is mixed in */
bool flag_control_velocity_enabled; /**< true if horizontal velocity (implies direction) is controlled */
bool flag_control_position_enabled; /**< true if position is controlled */
bool flag_control_altitude_enabled; /**< true if altitude is controlled */
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index 25137c1c6..c3bb3b893 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -72,6 +72,8 @@ struct vehicle_global_position_s {
float yaw; /**< Yaw in radians -PI..+PI. */
float eph; /**< Standard deviation of position estimate horizontally */
float epv; /**< Standard deviation of position vertically */
+ float terrain_alt; /**< Terrain altitude in m, WGS84 */
+ bool terrain_alt_valid; /**< Terrain altitude estimate is valid */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
index 80d65cd69..31e616f4f 100644
--- a/src/modules/uORB/topics/vehicle_gps_position.h
+++ b/src/modules/uORB/topics/vehicle_gps_position.h
@@ -62,7 +62,7 @@ struct vehicle_gps_position_s {
uint64_t timestamp_variance;
float s_variance_m_s; /**< speed accuracy estimate m/s */
float c_variance_rad; /**< course accuracy estimate rad */
- uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */
+ uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5: Real-Time Kinematic, float, 6: Real-Time Kinematic, fixed, 8: Extrapolated. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */
float eph; /**< GPS HDOP horizontal dilution of position in m */
float epv; /**< GPS VDOP horizontal dilution of position in m */
diff --git a/src/modules/uORB/topics/vehicle_local_position_setpoint.h b/src/modules/uORB/topics/vehicle_local_position_setpoint.h
index 8988a0330..6766bb58a 100644
--- a/src/modules/uORB/topics/vehicle_local_position_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_local_position_setpoint.h
@@ -50,11 +50,12 @@
*/
struct vehicle_local_position_setpoint_s {
+ uint64_t timestamp; /**< timestamp of the setpoint */
float x; /**< in meters NED */
float y; /**< in meters NED */
float z; /**< in meters NED */
float yaw; /**< in radians NED -PI..+PI */
-}; /**< Local position in NED frame to go to */
+}; /**< Local position in NED frame */
/**
* @}
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index b683bf98a..a1b2667e3 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -102,7 +102,10 @@ typedef enum {
NAVIGATION_STATE_AUTO_MISSION, /**< Auto mission mode */
NAVIGATION_STATE_AUTO_LOITER, /**< Auto loiter mode */
NAVIGATION_STATE_AUTO_RTL, /**< Auto return to launch mode */
+ NAVIGATION_STATE_AUTO_RCRECOVER, /**< RC recover mode */
NAVIGATION_STATE_AUTO_RTGS, /**< Auto return to groundstation on data link loss */
+ NAVIGATION_STATE_AUTO_LANDENGFAIL, /**< Auto land on engine failure */
+ NAVIGATION_STATE_AUTO_LANDGPSFAIL, /**< Auto land on gps failure (e.g. open loop loiter down) */
NAVIGATION_STATE_ACRO, /**< Acro mode */
NAVIGATION_STATE_LAND, /**< Land mode */
NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */
@@ -198,14 +201,25 @@ struct vehicle_status_s {
bool rc_signal_found_once;
bool rc_signal_lost; /**< true if RC reception lost */
+ bool rc_signal_lost_cmd; /**< true if RC lost mode is commanded */
bool rc_input_blocked; /**< set if RC input should be ignored */
- bool data_link_lost; /**< datalink to GCS lost */
+ bool data_link_lost; /**< datalink to GCS lost */
+ bool data_link_lost_cmd; /**< datalink to GCS lost mode commanded */
+ uint8_t data_link_lost_counter; /**< counts unique data link lost events */
+ bool engine_failure; /** Set to true if an engine failure is detected */
+ bool engine_failure_cmd; /** Set to true if an engine failure mode is commanded */
+ bool gps_failure; /** Set to true if a gps failure is detected */
+ bool gps_failure_cmd; /** Set to true if a gps failure mode is commanded */
+
+ bool barometer_failure; /** Set to true if a barometer failure is detected */
bool offboard_control_signal_found_once;
bool offboard_control_signal_lost;
bool offboard_control_signal_weak;
uint64_t offboard_control_signal_lost_interval; /**< interval in microseconds without an offboard control message */
+ bool offboard_control_set_by_command; /**< true if the offboard mode was set by a mavlink command
+ and should not be overridden by RC */
/* see SYS_STATUS mavlink message for the following */
uint32_t onboard_control_sensors_present;
@@ -227,6 +241,8 @@ struct vehicle_status_s {
bool circuit_breaker_engaged_power_check;
bool circuit_breaker_engaged_airspd_check;
+ bool circuit_breaker_engaged_enginefailure_check;
+ bool circuit_breaker_engaged_gpsfailure_check;
};
/**
diff --git a/src/modules/uORB/topics/vision_position_estimate.h b/src/modules/uORB/topics/vision_position_estimate.h
new file mode 100644
index 000000000..74c96cf2e
--- /dev/null
+++ b/src/modules/uORB/topics/vision_position_estimate.h
@@ -0,0 +1,82 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vision_position_estimate.h
+ * Vision based position estimate
+ */
+
+#ifndef TOPIC_VISION_POSITION_ESTIMATE_H_
+#define TOPIC_VISION_POSITION_ESTIMATE_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Vision based position estimate in NED frame
+ */
+struct vision_position_estimate {
+
+ unsigned id; /**< ID of the estimator, commonly the component ID of the incoming message */
+
+ uint64_t timestamp_boot; /**< time of this estimate, in microseconds since system start */
+ uint64_t timestamp_computer; /**< timestamp provided by the companion computer, in us */
+
+ float x; /**< X position in meters in NED earth-fixed frame */
+ float y; /**< Y position in meters in NED earth-fixed frame */
+ float z; /**< Z position in meters in NED earth-fixed frame (negative altitude) */
+
+ float vx; /**< X velocity in meters per second in NED earth-fixed frame */
+ float vy; /**< Y velocity in meters per second in NED earth-fixed frame */
+ float vz; /**< Z velocity in meters per second in NED earth-fixed frame */
+
+ float q[4]; /**< Estimated attitude as quaternion */
+
+ // XXX Add covariances here
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vision_position_estimate);
+
+#endif /* TOPIC_VISION_POSITION_ESTIMATE_H_ */
diff --git a/src/modules/uavcan/esc_controller.cpp b/src/modules/uavcan/actuators/esc.cpp
index 406eba88c..1990651ef 100644
--- a/src/modules/uavcan/esc_controller.cpp
+++ b/src/modules/uavcan/actuators/esc.cpp
@@ -32,12 +32,12 @@
****************************************************************************/
/**
- * @file esc_controller.cpp
+ * @file esc.cpp
*
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
*/
-#include "esc_controller.hpp"
+#include "esc.hpp"
#include <systemlib/err.h>
UavcanEscController::UavcanEscController(uavcan::INode &node) :
@@ -73,7 +73,7 @@ int UavcanEscController::init()
void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
{
- if ((outputs == nullptr) || (num_outputs > MAX_ESCS)) {
+ if ((outputs == nullptr) || (num_outputs > uavcan::equipment::esc::RawCommand::FieldTypes::cmd::MaxSize)) {
perf_count(_perfcnt_invalid_input);
return;
}
@@ -93,25 +93,24 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
*/
uavcan::equipment::esc::RawCommand msg;
+ static const int cmd_max = uavcan::equipment::esc::RawCommand::FieldTypes::cmd::RawValueType::max();
+
if (_armed) {
for (unsigned i = 0; i < num_outputs; i++) {
- float scaled = (outputs[i] + 1.0F) * 0.5F * uavcan::equipment::esc::RawCommand::CMD_MAX;
+ float scaled = (outputs[i] + 1.0F) * 0.5F * cmd_max;
if (scaled < 1.0F) {
scaled = 1.0F; // Since we're armed, we don't want to stop it completely
}
- if (scaled < uavcan::equipment::esc::RawCommand::CMD_MIN) {
- scaled = uavcan::equipment::esc::RawCommand::CMD_MIN;
- perf_count(_perfcnt_scaling_error);
- } else if (scaled > uavcan::equipment::esc::RawCommand::CMD_MAX) {
- scaled = uavcan::equipment::esc::RawCommand::CMD_MAX;
+ if (scaled > cmd_max) {
+ scaled = cmd_max;
perf_count(_perfcnt_scaling_error);
- } else {
- ; // Correct value
}
- msg.cmd.push_back(static_cast<unsigned>(scaled));
+ msg.cmd.push_back(static_cast<int>(scaled));
+
+ _esc_status.esc[i].esc_setpoint_raw = abs(static_cast<int>(scaled));
}
}
@@ -129,10 +128,31 @@ void UavcanEscController::arm_esc(bool arm)
void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status> &msg)
{
- // TODO save status into a local storage; publish to ORB later from orb_pub_timer_cb()
+ if (msg.esc_index < CONNECTED_ESC_MAX) {
+ _esc_status.esc_count = uavcan::max<int>(_esc_status.esc_count, msg.esc_index + 1);
+ _esc_status.timestamp = msg.getMonotonicTimestamp().toUSec();
+
+ auto &ref = _esc_status.esc[msg.esc_index];
+
+ ref.esc_address = msg.getSrcNodeID().get();
+
+ ref.esc_voltage = msg.voltage;
+ ref.esc_current = msg.current;
+ ref.esc_temperature = msg.temperature;
+ ref.esc_setpoint = msg.power_rating_pct;
+ ref.esc_rpm = msg.rpm;
+ ref.esc_errorcount = msg.error_count;
+ }
}
void UavcanEscController::orb_pub_timer_cb(const uavcan::TimerEvent&)
{
- // TODO publish to ORB
+ _esc_status.counter += 1;
+ _esc_status.esc_connectiontype = ESC_CONNECTION_TYPE_CAN;
+
+ if (_esc_status_pub > 0) {
+ (void)orb_publish(ORB_ID(esc_status), _esc_status_pub, &_esc_status);
+ } else {
+ _esc_status_pub = orb_advertise(ORB_ID(esc_status), &_esc_status);
+ }
}
diff --git a/src/modules/uavcan/esc_controller.hpp b/src/modules/uavcan/actuators/esc.hpp
index 559ede561..f4a3877e6 100644
--- a/src/modules/uavcan/esc_controller.hpp
+++ b/src/modules/uavcan/actuators/esc.hpp
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file esc_controller.hpp
+ * @file esc.hpp
*
* UAVCAN <--> ORB bridge for ESC messages:
* uavcan.equipment.esc.RawCommand
@@ -48,6 +48,8 @@
#include <uavcan/equipment/esc/RawCommand.hpp>
#include <uavcan/equipment/esc/Status.hpp>
#include <systemlib/perf_counter.h>
+#include <uORB/topics/esc_status.h>
+
class UavcanEscController
{
@@ -73,9 +75,8 @@ private:
void orb_pub_timer_cb(const uavcan::TimerEvent &event);
- static constexpr unsigned MAX_RATE_HZ = 100; ///< XXX make this configurable
- static constexpr unsigned ESC_STATUS_UPDATE_RATE_HZ = 5;
- static constexpr unsigned MAX_ESCS = uavcan::equipment::esc::RawCommand::FieldTypes::cmd::MaxSize;
+ static constexpr unsigned MAX_RATE_HZ = 200; ///< XXX make this configurable
+ static constexpr unsigned ESC_STATUS_UPDATE_RATE_HZ = 10;
typedef uavcan::MethodBinder<UavcanEscController*,
void (UavcanEscController::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::Status>&)>
@@ -84,6 +85,10 @@ private:
typedef uavcan::MethodBinder<UavcanEscController*, void (UavcanEscController::*)(const uavcan::TimerEvent&)>
TimerCbBinder;
+ bool _armed = false;
+ esc_status_s _esc_status = {};
+ orb_advert_t _esc_status_pub = -1;
+
/*
* libuavcan related things
*/
@@ -94,12 +99,6 @@ private:
uavcan::TimerEventForwarder<TimerCbBinder> _orb_timer;
/*
- * ESC states
- */
- bool _armed = false;
- uavcan::equipment::esc::Status _states[MAX_ESCS];
-
- /*
* Perf counters
*/
perf_counter_t _perfcnt_invalid_input = perf_alloc(PC_COUNT, "uavcan_esc_invalid_input");
diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk
index 1ef6f0cfa..f92bc754f 100644
--- a/src/modules/uavcan/module.mk
+++ b/src/modules/uavcan/module.mk
@@ -40,10 +40,19 @@ MODULE_COMMAND = uavcan
MAXOPTIMIZATION = -Os
-SRCS += uavcan_main.cpp \
- uavcan_clock.cpp \
- esc_controller.cpp \
- gnss_receiver.cpp
+# Main
+SRCS += uavcan_main.cpp \
+ uavcan_clock.cpp \
+ uavcan_params.c
+
+# Actuators
+SRCS += actuators/esc.cpp
+
+# Sensors
+SRCS += sensors/sensor_bridge.cpp \
+ sensors/gnss.cpp \
+ sensors/mag.cpp \
+ sensors/baro.cpp
#
# libuavcan
@@ -65,10 +74,6 @@ override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM
#
# Invoke DSDL compiler
-# TODO: Add make target for this, or invoke dsdlc manually.
-# The second option assumes that the generated headers shall be saved
-# under the version control, which may be undesirable.
-# The first option requires any Python and the Python Mako library for the sources to be built.
#
$(info $(shell $(LIBUAVCAN_DSDLC) $(UAVCAN_DSDL_DIR)))
INCLUDE_DIRS += dsdlc_generated
diff --git a/src/modules/uavcan/sensors/baro.cpp b/src/modules/uavcan/sensors/baro.cpp
new file mode 100644
index 000000000..80c5e3828
--- /dev/null
+++ b/src/modules/uavcan/sensors/baro.cpp
@@ -0,0 +1,117 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+#include "baro.hpp"
+#include <cmath>
+
+static const orb_id_t BARO_TOPICS[2] = {
+ ORB_ID(sensor_baro0),
+ ORB_ID(sensor_baro1)
+};
+
+const char *const UavcanBarometerBridge::NAME = "baro";
+
+UavcanBarometerBridge::UavcanBarometerBridge(uavcan::INode& node) :
+UavcanCDevSensorBridgeBase("uavcan_baro", "/dev/uavcan/baro", BARO_DEVICE_PATH, BARO_TOPICS),
+_sub_air_data(node)
+{
+}
+
+int UavcanBarometerBridge::init()
+{
+ int res = device::CDev::init();
+ if (res < 0) {
+ return res;
+ }
+
+ res = _sub_air_data.start(AirDataCbBinder(this, &UavcanBarometerBridge::air_data_sub_cb));
+ if (res < 0) {
+ log("failed to start uavcan sub: %d", res);
+ return res;
+ }
+ return 0;
+}
+
+int UavcanBarometerBridge::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+ case BAROIOCSMSLPRESSURE: {
+ if ((arg < 80000) || (arg > 120000)) {
+ return -EINVAL;
+ } else {
+ log("new msl pressure %u", _msl_pressure);
+ _msl_pressure = arg;
+ return OK;
+ }
+ }
+ case BAROIOCGMSLPRESSURE: {
+ return _msl_pressure;
+ }
+ default: {
+ return CDev::ioctl(filp, cmd, arg);
+ }
+ }
+}
+
+void UavcanBarometerBridge::air_data_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticAirData> &msg)
+{
+ auto report = ::baro_report();
+
+ report.timestamp = msg.getUtcTimestamp().toUSec();
+ if (report.timestamp == 0) {
+ report.timestamp = msg.getMonotonicTimestamp().toUSec();
+ }
+
+ report.temperature = msg.static_temperature;
+ report.pressure = msg.static_pressure / 100.0F; // Convert to millibar
+
+ /*
+ * Altitude computation
+ * Refer to the MS5611 driver for details
+ */
+ const double T1 = 15.0 + 273.15; // temperature at base height in Kelvin
+ const double a = -6.5 / 1000; // temperature gradient in degrees per metre
+ const double g = 9.80665; // gravity constant in m/s/s
+ const double R = 287.05; // ideal gas constant in J/kg/K
+
+ const double p1 = _msl_pressure / 1000.0; // current pressure at MSL in kPa
+ const double p = double(msg.static_pressure) / 1000.0; // measured pressure in kPa
+
+ report.altitude = (((std::pow((p / p1), (-(a * R) / g))) * T1) - T1) / a;
+
+ publish(msg.getSrcNodeID().get(), &report);
+}
diff --git a/src/modules/uavcan/sensors/baro.hpp b/src/modules/uavcan/sensors/baro.hpp
new file mode 100644
index 000000000..9d470219e
--- /dev/null
+++ b/src/modules/uavcan/sensors/baro.hpp
@@ -0,0 +1,68 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+#pragma once
+
+#include "sensor_bridge.hpp"
+#include <drivers/drv_baro.h>
+
+#include <uavcan/equipment/air_data/StaticAirData.hpp>
+
+class UavcanBarometerBridge : public UavcanCDevSensorBridgeBase
+{
+public:
+ static const char *const NAME;
+
+ UavcanBarometerBridge(uavcan::INode& node);
+
+ const char *get_name() const override { return NAME; }
+
+ int init() override;
+
+private:
+ int ioctl(struct file *filp, int cmd, unsigned long arg) override;
+
+ void air_data_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticAirData> &msg);
+
+ typedef uavcan::MethodBinder<UavcanBarometerBridge*,
+ void (UavcanBarometerBridge::*)
+ (const uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticAirData>&)>
+ AirDataCbBinder;
+
+ uavcan::Subscriber<uavcan::equipment::air_data::StaticAirData, AirDataCbBinder> _sub_air_data;
+ unsigned _msl_pressure = 101325;
+};
diff --git a/src/modules/uavcan/gnss_receiver.cpp b/src/modules/uavcan/sensors/gnss.cpp
index ba1fe5e49..24afe6aaf 100644
--- a/src/modules/uavcan/gnss_receiver.cpp
+++ b/src/modules/uavcan/sensors/gnss.cpp
@@ -32,52 +32,72 @@
****************************************************************************/
/**
- * @file gnss_receiver.cpp
+ * @file gnss.cpp
*
* @author Pavel Kirienko <pavel.kirienko@gmail.com>
* @author Andrew Chambers <achamber@gmail.com>
*
*/
-#include "gnss_receiver.hpp"
+#include "gnss.hpp"
#include <systemlib/err.h>
#include <mathlib/mathlib.h>
-#define MM_PER_CM 10 // Millimeters per centimeter
+const char *const UavcanGnssBridge::NAME = "gnss";
-UavcanGnssReceiver::UavcanGnssReceiver(uavcan::INode &node) :
+UavcanGnssBridge::UavcanGnssBridge(uavcan::INode &node) :
_node(node),
-_uavcan_sub_status(node),
+_sub_fix(node),
_report_pub(-1)
{
}
-int UavcanGnssReceiver::init()
+int UavcanGnssBridge::init()
{
- int res = -1;
-
- // GNSS fix subscription
- res = _uavcan_sub_status.start(FixCbBinder(this, &UavcanGnssReceiver::gnss_fix_sub_cb));
+ int res = _sub_fix.start(FixCbBinder(this, &UavcanGnssBridge::gnss_fix_sub_cb));
if (res < 0)
{
warnx("GNSS fix sub failed %i", res);
return res;
}
+ return res;
+}
- // Clear the uORB GPS report
- memset(&_report, 0, sizeof(_report));
+unsigned UavcanGnssBridge::get_num_redundant_channels() const
+{
+ return (_receiver_node_id < 0) ? 0 : 1;
+}
- return res;
+void UavcanGnssBridge::print_status() const
+{
+ printf("RX errors: %d, receiver node id: ", _sub_fix.getFailureCount());
+ if (_receiver_node_id < 0) {
+ printf("N/A\n");
+ } else {
+ printf("%d\n", _receiver_node_id);
+ }
}
-void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix> &msg)
+void UavcanGnssBridge::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix> &msg)
{
- _report.timestamp_position = hrt_absolute_time();
- _report.lat = msg.lat_1e7;
- _report.lon = msg.lon_1e7;
- _report.alt = msg.alt_1e2 * MM_PER_CM; // Convert from centimeter (1e2) to millimeters (1e3)
+ // This bridge does not support redundant GNSS receivers yet.
+ if (_receiver_node_id < 0) {
+ _receiver_node_id = msg.getSrcNodeID().get();
+ warnx("GNSS receiver node ID: %d", _receiver_node_id);
+ } else {
+ if (_receiver_node_id != msg.getSrcNodeID().get()) {
+ return; // This GNSS receiver is the redundant one, ignore it.
+ }
+ }
+
+ auto report = ::vehicle_gps_position_s();
+
+ report.timestamp_position = hrt_absolute_time();
+ report.lat = msg.latitude_deg_1e8 / 10;
+ report.lon = msg.longitude_deg_1e8 / 10;
+ report.alt = msg.height_msl_mm;
- _report.timestamp_variance = _report.timestamp_position;
+ report.timestamp_variance = report.timestamp_position;
// Check if the msg contains valid covariance information
@@ -90,19 +110,19 @@ void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uav
// Horizontal position uncertainty
const float horizontal_pos_variance = math::max(pos_cov[0], pos_cov[4]);
- _report.eph = (horizontal_pos_variance > 0) ? sqrtf(horizontal_pos_variance) : -1.0F;
+ report.eph = (horizontal_pos_variance > 0) ? sqrtf(horizontal_pos_variance) : -1.0F;
// Vertical position uncertainty
- _report.epv = (pos_cov[8] > 0) ? sqrtf(pos_cov[8]) : -1.0F;
+ report.epv = (pos_cov[8] > 0) ? sqrtf(pos_cov[8]) : -1.0F;
} else {
- _report.eph = -1.0F;
- _report.epv = -1.0F;
+ report.eph = -1.0F;
+ report.epv = -1.0F;
}
if (valid_velocity_covariance) {
float vel_cov[9];
msg.velocity_covariance.unpackSquareMatrix(vel_cov);
- _report.s_variance_m_s = math::max(math::max(vel_cov[0], vel_cov[4]), vel_cov[8]);
+ report.s_variance_m_s = math::max(math::max(vel_cov[0], vel_cov[4]), vel_cov[8]);
/* There is a nonlinear relationship between the velocity vector and the heading.
* Use Jacobian to transform velocity covariance to heading covariance
@@ -118,36 +138,36 @@ void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uav
float vel_e = msg.ned_velocity[1];
float vel_n_sq = vel_n * vel_n;
float vel_e_sq = vel_e * vel_e;
- _report.c_variance_rad =
+ report.c_variance_rad =
(vel_e_sq * vel_cov[0] +
-2 * vel_n * vel_e * vel_cov[1] + // Covariance matrix is symmetric
vel_n_sq* vel_cov[4]) / ((vel_n_sq + vel_e_sq) * (vel_n_sq + vel_e_sq));
} else {
- _report.s_variance_m_s = -1.0F;
- _report.c_variance_rad = -1.0F;
+ report.s_variance_m_s = -1.0F;
+ report.c_variance_rad = -1.0F;
}
- _report.fix_type = msg.status;
+ report.fix_type = msg.status;
- _report.timestamp_velocity = _report.timestamp_position;
- _report.vel_n_m_s = msg.ned_velocity[0];
- _report.vel_e_m_s = msg.ned_velocity[1];
- _report.vel_d_m_s = msg.ned_velocity[2];
- _report.vel_m_s = sqrtf(_report.vel_n_m_s * _report.vel_n_m_s + _report.vel_e_m_s * _report.vel_e_m_s + _report.vel_d_m_s * _report.vel_d_m_s);
- _report.cog_rad = atan2f(_report.vel_e_m_s, _report.vel_n_m_s);
- _report.vel_ned_valid = true;
+ report.timestamp_velocity = report.timestamp_position;
+ report.vel_n_m_s = msg.ned_velocity[0];
+ report.vel_e_m_s = msg.ned_velocity[1];
+ report.vel_d_m_s = msg.ned_velocity[2];
+ report.vel_m_s = sqrtf(report.vel_n_m_s * report.vel_n_m_s + report.vel_e_m_s * report.vel_e_m_s + report.vel_d_m_s * report.vel_d_m_s);
+ report.cog_rad = atan2f(report.vel_e_m_s, report.vel_n_m_s);
+ report.vel_ned_valid = true;
- _report.timestamp_time = _report.timestamp_position;
- _report.time_gps_usec = uavcan::UtcTime(msg.gnss_timestamp).toUSec(); // Convert to microseconds
+ report.timestamp_time = report.timestamp_position;
+ report.time_gps_usec = uavcan::UtcTime(msg.gnss_timestamp).toUSec(); // Convert to microseconds
- _report.satellites_used = msg.sats_used;
+ report.satellites_used = msg.sats_used;
if (_report_pub > 0) {
- orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report);
+ orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &report);
} else {
- _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report);
+ _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &report);
}
}
diff --git a/src/modules/uavcan/gnss_receiver.hpp b/src/modules/uavcan/sensors/gnss.hpp
index 18df8da2f..e8466b401 100644
--- a/src/modules/uavcan/gnss_receiver.hpp
+++ b/src/modules/uavcan/sensors/gnss.hpp
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file gnss_receiver.hpp
+ * @file gnss.hpp
*
* UAVCAN --> ORB bridge for GNSS messages:
* uavcan.equipment.gnss.Fix
@@ -51,12 +51,22 @@
#include <uavcan/uavcan.hpp>
#include <uavcan/equipment/gnss/Fix.hpp>
-class UavcanGnssReceiver
+#include "sensor_bridge.hpp"
+
+class UavcanGnssBridge : public IUavcanSensorBridge
{
public:
- UavcanGnssReceiver(uavcan::INode& node);
+ static const char *const NAME;
+
+ UavcanGnssBridge(uavcan::INode& node);
+
+ const char *get_name() const override { return NAME; }
+
+ int init() override;
- int init();
+ unsigned get_num_redundant_channels() const override;
+
+ void print_status() const override;
private:
/**
@@ -64,21 +74,14 @@ private:
*/
void gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix> &msg);
-
- typedef uavcan::MethodBinder<UavcanGnssReceiver*,
- void (UavcanGnssReceiver::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix>&)>
+ typedef uavcan::MethodBinder<UavcanGnssBridge*,
+ void (UavcanGnssBridge::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix>&)>
FixCbBinder;
- /*
- * libuavcan related things
- */
- uavcan::INode &_node;
- uavcan::Subscriber<uavcan::equipment::gnss::Fix, FixCbBinder> _uavcan_sub_status;
+ uavcan::INode &_node;
+ uavcan::Subscriber<uavcan::equipment::gnss::Fix, FixCbBinder> _sub_fix;
+ int _receiver_node_id = -1;
- /*
- * uORB
- */
- struct vehicle_gps_position_s _report; ///< uORB topic for gnss position
- orb_advert_t _report_pub; ///< uORB pub for gnss position
+ orb_advert_t _report_pub; ///< uORB pub for gnss position
};
diff --git a/src/modules/uavcan/sensors/mag.cpp b/src/modules/uavcan/sensors/mag.cpp
new file mode 100644
index 000000000..8e6a9a22f
--- /dev/null
+++ b/src/modules/uavcan/sensors/mag.cpp
@@ -0,0 +1,123 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+#include "mag.hpp"
+
+static const orb_id_t MAG_TOPICS[3] = {
+ ORB_ID(sensor_mag0),
+ ORB_ID(sensor_mag1),
+ ORB_ID(sensor_mag2)
+};
+
+const char *const UavcanMagnetometerBridge::NAME = "mag";
+
+UavcanMagnetometerBridge::UavcanMagnetometerBridge(uavcan::INode& node) :
+UavcanCDevSensorBridgeBase("uavcan_mag", "/dev/uavcan/mag", MAG_DEVICE_PATH, MAG_TOPICS),
+_sub_mag(node)
+{
+ _scale.x_scale = 1.0F;
+ _scale.y_scale = 1.0F;
+ _scale.z_scale = 1.0F;
+}
+
+int UavcanMagnetometerBridge::init()
+{
+ int res = device::CDev::init();
+ if (res < 0) {
+ return res;
+ }
+
+ res = _sub_mag.start(MagCbBinder(this, &UavcanMagnetometerBridge::mag_sub_cb));
+ if (res < 0) {
+ log("failed to start uavcan sub: %d", res);
+ return res;
+ }
+ return 0;
+}
+
+int UavcanMagnetometerBridge::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+ case MAGIOCSSCALE: {
+ std::memcpy(&_scale, reinterpret_cast<const void*>(arg), sizeof(_scale));
+ return 0;
+ }
+ case MAGIOCGSCALE: {
+ std::memcpy(reinterpret_cast<void*>(arg), &_scale, sizeof(_scale));
+ return 0;
+ }
+ case MAGIOCSELFTEST: {
+ return 0; // Nothing to do
+ }
+ case MAGIOCGEXTERNAL: {
+ return 0; // We don't want anyone to transform the coordinate frame, so we declare it onboard
+ }
+ case MAGIOCSSAMPLERATE: {
+ return 0; // Pretend that this stuff is supported to keep the sensor app happy
+ }
+ case MAGIOCCALIBRATE:
+ case MAGIOCGSAMPLERATE:
+ case MAGIOCSRANGE:
+ case MAGIOCGRANGE:
+ case MAGIOCSLOWPASS:
+ case MAGIOCEXSTRAP:
+ case MAGIOCGLOWPASS: {
+ return -EINVAL;
+ }
+ default: {
+ return CDev::ioctl(filp, cmd, arg);
+ }
+ }
+}
+
+void UavcanMagnetometerBridge::mag_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer> &msg)
+{
+ auto report = ::mag_report();
+
+ report.range_ga = 1.3F; // Arbitrary number, doesn't really mean anything
+
+ report.timestamp = msg.getUtcTimestamp().toUSec();
+ if (report.timestamp == 0) {
+ report.timestamp = msg.getMonotonicTimestamp().toUSec();
+ }
+
+ report.x = (msg.magnetic_field[0] - _scale.x_offset) * _scale.x_scale;
+ report.y = (msg.magnetic_field[1] - _scale.y_offset) * _scale.y_scale;
+ report.z = (msg.magnetic_field[2] - _scale.z_offset) * _scale.z_scale;
+
+ publish(msg.getSrcNodeID().get(), &report);
+}
diff --git a/src/modules/uavcan/sensors/mag.hpp b/src/modules/uavcan/sensors/mag.hpp
new file mode 100644
index 000000000..6d413a8f7
--- /dev/null
+++ b/src/modules/uavcan/sensors/mag.hpp
@@ -0,0 +1,68 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+#pragma once
+
+#include "sensor_bridge.hpp"
+#include <drivers/drv_mag.h>
+
+#include <uavcan/equipment/ahrs/Magnetometer.hpp>
+
+class UavcanMagnetometerBridge : public UavcanCDevSensorBridgeBase
+{
+public:
+ static const char *const NAME;
+
+ UavcanMagnetometerBridge(uavcan::INode& node);
+
+ const char *get_name() const override { return NAME; }
+
+ int init() override;
+
+private:
+ int ioctl(struct file *filp, int cmd, unsigned long arg) override;
+
+ void mag_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer> &msg);
+
+ typedef uavcan::MethodBinder<UavcanMagnetometerBridge*,
+ void (UavcanMagnetometerBridge::*)
+ (const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer>&)>
+ MagCbBinder;
+
+ uavcan::Subscriber<uavcan::equipment::ahrs::Magnetometer, MagCbBinder> _sub_mag;
+ mag_scale _scale = {};
+};
diff --git a/src/modules/uavcan/sensors/sensor_bridge.cpp b/src/modules/uavcan/sensors/sensor_bridge.cpp
new file mode 100644
index 000000000..9608ce680
--- /dev/null
+++ b/src/modules/uavcan/sensors/sensor_bridge.cpp
@@ -0,0 +1,158 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+#include "sensor_bridge.hpp"
+#include <cassert>
+
+#include "gnss.hpp"
+#include "mag.hpp"
+#include "baro.hpp"
+
+/*
+ * IUavcanSensorBridge
+ */
+void IUavcanSensorBridge::make_all(uavcan::INode &node, List<IUavcanSensorBridge*> &list)
+{
+ list.add(new UavcanBarometerBridge(node));
+ list.add(new UavcanMagnetometerBridge(node));
+ list.add(new UavcanGnssBridge(node));
+}
+
+/*
+ * UavcanCDevSensorBridgeBase
+ */
+UavcanCDevSensorBridgeBase::~UavcanCDevSensorBridgeBase()
+{
+ for (unsigned i = 0; i < _max_channels; i++) {
+ if (_channels[i].node_id >= 0) {
+ (void)unregister_class_devname(_class_devname, _channels[i].class_instance);
+ }
+ }
+ delete [] _orb_topics;
+ delete [] _channels;
+}
+
+void UavcanCDevSensorBridgeBase::publish(const int node_id, const void *report)
+{
+ assert(report != nullptr);
+
+ Channel *channel = nullptr;
+
+ // Checking if such channel already exists
+ for (unsigned i = 0; i < _max_channels; i++) {
+ if (_channels[i].node_id == node_id) {
+ channel = _channels + i;
+ break;
+ }
+ }
+
+ // No such channel - try to create one
+ if (channel == nullptr) {
+ if (_out_of_channels) {
+ return; // Give up immediately - saves some CPU time
+ }
+
+ log("adding channel %d...", node_id);
+
+ // Search for the first free channel
+ for (unsigned i = 0; i < _max_channels; i++) {
+ if (_channels[i].node_id < 0) {
+ channel = _channels + i;
+ break;
+ }
+ }
+
+ // No free channels left
+ if (channel == nullptr) {
+ _out_of_channels = true;
+ log("out of channels");
+ return;
+ }
+
+ // Ask the CDev helper which class instance we can take
+ const int class_instance = register_class_devname(_class_devname);
+ if (class_instance < 0 || class_instance >= int(_max_channels)) {
+ _out_of_channels = true;
+ log("out of class instances");
+ (void)unregister_class_devname(_class_devname, class_instance);
+ return;
+ }
+
+ // Publish to the appropriate topic, abort on failure
+ channel->orb_id = _orb_topics[class_instance];
+ channel->node_id = node_id;
+ channel->class_instance = class_instance;
+
+ channel->orb_advert = orb_advertise(channel->orb_id, report);
+ if (channel->orb_advert < 0) {
+ log("ADVERTISE FAILED");
+ (void)unregister_class_devname(_class_devname, class_instance);
+ *channel = Channel();
+ return;
+ }
+
+ log("channel %d class instance %d ok", channel->node_id, channel->class_instance);
+ }
+ assert(channel != nullptr);
+
+ (void)orb_publish(channel->orb_id, channel->orb_advert, report);
+}
+
+unsigned UavcanCDevSensorBridgeBase::get_num_redundant_channels() const
+{
+ unsigned out = 0;
+ for (unsigned i = 0; i < _max_channels; i++) {
+ if (_channels[i].node_id >= 0) {
+ out += 1;
+ }
+ }
+ return out;
+}
+
+void UavcanCDevSensorBridgeBase::print_status() const
+{
+ printf("devname: %s\n", _class_devname);
+
+ for (unsigned i = 0; i < _max_channels; i++) {
+ if (_channels[i].node_id >= 0) {
+ printf("channel %d: node id %d --> class instance %d\n",
+ i, _channels[i].node_id, _channels[i].class_instance);
+ } else {
+ printf("channel %d: empty\n", i);
+ }
+ }
+}
diff --git a/src/modules/uavcan/sensors/sensor_bridge.hpp b/src/modules/uavcan/sensors/sensor_bridge.hpp
new file mode 100644
index 000000000..1316f7ecc
--- /dev/null
+++ b/src/modules/uavcan/sensors/sensor_bridge.hpp
@@ -0,0 +1,131 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+#pragma once
+
+#include <containers/List.hpp>
+#include <uavcan/uavcan.hpp>
+#include <drivers/device/device.h>
+#include <drivers/drv_orb_dev.h>
+
+/**
+ * A sensor bridge class must implement this interface.
+ */
+class IUavcanSensorBridge : uavcan::Noncopyable, public ListNode<IUavcanSensorBridge*>
+{
+public:
+ static constexpr unsigned MAX_NAME_LEN = 20;
+
+ virtual ~IUavcanSensorBridge() { }
+
+ /**
+ * Returns ASCII name of the bridge.
+ */
+ virtual const char *get_name() const = 0;
+
+ /**
+ * Starts the bridge.
+ * @return Non-negative value on success, negative on error.
+ */
+ virtual int init() = 0;
+
+ /**
+ * Returns number of active redundancy channels.
+ */
+ virtual unsigned get_num_redundant_channels() const = 0;
+
+ /**
+ * Prints current status in a human readable format to stdout.
+ */
+ virtual void print_status() const = 0;
+
+ /**
+ * Sensor bridge factory.
+ * Creates a bridge object by its ASCII name, e.g. "gnss", "mag".
+ * @return nullptr if such bridge can't be created.
+ */
+ static void make_all(uavcan::INode &node, List<IUavcanSensorBridge*> &list);
+};
+
+/**
+ * This is the base class for redundant sensors with an independent ORB topic per each redundancy channel.
+ * For example, sensor_mag0, sensor_mag1, etc.
+ */
+class UavcanCDevSensorBridgeBase : public IUavcanSensorBridge, public device::CDev
+{
+ struct Channel
+ {
+ int node_id = -1;
+ orb_id_t orb_id = nullptr;
+ orb_advert_t orb_advert = -1;
+ int class_instance = -1;
+ };
+
+ const unsigned _max_channels;
+ const char *const _class_devname;
+ orb_id_t *const _orb_topics;
+ Channel *const _channels;
+ bool _out_of_channels = false;
+
+protected:
+ template <unsigned MaxChannels>
+ UavcanCDevSensorBridgeBase(const char *name, const char *devname, const char *class_devname,
+ const orb_id_t (&orb_topics)[MaxChannels]) :
+ device::CDev(name, devname),
+ _max_channels(MaxChannels),
+ _class_devname(class_devname),
+ _orb_topics(new orb_id_t[MaxChannels]),
+ _channels(new Channel[MaxChannels])
+ {
+ memcpy(_orb_topics, orb_topics, sizeof(orb_id_t) * MaxChannels);
+ }
+
+ /**
+ * Sends one measurement into appropriate ORB topic.
+ * New redundancy channels will be registered automatically.
+ * @param node_id Sensor's Node ID
+ * @param report Pointer to ORB message object
+ */
+ void publish(const int node_id, const void *report);
+
+public:
+ virtual ~UavcanCDevSensorBridgeBase();
+
+ unsigned get_num_redundant_channels() const override;
+
+ void print_status() const override;
+};
diff --git a/src/modules/uavcan/uavcan_clock.cpp b/src/modules/uavcan/uavcan_clock.cpp
index e41d5f953..fe8ba406a 100644
--- a/src/modules/uavcan/uavcan_clock.cpp
+++ b/src/modules/uavcan/uavcan_clock.cpp
@@ -62,6 +62,8 @@ void adjustUtc(uavcan::UtcDuration adjustment)
(void)adjustment;
}
+uavcan::uint64_t getUtcUSecFromCanInterrupt();
+
uavcan::uint64_t getUtcUSecFromCanInterrupt()
{
return 0;
diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp
index 27e77e9c5..a8485ee44 100644
--- a/src/modules/uavcan/uavcan_main.cpp
+++ b/src/modules/uavcan/uavcan_main.cpp
@@ -38,7 +38,11 @@
#include <fcntl.h>
#include <systemlib/err.h>
#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
#include <systemlib/mixer/mixer.h>
+#include <systemlib/board_serial.h>
+#include <systemlib/scheduling_priorities.h>
+#include <version/version.h>
#include <arch/board/board.h>
#include <arch/chip/chip.h>
@@ -63,16 +67,18 @@ UavcanNode *UavcanNode::_instance;
UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) :
CDev("uavcan", UAVCAN_DEVICE_PATH),
_node(can_driver, system_clock),
- _esc_controller(_node),
- _gnss_receiver(_node)
+ _node_mutex(),
+ _esc_controller(_node)
{
_control_topics[0] = ORB_ID(actuator_controls_0);
_control_topics[1] = ORB_ID(actuator_controls_1);
_control_topics[2] = ORB_ID(actuator_controls_2);
_control_topics[3] = ORB_ID(actuator_controls_3);
- // memset(_controls, 0, sizeof(_controls));
- // memset(_poll_fds, 0, sizeof(_poll_fds));
+ const int res = pthread_mutex_init(&_node_mutex, nullptr);
+ if (res < 0) {
+ std::abort();
+ }
}
UavcanNode::~UavcanNode()
@@ -97,10 +103,18 @@ UavcanNode::~UavcanNode()
}
/* clean up the alternate device node */
- // unregister_driver(PWM_OUTPUT_DEVICE_PATH);
+ // unregister_driver(PWM_OUTPUT_DEVICE_PATH);
::close(_armed_sub);
+ // Removing the sensor bridges
+ auto br = _sensor_bridges.getHead();
+ while (br != nullptr) {
+ auto next = br->getSibling();
+ delete br;
+ br = next;
+ }
+
_instance = nullptr;
}
@@ -162,7 +176,7 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate)
* Start the task. Normally it should never exit.
*/
static auto run_trampoline = [](int, char *[]) {return UavcanNode::_instance->run();};
- _instance->_task = task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, StackSize,
+ _instance->_task = task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_ACTUATOR_OUTPUTS, StackSize,
static_cast<main_t>(run_trampoline), nullptr);
if (_instance->_task < 0) {
@@ -173,37 +187,76 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate)
return OK;
}
+void UavcanNode::fill_node_info()
+{
+ /* software version */
+ uavcan::protocol::SoftwareVersion swver;
+
+ // Extracting the first 8 hex digits of FW_GIT and converting them to int
+ char fw_git_short[9] = {};
+ std::memmove(fw_git_short, FW_GIT, 8);
+ assert(fw_git_short[8] == '\0');
+ char *end = nullptr;
+ swver.vcs_commit = std::strtol(fw_git_short, &end, 16);
+ swver.optional_field_mask |= swver.OPTIONAL_FIELD_MASK_VCS_COMMIT;
+
+ warnx("SW version vcs_commit: 0x%08x", unsigned(swver.vcs_commit));
+
+ _node.setSoftwareVersion(swver);
+
+ /* hardware version */
+ uavcan::protocol::HardwareVersion hwver;
+
+ if (!std::strncmp(HW_ARCH, "PX4FMU_V1", 9)) {
+ hwver.major = 1;
+ } else if (!std::strncmp(HW_ARCH, "PX4FMU_V2", 9)) {
+ hwver.major = 2;
+ } else {
+ ; // All other values of HW_ARCH resolve to zero
+ }
+
+ uint8_t udid[12] = {}; // Someone seems to love magic numbers
+ get_board_serial(udid);
+ uavcan::copy(udid, udid + sizeof(udid), hwver.unique_id.begin());
+
+ _node.setHardwareVersion(hwver);
+}
+
int UavcanNode::init(uavcan::NodeID node_id)
{
int ret = -1;
- /* do regular cdev init */
+ // Do regular cdev init
ret = CDev::init();
- if (ret != OK)
- return ret;
-
- ret = _esc_controller.init();
- if (ret < 0)
+ if (ret != OK) {
return ret;
+ }
- ret = _gnss_receiver.init();
- if (ret < 0)
- return ret;
+ _node.setName("org.pixhawk.pixhawk");
- uavcan::protocol::SoftwareVersion swver;
- swver.major = 12; // TODO fill version info
- swver.minor = 34;
- _node.setSoftwareVersion(swver);
+ _node.setNodeID(node_id);
- uavcan::protocol::HardwareVersion hwver;
- hwver.major = 42; // TODO fill version info
- hwver.minor = 42;
- _node.setHardwareVersion(hwver);
+ fill_node_info();
- _node.setName("org.pixhawk"); // Huh?
+ // Actuators
+ ret = _esc_controller.init();
+ if (ret < 0) {
+ return ret;
+ }
- _node.setNodeID(node_id);
+ // Sensor bridges
+ IUavcanSensorBridge::make_all(_node, _sensor_bridges);
+ auto br = _sensor_bridges.getHead();
+ while (br != nullptr) {
+ ret = br->init();
+ if (ret < 0) {
+ warnx("cannot init sensor bridge '%s' (%d)", br->get_name(), ret);
+ return ret;
+ }
+ warnx("sensor bridge '%s' init ok", br->get_name());
+ br = br->getSibling();
+ }
return _node.start();
}
@@ -218,12 +271,13 @@ void UavcanNode::node_spin_once()
int UavcanNode::run()
{
+ (void)pthread_mutex_lock(&_node_mutex);
+
const unsigned PollTimeoutMs = 50;
// XXX figure out the output count
_output_count = 2;
-
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
actuator_outputs_s outputs;
@@ -243,25 +297,32 @@ int UavcanNode::run()
_node.setStatusOk();
- while (!_task_should_exit) {
+ /*
+ * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error).
+ * Please note that with such multiplexing it is no longer possible to rely only on
+ * the value returned from poll() to detect whether actuator control has timed out or not.
+ * Instead, all ORB events need to be checked individually (see below).
+ */
+ _poll_fds_num = 0;
+ _poll_fds[_poll_fds_num] = ::pollfd();
+ _poll_fds[_poll_fds_num].fd = busevent_fd;
+ _poll_fds[_poll_fds_num].events = POLLIN;
+ _poll_fds_num += 1;
+ while (!_task_should_exit) {
+ // update actuator controls subscriptions if needed
if (_groups_subscribed != _groups_required) {
subscribe();
_groups_subscribed = _groups_required;
- /*
- * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error).
- * Please note that with such multiplexing it is no longer possible to rely only on
- * the value returned from poll() to detect whether actuator control has timed out or not.
- * Instead, all ORB events need to be checked individually (see below).
- */
- _poll_fds[_poll_fds_num] = ::pollfd();
- _poll_fds[_poll_fds_num].fd = busevent_fd;
- _poll_fds[_poll_fds_num].events = POLLIN;
- _poll_fds_num += 1;
}
+ // Mutex is unlocked while the thread is blocked on IO multiplexing
+ (void)pthread_mutex_unlock(&_node_mutex);
+
const int poll_ret = ::poll(_poll_fds, _poll_fds_num, PollTimeoutMs);
+ (void)pthread_mutex_lock(&_node_mutex);
+
node_spin_once(); // Non-blocking
// this would be bad...
@@ -271,7 +332,7 @@ int UavcanNode::run()
} else {
// get controls for required topics
bool controls_updated = false;
- unsigned poll_id = 0;
+ unsigned poll_id = 1;
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
if (_control_subs[i] > 0) {
if (_poll_fds[poll_id].revents & POLLIN) {
@@ -282,12 +343,7 @@ int UavcanNode::run()
}
}
- if (!controls_updated) {
- // timeout: no control data, switch to failsafe values
- // XXX trigger failsafe
- }
-
- //can we mix?
+ // can we mix?
if (controls_updated && (_mixers != nullptr)) {
// XXX one output group has 8 outputs max,
@@ -326,7 +382,6 @@ int UavcanNode::run()
// Output to the bus
_esc_controller.update_outputs(outputs.output, outputs.noutputs);
}
-
}
// Check arming state
@@ -350,10 +405,7 @@ int UavcanNode::run()
}
int
-UavcanNode::control_callback(uintptr_t handle,
- uint8_t control_group,
- uint8_t control_index,
- float &input)
+UavcanNode::control_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input)
{
const actuator_controls_s *controls = (actuator_controls_s *)handle;
@@ -387,7 +439,8 @@ UavcanNode::subscribe()
// Subscribe/unsubscribe to required actuator control groups
uint32_t sub_groups = _groups_required & ~_groups_subscribed;
uint32_t unsub_groups = _groups_subscribed & ~_groups_required;
- _poll_fds_num = 0;
+ // the first fd used by CAN
+ _poll_fds_num = 1;
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
if (sub_groups & (1 << i)) {
warnx("subscribe to actuator_controls_%d", i);
@@ -493,8 +546,23 @@ UavcanNode::print_info()
warnx("not running, start first");
}
- warnx("groups: sub: %u / req: %u / fds: %u", (unsigned)_groups_subscribed, (unsigned)_groups_required, _poll_fds_num);
- warnx("mixer: %s", (_mixers == nullptr) ? "FAIL" : "OK");
+ (void)pthread_mutex_lock(&_node_mutex);
+
+ // ESC mixer status
+ printf("ESC actuators control groups: sub: %u / req: %u / fds: %u\n",
+ (unsigned)_groups_subscribed, (unsigned)_groups_required, _poll_fds_num);
+ printf("ESC mixer: %s\n", (_mixers == nullptr) ? "NONE" : "OK");
+
+ // Sensor bridges
+ auto br = _sensor_bridges.getHead();
+ while (br != nullptr) {
+ printf("Sensor '%s':\n", br->get_name());
+ br->print_status();
+ printf("\n");
+ br = br->getSibling();
+ }
+
+ (void)pthread_mutex_unlock(&_node_mutex);
}
/*
@@ -502,79 +570,57 @@ UavcanNode::print_info()
*/
static void print_usage()
{
- warnx("usage: uavcan start <node_id> [can_bitrate]");
+ warnx("usage: \n"
+ "\tuavcan {start|status|stop}");
}
extern "C" __EXPORT int uavcan_main(int argc, char *argv[]);
int uavcan_main(int argc, char *argv[])
{
- constexpr unsigned DEFAULT_CAN_BITRATE = 1000000;
-
if (argc < 2) {
print_usage();
::exit(1);
}
if (!std::strcmp(argv[1], "start")) {
- if (argc < 3) {
- print_usage();
- ::exit(1);
+ if (UavcanNode::instance()) {
+ errx(1, "already started");
}
- /*
- * Node ID
- */
- const int node_id = atoi(argv[2]);
+ // Node ID
+ int32_t node_id = 0;
+ (void)param_get(param_find("UAVCAN_NODE_ID"), &node_id);
if (node_id < 0 || node_id > uavcan::NodeID::Max || !uavcan::NodeID(node_id).isUnicast()) {
warnx("Invalid Node ID %i", node_id);
::exit(1);
}
- /*
- * CAN bitrate
- */
- unsigned bitrate = 0;
-
- if (argc > 3) {
- bitrate = atol(argv[3]);
- }
-
- if (bitrate <= 0) {
- bitrate = DEFAULT_CAN_BITRATE;
- }
-
- if (UavcanNode::instance()) {
- errx(1, "already started");
- }
+ // CAN bitrate
+ int32_t bitrate = 0;
+ (void)param_get(param_find("UAVCAN_BITRATE"), &bitrate);
- /*
- * Start
- */
+ // Start
warnx("Node ID %u, bitrate %u", node_id, bitrate);
return UavcanNode::start(node_id, bitrate);
-
}
/* commands below require the app to be started */
- UavcanNode *inst = UavcanNode::instance();
+ UavcanNode *const inst = UavcanNode::instance();
if (!inst) {
errx(1, "application not running");
}
if (!std::strcmp(argv[1], "status") || !std::strcmp(argv[1], "info")) {
-
- inst->print_info();
- return OK;
+ inst->print_info();
+ ::exit(0);
}
if (!std::strcmp(argv[1], "stop")) {
-
- delete inst;
- inst = nullptr;
- return OK;
+ delete inst;
+ ::exit(0);
}
print_usage();
diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp
index 443525379..be7db9741 100644
--- a/src/modules/uavcan/uavcan_main.hpp
+++ b/src/modules/uavcan/uavcan_main.hpp
@@ -42,8 +42,8 @@
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
-#include "esc_controller.hpp"
-#include "gnss_receiver.hpp"
+#include "actuators/esc.hpp"
+#include "sensors/sensor_bridge.hpp"
/**
* @file uavcan_main.hpp
@@ -77,12 +77,10 @@ public:
static int start(uavcan::NodeID node_id, uint32_t bitrate);
- Node& getNode() { return _node; }
+ Node& get_node() { return _node; }
- static int control_callback(uintptr_t handle,
- uint8_t control_group,
- uint8_t control_index,
- float &input);
+ // TODO: move the actuator mixing stuff into the ESC controller class
+ static int control_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input);
void subscribe();
@@ -94,6 +92,7 @@ public:
static UavcanNode* instance() { return _instance; }
private:
+ void fill_node_info();
int init(uavcan::NodeID node_id);
void node_spin_once();
int run();
@@ -108,8 +107,11 @@ private:
static UavcanNode *_instance; ///< singleton pointer
Node _node; ///< library instance
+ pthread_mutex_t _node_mutex;
+
UavcanEscController _esc_controller;
- UavcanGnssReceiver _gnss_receiver;
+
+ List<IUavcanSensorBridge*> _sensor_bridges; ///< List of active sensor bridges
MixerGroup *_mixers = nullptr;
diff --git a/src/modules/uavcan/uavcan_params.c b/src/modules/uavcan/uavcan_params.c
new file mode 100644
index 000000000..e6ea8a8fb
--- /dev/null
+++ b/src/modules/uavcan/uavcan_params.c
@@ -0,0 +1,73 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+#include <nuttx/config.h>
+#include <systemlib/param/param.h>
+
+/**
+ * Enable UAVCAN.
+ *
+ * Enables support for UAVCAN-interfaced actuators and sensors.
+ *
+ * @min 0
+ * @max 1
+ * @group UAVCAN
+ */
+PARAM_DEFINE_INT32(UAVCAN_ENABLE, 0);
+
+/**
+ * UAVCAN Node ID.
+ *
+ * Read the specs at http://uavcan.org to learn more about Node ID.
+ *
+ * @min 1
+ * @max 125
+ * @group UAVCAN
+ */
+PARAM_DEFINE_INT32(UAVCAN_NODE_ID, 1);
+
+/**
+ * UAVCAN CAN bus bitrate.
+ *
+ * @min 20000
+ * @max 1000000
+ * @group UAVCAN
+ */
+PARAM_DEFINE_INT32(UAVCAN_BITRATE, 1000000);
+
+
+
diff --git a/src/modules/unit_test/module.mk b/src/modules/unit_test/module.mk
index f00b0f592..5000790a5 100644
--- a/src/modules/unit_test/module.mk
+++ b/src/modules/unit_test/module.mk
@@ -37,3 +37,4 @@
SRCS = unit_test.cpp
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/unit_test/unit_test.cpp b/src/modules/unit_test/unit_test.cpp
index 02d1af481..b7568ce3a 100644
--- a/src/modules/unit_test/unit_test.cpp
+++ b/src/modules/unit_test/unit_test.cpp
@@ -36,7 +36,11 @@
#include <systemlib/err.h>
-UnitTest::UnitTest()
+UnitTest::UnitTest() :
+ _tests_run(0),
+ _tests_failed(0),
+ _tests_passed(0),
+ _assertions(0)
{
}
@@ -44,15 +48,22 @@ UnitTest::~UnitTest()
{
}
-void UnitTest::printResults(void)
+void UnitTest::print_results(void)
{
- warnx(mu_tests_failed() ? "SOME TESTS FAILED" : "ALL TESTS PASSED");
- warnx(" Tests passed : %d", mu_tests_passed());
- warnx(" Tests failed : %d", mu_tests_failed());
- warnx(" Assertions : %d", mu_assertion());
+ warnx(_tests_failed ? "SOME TESTS FAILED" : "ALL TESTS PASSED");
+ warnx(" Tests passed : %d", _tests_passed);
+ warnx(" Tests failed : %d", _tests_failed);
+ warnx(" Assertions : %d", _assertions);
}
-void UnitTest::printAssert(const char* msg, const char* test, const char* file, int line)
+/// @brief Used internally to the ut_assert macro to print assert failures.
+void UnitTest::_print_assert(const char* msg, const char* test, const char* file, int line)
{
- warnx("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
+ warnx("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
+}
+
+/// @brief Used internally to the ut_compare macro to print assert failures.
+void UnitTest::_print_compare(const char* msg, const char *v1_text, int v1, const char *v2_text, int v2, const char* file, int line)
+{
+ warnx("Compare failed: %s - (%s:%d) (%s:%d) (%s:%d)", msg, v1_text, v1, v2_text, v2, file, line);
}
diff --git a/src/modules/unit_test/unit_test.h b/src/modules/unit_test/unit_test.h
index 32eb8c308..8ed4efadf 100644
--- a/src/modules/unit_test/unit_test.h
+++ b/src/modules/unit_test/unit_test.h
@@ -37,50 +37,85 @@
#include <systemlib/err.h>
+/// @brief Base class to be used for unit tests.
class __EXPORT UnitTest
{
-
public:
-#define INLINE_GLOBAL(type,func) inline type& func() { static type x; return x; }
-
-INLINE_GLOBAL(int, mu_tests_run)
-INLINE_GLOBAL(int, mu_tests_failed)
-INLINE_GLOBAL(int, mu_tests_passed)
-INLINE_GLOBAL(int, mu_assertion)
-INLINE_GLOBAL(int, mu_line)
-INLINE_GLOBAL(const char*, mu_last_test)
UnitTest();
- virtual ~UnitTest();
-
- virtual void runTests(void) = 0;
- void printResults(void);
-
- void printAssert(const char* msg, const char* test, const char* file, int line);
-
-#define ut_assert(message, test) \
- do { \
- if (!(test)) { \
- printAssert(message, #test, __FILE__, __LINE__); \
- return false; \
- } else { \
- mu_assertion()++; \
- } \
- } while (0)
-
-#define ut_run_test(test) \
- do { \
- warnx("RUNNING TEST: %s", #test); \
- mu_tests_run()++; \
- if (!test()) { \
- warnx("TEST FAILED: %s", #test); \
- mu_tests_failed()++; \
- } else { \
- warnx("TEST PASSED: %s", #test); \
- mu_tests_passed()++; \
- } \
- } while (0)
+ virtual ~UnitTest();
+
+ /// @brief Override to run your unit tests. Unit tests should be called using ut_run_test macro.
+ /// @return true: all unit tests succeeded, false: one or more unit tests failed
+ virtual bool run_tests(void) = 0;
+
+ /// @brief Prints results from running of unit tests.
+ void print_results(void);
+
+/// @brief Macro to create a function which will run a unit test class and print results.
+#define ut_declare_test(test_function, test_class) \
+ bool test_function(void) \
+ { \
+ test_class* test = new test_class(); \
+ bool success = test->run_tests(); \
+ test->print_results(); \
+ return success; \
+ }
+
+protected:
+
+/// @brief Runs a single unit test. Unit tests must have the function signature of bool test(void). The unit
+/// test should return true if it succeeded, false for fail.
+#define ut_run_test(test) \
+ do { \
+ warnx("RUNNING TEST: %s", #test); \
+ _tests_run++; \
+ _init(); \
+ if (!test()) { \
+ warnx("TEST FAILED: %s", #test); \
+ _tests_failed++; \
+ } else { \
+ warnx("TEST PASSED: %s", #test); \
+ _tests_passed++; \
+ } \
+ _cleanup(); \
+ } while (0)
+
+/// @brief Used to assert a value within a unit test.
+#define ut_assert(message, test) \
+ do { \
+ if (!(test)) { \
+ _print_assert(message, #test, __FILE__, __LINE__); \
+ return false; \
+ } else { \
+ _assertions++; \
+ } \
+ } while (0)
+
+/// @brief Used to compare two integer values within a unit test. If possible use ut_compare instead of ut_assert
+/// since it will give you better error reporting of the actual values being compared.
+#define ut_compare(message, v1, v2) \
+ do { \
+ int _v1 = v1; \
+ int _v2 = v2; \
+ if (_v1 != _v2) { \
+ _print_compare(message, #v1, _v1, #v2, _v2, __FILE__, __LINE__); \
+ return false; \
+ } else { \
+ _assertions++; \
+ } \
+ } while (0)
+
+ virtual void _init(void) { }; ///< Run before each unit test. Override to provide custom behavior.
+ virtual void _cleanup(void) { }; ///< Run after each unit test. Override to provide custom behavior.
+
+ void _print_assert(const char* msg, const char* test, const char* file, int line);
+ void _print_compare(const char* msg, const char *v1_text, int v1, const char *v2_text, int v2, const char* file, int line);
+ int _tests_run; ///< The number of individual unit tests run
+ int _tests_failed; ///< The number of unit tests which failed
+ int _tests_passed; ///< The number of unit tests which passed
+ int _assertions; ///< Total number of assertions tested by all unit tests
};
#endif /* UNIT_TEST_H_ */
diff --git a/src/systemcmds/esc_calib/module.mk b/src/systemcmds/esc_calib/module.mk
index 990c56768..ce87eb3e2 100644
--- a/src/systemcmds/esc_calib/module.mk
+++ b/src/systemcmds/esc_calib/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = esc_calib
SRCS = esc_calib.c
MODULE_STACKSIZE = 4096
+
+MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/motor_test/module.mk b/src/systemcmds/motor_test/module.mk
new file mode 100644
index 000000000..eb36d2ded
--- /dev/null
+++ b/src/systemcmds/motor_test/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Build the motor_test tool.
+#
+
+MODULE_COMMAND = motor_test
+SRCS = motor_test.c
+
+MODULE_STACKSIZE = 4096
diff --git a/src/systemcmds/motor_test/motor_test.c b/src/systemcmds/motor_test/motor_test.c
new file mode 100644
index 000000000..079f99674
--- /dev/null
+++ b/src/systemcmds/motor_test/motor_test.c
@@ -0,0 +1,128 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ * Author: Holger Steinhaus <hsteinhaus@gmx.de>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file motor_test.c
+ *
+ * Tool for drive testing
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
+#include <arch/board/board.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/test_motor.h>
+
+
+#include "systemlib/systemlib.h"
+#include "systemlib/err.h"
+
+
+__EXPORT int motor_test_main(int argc, char *argv[]);
+static void motor_test(unsigned channel, float value);
+static void usage(const char *reason);
+
+void motor_test(unsigned channel, float value)
+{
+ orb_advert_t _test_motor_pub;
+ struct test_motor_s _test_motor;
+
+ _test_motor.motor_number = channel;
+ _test_motor.timestamp = hrt_absolute_time();
+ _test_motor.value = value;
+
+ if (_test_motor_pub > 0) {
+ /* publish armed state */
+ orb_publish(ORB_ID(test_motor), _test_motor_pub, &_test_motor);
+ } else {
+ /* advertise and publish */
+ _test_motor_pub = orb_advertise(ORB_ID(test_motor), &_test_motor);
+ }
+}
+
+static void usage(const char *reason)
+{
+ if (reason != NULL)
+ warnx("%s", reason);
+
+ errx(1,
+ "usage:\n"
+ "motor_test\n"
+ " -m <channel> Motor to test (0..7)\n"
+ " -p <power> Power (0..100)\n");
+}
+
+int motor_test_main(int argc, char *argv[])
+{
+ unsigned long channel, lval;
+ float value;
+ int ch;
+
+ if (argc != 5) {
+ usage("please specify motor and power");
+ }
+
+ while ((ch = getopt(argc, argv, "m:p:")) != EOF) {
+ switch (ch) {
+
+ case 'm':
+ /* Read in channels supplied as one int and convert to mask: 1234 -> 0xF */
+ channel = strtoul(optarg, NULL, 0);
+ break;
+
+ case 'p':
+ /* Read in custom low value */
+ lval = strtoul(optarg, NULL, 0);
+
+ if (lval > 100)
+ usage("value invalid");
+
+ value = (float)lval/100.f;
+ break;
+ default:
+ usage(NULL);
+ }
+ }
+
+ motor_test(channel, value);
+
+ printf("motor %d set to %.2f\n", channel, value);
+
+ exit(0);
+}
diff --git a/src/systemcmds/mtd/24xxxx_mtd.c b/src/systemcmds/mtd/24xxxx_mtd.c
index 991363797..f85ed8e2d 100644
--- a/src/systemcmds/mtd/24xxxx_mtd.c
+++ b/src/systemcmds/mtd/24xxxx_mtd.c
@@ -80,11 +80,17 @@
/* As a minimum, the size of the AT24 part and its 7-bit I2C address are required. */
#ifndef CONFIG_AT24XX_SIZE
-# warning "Assuming AT24 size 64"
+/* XXX this is a well vetted special case,
+ * do not issue a warning any more
+ * # warning "Assuming AT24 size 64"
+ */
# define CONFIG_AT24XX_SIZE 64
#endif
#ifndef CONFIG_AT24XX_ADDR
-# warning "Assuming AT24 address of 0x50"
+/* XXX this is a well vetted special case,
+ * do not issue a warning any more
+ * # warning "Assuming AT24 address of 0x50"
+ */
# define CONFIG_AT24XX_ADDR 0x50
#endif
@@ -115,7 +121,10 @@
*/
#ifndef CONFIG_AT24XX_MTD_BLOCKSIZE
-# warning "Assuming driver block size is the same as the FLASH page size"
+/* XXX this is a well vetted special case,
+ * do not issue a warning any more
+ * # warning "Assuming driver block size is the same as the FLASH page size"
+ */
# define CONFIG_AT24XX_MTD_BLOCKSIZE AT24XX_PAGESIZE
#endif
diff --git a/src/systemcmds/mtd/module.mk b/src/systemcmds/mtd/module.mk
index b3fceceb5..1bc4f414e 100644
--- a/src/systemcmds/mtd/module.mk
+++ b/src/systemcmds/mtd/module.mk
@@ -4,3 +4,5 @@
MODULE_COMMAND = mtd
SRCS = mtd.c 24xxxx_mtd.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/nshterm/module.mk b/src/systemcmds/nshterm/module.mk
index e2fa0ff80..a12bc369e 100644
--- a/src/systemcmds/nshterm/module.mk
+++ b/src/systemcmds/nshterm/module.mk
@@ -38,4 +38,8 @@
MODULE_COMMAND = nshterm
SRCS = nshterm.c
-MODULE_STACKSIZE = 1400
+MODULE_STACKSIZE = 1600
+
+MAXOPTIMIZATION = -Os
+
+MODULE_PRIORITY = "SCHED_PRIORITY_DEFAULT-30"
diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c
index fca1798e6..f06c49552 100644
--- a/src/systemcmds/nshterm/nshterm.c
+++ b/src/systemcmds/nshterm/nshterm.c
@@ -87,7 +87,7 @@ nshterm_main(int argc, char *argv[])
/* Back up the original uart configuration to restore it after exit */
if ((termios_state = tcgetattr(fd, &uart_config)) < 0) {
- warnx("ERROR get termios config %s: %d\n", argv[1], termios_state);
+ warnx("ERR get config %s: %d\n", argv[1], termios_state);
close(fd);
return -1;
}
@@ -96,7 +96,7 @@ nshterm_main(int argc, char *argv[])
uart_config.c_oflag |= (ONLCR | OPOST/* | OCRNL*/);
if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
- warnx("ERROR setting baudrate / termios config for %s (tcsetattr)\n", argv[1]);
+ warnx("ERR set config %s\n", argv[1]);
close(fd);
return -1;
}
diff --git a/src/systemcmds/pwm/module.mk b/src/systemcmds/pwm/module.mk
index 13a24150f..a51ac8e0c 100644
--- a/src/systemcmds/pwm/module.mk
+++ b/src/systemcmds/pwm/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = pwm
SRCS = pwm.c
MODULE_STACKSIZE = 1800
+
+MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c
index c8d698b86..478c2a772 100644
--- a/src/systemcmds/pwm/pwm.c
+++ b/src/systemcmds/pwm/pwm.c
@@ -654,9 +654,28 @@ pwm_main(int argc, char *argv[])
}
}
exit(0);
+ } else if (!strcmp(argv[1], "terminatefail")) {
+
+ if (argc < 3) {
+ errx(1, "arg missing [on|off]");
+ } else {
+
+ if (!strcmp(argv[2], "on")) {
+ /* force failsafe */
+ ret = ioctl(fd, PWM_SERVO_SET_TERMINATION_FAILSAFE, 1);
+ } else {
+ /* force failsafe */
+ ret = ioctl(fd, PWM_SERVO_SET_TERMINATION_FAILSAFE, 0);
+ }
+
+ if (ret != OK) {
+ warnx("FAILED setting termination failsafe %s", argv[2]);
+ }
+ }
+ exit(0);
}
- usage("specify arm|disarm|rate|failsafe|disarmed|min|max|test|info|forcefail");
+ usage("specify arm|disarm|rate|failsafe\n\t\tdisarmed|min|max|test|info|forcefail|terminatefail");
return 0;
}
diff --git a/src/systemcmds/tests/test_sensors.c b/src/systemcmds/tests/test_sensors.c
index a4f17eebd..e005bf9c1 100644
--- a/src/systemcmds/tests/test_sensors.c
+++ b/src/systemcmds/tests/test_sensors.c
@@ -331,7 +331,7 @@ mag(int argc, char *argv[])
float len = sqrtf(buf.x * buf.x + buf.y * buf.y + buf.z * buf.z);
- if (len < 1.0f || len > 3.0f) {
+ if (len < 0.25f || len > 3.0f) {
warnx("MAG scale error!");
return ERROR;
}
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index e3f26924f..0f56704e6 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -110,7 +110,9 @@ const struct {
{"conv", test_conv, OPT_NOJIGTEST | OPT_NOALLTEST},
{"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST},
{"mtd", test_mtd, 0},
+#ifndef TESTS_MATHLIB_DISABLE
{"mathlib", test_mathlib, 0},
+#endif
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
{NULL, NULL, 0}
};
diff --git a/uavcan b/uavcan
-Subproject d84fc8a84678d93f97f93b240c81472797ca588
+Subproject 4de0338824972de4d3a8e29697ea1a2d95a926c